Skip to content

Commit e49c633

Browse files
authored
Merge pull request #87 from dojo-sim/jan/env_copyable
Make DojoEnvironment files copyable
2 parents 7b6c368 + 4a95730 commit e49c633

File tree

8 files changed

+24
-24
lines changed

8 files changed

+24
-24
lines changed

DojoEnvironments/src/environments/ant_ars.jl

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -50,12 +50,12 @@ function ant_ars(;
5050
return AntARS{T,horizon}(mechanism, storage)
5151
end
5252

53-
function state_map(::AntARS, state)
53+
function DojoEnvironments.state_map(::AntARS, state)
5454
state = state[1:28]
5555
return state
5656
end
5757

58-
function input_map(::AntARS, input::AbstractVector)
58+
function DojoEnvironments.input_map(::AntARS, input::AbstractVector)
5959
input = [zeros(6);input] # floating base not actuated
6060
return input
6161
end
@@ -69,7 +69,7 @@ function Dojo.step!(environment::AntARS, state, input=nothing; k=1, record=false
6969
return
7070
end
7171

72-
function get_state(environment::AntARS{T}) where T
72+
function DojoEnvironments.get_state(environment::AntARS{T}) where T
7373
contact_force = T[]
7474
for contact in environment.mechanism.contacts
7575
push!(contact_force, max(-1, min(1, contact.impulses[2][1])))

DojoEnvironments/src/environments/cartpole_dqn.jl

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -40,11 +40,11 @@ function cartpole_dqn(;
4040
return CartpoleDQN{T,horizon}(mechanism, storage)
4141
end
4242

43-
function state_map(::CartpoleDQN, state)
43+
function DojoEnvironments.state_map(::CartpoleDQN, state)
4444
return state
4545
end
4646

47-
function input_map(::CartpoleDQN, input::AbstractVector)
47+
function DojoEnvironments.input_map(::CartpoleDQN, input::AbstractVector)
4848
input = [input;0] # only the cart is actuated
4949
return input
5050
end
@@ -58,7 +58,7 @@ function Dojo.step!(environment::CartpoleDQN, state, input=nothing; k=1, record=
5858
return
5959
end
6060

61-
function get_state(environment::CartpoleDQN)
61+
function DojoEnvironments.get_state(environment::CartpoleDQN)
6262
state = get_minimal_state(environment.mechanism)
6363
return state
6464
end

DojoEnvironments/src/environments/pendulum.jl

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -38,11 +38,11 @@ function pendulum(;
3838
return Pendulum{T,horizon}(mechanism, storage)
3939
end
4040

41-
function state_map(::Pendulum, state)
41+
function DojoEnvironments.state_map(::Pendulum, state)
4242
return state
4343
end
4444

45-
function input_map(::Pendulum, input::AbstractVector)
45+
function DojoEnvironments.input_map(::Pendulum, input::AbstractVector)
4646
return input
4747
end
4848

@@ -55,7 +55,7 @@ function Dojo.step!(environment::Pendulum, state, input=nothing; k=1, record=fal
5555
return
5656
end
5757

58-
function get_state(environment::Pendulum)
58+
function DojoEnvironments.get_state(environment::Pendulum)
5959
state = get_minimal_state(environment.mechanism)
6060
return state
6161
end

DojoEnvironments/src/environments/quadrotor_waypoint.jl

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -44,12 +44,12 @@ function quadrotor_waypoint(;
4444
return QuadrotorWaypoint{T,horizon}(mechanism, storage, zeros(4))
4545
end
4646

47-
function state_map(::QuadrotorWaypoint, state)
47+
function DojoEnvironments.state_map(::QuadrotorWaypoint, state)
4848
state = [state;zeros(8)]
4949
return state
5050
end
5151

52-
function input_map(environment::QuadrotorWaypoint, input::AbstractVector)
52+
function DojoEnvironments.input_map(environment::QuadrotorWaypoint, input::AbstractVector)
5353
# Input is rotor rpm directly
5454
# Rotors are only visualized, dynamics are mapped here
5555
environment.rpms = input
@@ -94,7 +94,7 @@ function Dojo.simulate!(environment::QuadrotorWaypoint{T,N}, controller! = (envi
9494
simulate!(environment.mechanism, 1:N, environment.storage, controller_wrapper!; kwargs...)
9595
end
9696

97-
function get_state(environment::QuadrotorWaypoint)
97+
function DojoEnvironments.get_state(environment::QuadrotorWaypoint)
9898
state = get_minimal_state(environment.mechanism)[1:12]
9999
return state
100100
end

DojoEnvironments/src/environments/quadruped_sampling.jl

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -48,11 +48,11 @@ function quadruped_sampling(;
4848
return QuadrupedSampling{T,horizon}(mechanism, storage)
4949
end
5050

51-
function state_map(::QuadrupedSampling, state)
51+
function DojoEnvironments.state_map(::QuadrupedSampling, state)
5252
return state
5353
end
5454

55-
function input_map(::QuadrupedSampling, input::AbstractVector)
55+
function DojoEnvironments.input_map(::QuadrupedSampling, input::AbstractVector)
5656
input = [zeros(6);input] # trunk not actuated
5757
return input
5858
end
@@ -66,7 +66,7 @@ function Dojo.step!(environment::QuadrupedSampling, state, input=nothing; k=1, r
6666
return
6767
end
6868

69-
function get_state(environment::QuadrupedSampling)
69+
function DojoEnvironments.get_state(environment::QuadrupedSampling)
7070
state = get_minimal_state(environment.mechanism)
7171

7272
# x: floating base, FR (hip, thigh, calf), FL, RR, RL

DojoEnvironments/src/environments/quadruped_waypoint.jl

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -48,11 +48,11 @@ function quadruped_waypoint(;
4848
return QuadrupedWaypoint{T,horizon}(mechanism, storage)
4949
end
5050

51-
function state_map(::QuadrupedWaypoint, state)
51+
function DojoEnvironments.state_map(::QuadrupedWaypoint, state)
5252
return state
5353
end
5454

55-
function input_map(::QuadrupedWaypoint, input::AbstractVector)
55+
function DojoEnvironments.input_map(::QuadrupedWaypoint, input::AbstractVector)
5656
input = [zeros(6);input] # trunk not actuated
5757
return input
5858
end
@@ -66,7 +66,7 @@ function Dojo.step!(environment::QuadrupedWaypoint, state, input=nothing; k=1, r
6666
return
6767
end
6868

69-
function get_state(environment::QuadrupedWaypoint)
69+
function DojoEnvironments.get_state(environment::QuadrupedWaypoint)
7070
state = get_minimal_state(environment.mechanism)
7171

7272
# x: floating base, FR (hip, thigh, calf), FL, RR, RL

DojoEnvironments/src/environments/uuv_waypoint.jl

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -42,12 +42,12 @@ function uuv_waypoint(;
4242
return UUVWaypoint{T,horizon}(mechanism, storage, zeros(6))
4343
end
4444

45-
function state_map(::UUVWaypoint, state)
45+
function DojoEnvironments.state_map(::UUVWaypoint, state)
4646
state = [state;zeros(12)]
4747
return state
4848
end
4949

50-
function input_map(environment::UUVWaypoint, input::AbstractVector)
50+
function DojoEnvironments.input_map(environment::UUVWaypoint, input::AbstractVector)
5151
# Input is rotor rpm directly
5252
# Rotors are only visualized, dynamics are mapped here
5353
environment.rpms = input
@@ -98,7 +98,7 @@ function Dojo.simulate!(environment::UUVWaypoint{T,N}, controller! = (environmen
9898
simulate!(environment.mechanism, 1:N, environment.storage, controller_wrapper!; kwargs...)
9999
end
100100

101-
function get_state(environment::UUVWaypoint)
101+
function DojoEnvironments.get_state(environment::UUVWaypoint)
102102
state = get_minimal_state(environment.mechanism)[1:12]
103103
return state
104104
end

DojoEnvironments/src/environments/youbot_waypoint.jl

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ function youbot_waypoint(;
4444
return YoubotWaypoint{T,horizon}(mechanism, storage)
4545
end
4646

47-
function state_map(::YoubotWaypoint, state)
47+
function DojoEnvironments.state_map(::YoubotWaypoint, state)
4848
xy = state[1:2] # minimal coordinates are rotated for youbot
4949
vxy = state[4:5] # minimal coordinates are rotated for youbot
5050
xy_minimal = Dojo.vector_rotate([xy;0],Dojo.RotZ(-pi/2))[1:2]
@@ -57,7 +57,7 @@ function state_map(::YoubotWaypoint, state)
5757
return state
5858
end
5959

60-
function input_map(environment::YoubotWaypoint, input::AbstractVector)
60+
function DojoEnvironments.input_map(environment::YoubotWaypoint, input::AbstractVector)
6161
# Wheels are only for visualization and not actuated
6262
# so the wheel input must be mapped to the base
6363
l = 0.456
@@ -122,7 +122,7 @@ function Dojo.simulate!(environment::YoubotWaypoint{T,N}, controller! = (environ
122122
simulate!(environment.mechanism, 1:N, environment.storage, controller_wrapper!; kwargs...)
123123
end
124124

125-
function get_state(environment::YoubotWaypoint)
125+
function DojoEnvironments.get_state(environment::YoubotWaypoint)
126126
state = get_minimal_state(environment.mechanism)
127127
xy_minimal = state[1:2] # minimal coordinates are rotated for youbot
128128
vxy_minimal = state[4:5] # minimal coordinates are rotated for youbot

0 commit comments

Comments
 (0)