Skip to content

Commit 18d6824

Browse files
kdh0429whikwon
authored andcommitted
Refactoring demo collector (#56)
1 parent 055d976 commit 18d6824

19 files changed

+972
-20
lines changed

Diff for: launch/open_manipulator_demo.launch

+42
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,42 @@
1+
<launch>
2+
<!-- These are the arguments you can pass this launch file, for example paused:=true -->
3+
<arg name="use_robot_name" default="open_manipulator"
4+
doc="Must match the robotNamespace tag in the gazebo description file"/>
5+
<arg name="paused" default="false"/>
6+
<arg name="use_sim_time" default="true"/>
7+
<arg name="gui" default="true"/>
8+
<arg name="headless" default="false"/>
9+
<arg name="debug" default="false"/>
10+
<arg name="use_platform" default="false"/>
11+
12+
<rosparam file="$(find open_manipulator_gazebo)/config/gazebo_controller.yaml" command="load" />
13+
14+
<!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
15+
<include file="$(find gazebo_ros)/launch/empty_world.launch">
16+
<arg name="world_name" value="$(find open_manipulator_gazebo)/worlds/empty.world"/>
17+
<arg name="debug" value="$(arg debug)" />
18+
<arg name="gui" value="$(arg gui)" />
19+
<arg name="paused" value="$(arg paused)"/>
20+
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
21+
<arg name="headless" value="$(arg headless)"/>
22+
</include>
23+
24+
<!-- Load the URDF into the ROS Parameter Server -->
25+
<param name="robot_description"
26+
command="$(find xacro)/xacro --inorder '$(find open_manipulator_description)/urdf/open_manipulator.urdf.xacro'"/>
27+
28+
<!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
29+
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
30+
args="-urdf -model open_manipulator -z 0.0 -param robot_description"/>
31+
32+
<!-- ros_control robotis manipulator launch file -->
33+
<include file="$(find open_manipulator_gazebo)/launch/open_manipulator_controller.launch">
34+
<arg name="use_robot_name" value="$(arg use_robot_name)"/>
35+
</include>
36+
37+
<!-- Run demo collector node -->
38+
<node name="open_manipulator_demo_collector" pkg="kair_algorithms" type="run_open_manipulator_demo.py" respawn="false" output="screen">
39+
<param name="use_platform" value="$(arg use_platform)" />
40+
</node>
41+
42+
</launch>

Diff for: scripts/algorithms/common/abstract/agent.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,7 @@ def save_params(self, params, n_episode):
8080
path = os.path.join("./save/" + save_name + "_ep_" + str(n_episode) + ".pt")
8181
torch.save(params, path)
8282

83-
print ("[INFO] Saved the model and optimizer to", path)
83+
print("[INFO] Saved the model and optimizer to", path)
8484

8585
@abstractmethod
8686
def write_log(self, *args):
@@ -109,7 +109,7 @@ def test(self):
109109
score += reward
110110
step += 1
111111

112-
print (
112+
print(
113113
"[INFO] episode %d\tstep: %d\ttotal score: %d"
114114
% (i_episode, step, score)
115115
)

Diff for: scripts/algorithms/fd/sac_agent.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -201,7 +201,7 @@ def update_model(self, experiences):
201201
def pretrain(self):
202202
"""Pretraining steps."""
203203
pretrain_loss = list()
204-
print ("[INFO] Pre-Train %d steps." % self.hyper_params["PRETRAIN_STEP"])
204+
print("[INFO] Pre-Train %d steps." % self.hyper_params["PRETRAIN_STEP"])
205205
for i_step in range(1, self.hyper_params["PRETRAIN_STEP"] + 1):
206206
loss = self.update_model()
207207
pretrain_loss.append(loss) # for logging

Diff for: scripts/algorithms/fd/td3_agent.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -180,7 +180,7 @@ def update_model(self, experiences):
180180
def pretrain(self):
181181
"""Pretraining steps."""
182182
pretrain_loss = list()
183-
print ("[INFO] Pre-Train %d steps." % self.hyper_params["PRETRAIN_STEP"])
183+
print("[INFO] Pre-Train %d steps." % self.hyper_params["PRETRAIN_STEP"])
184184
for i_step in range(1, self.hyper_params["PRETRAIN_STEP"] + 1):
185185
loss = self.update_model()
186186
pretrain_loss.append(loss) # for logging

Diff for: scripts/algorithms/sac/agent.py

+3-3
Original file line numberDiff line numberDiff line change
@@ -264,7 +264,7 @@ def update_model(self, experiences):
264264
def load_params(self, path):
265265
"""Load model and optimizer parameters."""
266266
if not os.path.exists(path):
267-
print ("[ERROR] the input path does not exist. ->", path)
267+
print("[ERROR] the input path does not exist. ->", path)
268268
return
269269

270270
params = torch.load(path)
@@ -281,7 +281,7 @@ def load_params(self, path):
281281
if self.hyper_params["AUTO_ENTROPY_TUNING"]:
282282
self.alpha_optimizer.load_state_dict(params["alpha_optim"])
283283

284-
print ("[INFO] loaded the model and optimizer from", path)
284+
print("[INFO] loaded the model and optimizer from", path)
285285

286286
def save_params(self, n_episode):
287287
"""Save model and optimizer parameters."""
@@ -306,7 +306,7 @@ def write_log(self, i, loss, score=0.0, delayed_update=1):
306306
"""Write log about loss and score"""
307307
total_loss = loss.sum()
308308

309-
print (
309+
print(
310310
"[INFO] episode %d, episode_step %d, total step %d, total score: %d\n"
311311
"total loss: %.3f actor_loss: %.3f qf_1_loss: %.3f qf_2_loss: %.3f "
312312
"vf_loss: %.3f alpha_loss: %.3f\n"

Diff for: scripts/algorithms/td3/agent.py

+3-3
Original file line numberDiff line numberDiff line change
@@ -177,7 +177,7 @@ def update_model(self, experiences):
177177
def load_params(self, path):
178178
"""Load model and optimizer parameters."""
179179
if not os.path.exists(path):
180-
print ("[ERROR] the input path does not exist. ->", path)
180+
print("[ERROR] the input path does not exist. ->", path)
181181
return
182182

183183
params = torch.load(path)
@@ -189,7 +189,7 @@ def load_params(self, path):
189189
self.critic2_target.load_state_dict(params["critic2_target_state_dict"])
190190
self.actor_optim.load_state_dict(params["actor_optim_state_dict"])
191191
self.critic_optim.load_state_dict(params["critic_optim_state_dict"])
192-
print ("[INFO] loaded the model and optimizer from", path)
192+
print("[INFO] loaded the model and optimizer from", path)
193193

194194
def save_params(self, n_episode):
195195
"""Save model and optimizer parameters."""
@@ -210,7 +210,7 @@ def write_log(self, i, loss, score):
210210
"""Write log about loss and score"""
211211
total_loss = loss.sum()
212212

213-
print (
213+
print(
214214
"[INFO] total_steps: %d episode: %d total score: %d, total loss: %f\n"
215215
"actor_loss: %.3f critic1_loss: %.3f critic2_loss: %.3f\n"
216216
% (self.total_steps, i, score, total_loss, loss[0], loss[1], loss[2])

Diff for: scripts/config/demo/__init__.py

Whitespace-only changes.

Diff for: scripts/config/demo/open_manipulator/__init__.py

Whitespace-only changes.

Diff for: scripts/config/demo/open_manipulator/reacher_v0.py

+12
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
config = {
2+
"USE_PLATFORM": False,
3+
"DAMPING": 0.01,
4+
"JOINT_VEL_LIMIT": 4,
5+
"NUM_TARGET_DEMO": 10,
6+
"HZ": 100,
7+
"SAVE_PATH": "../demo_collection.json",
8+
}
9+
10+
11+
def get():
12+
return config

Diff for: scripts/config/dynamixel/config.py

+31
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,31 @@
1+
config = {
2+
"DXL_RESOLUTION": 0.088, # Position resolution of XM430-W210 in degree
3+
"DXL_VELOCITY_RESOLUTION": 0.229, # Velocity resolition of XM430-W210 in rpm
4+
"DXL_TO_CURRENT": 2.69, # From dynamixel return value to current
5+
# Control table address
6+
"ADDR_TORQUE_ENABLE": 64, # To set torque on/off
7+
"ADDR_PRESENT_POSITION": 132, # To read position
8+
"ADDR_PRESENT_VELOCITY": 128, # To read velocity
9+
"ADDR_PRESENT_CURRENT": 126, # To read current
10+
"ADDR_OP_MODE": 11, # To set operation mode (position/velocity/multi_turn mode)
11+
"ADDR_GOAL_POSITION": 116, # To write position
12+
# Data Byte Length
13+
"LEN_GOAL_POSITION": 4, # In byte
14+
"LEN_PRESENT_POSITION": 4, # In byte
15+
"LEN_PRESENT_VELOCITY": 4, # In byte
16+
"LEN_PRESENT_CURRENT": 2, # In byte
17+
"CW_LIMIT": 4095, # Clockwise limit
18+
"CCW_LIMIT": 0, # Counter clock wise limit
19+
"DXL_POS_OFFSET": 2048, # Initial position
20+
# Protocol version
21+
"PROTOCOL_VERSION": 2.0,
22+
# Default setting
23+
"DXL1_ID": 11, # Joint 1 ID
24+
"DXL2_ID": 12, # Joint 2 ID
25+
"DXL3_ID": 13, # Joint 3 ID
26+
"DXL4_ID": 14, # Joint 4 ID
27+
"BAUDRATE": 1000000,
28+
"DEVICENAME": "/dev/ttyUSB0", # Connected USB port
29+
"TORQUE_ENABLE": 1, # Torque on
30+
"TORQUE_DISABLE": 0, # Torque off
31+
}

Diff for: scripts/demo/__init__.py

Whitespace-only changes.

Diff for: scripts/demo/open_manipulator/__init__.py

Whitespace-only changes.

0 commit comments

Comments
 (0)