Skip to content

Commit 0723716

Browse files
Add simulation argument in launch file
- control period is different in simulation (gazebo: 0.01) and on the real robot (0.002).
1 parent f6e10c0 commit 0723716

File tree

4 files changed

+41
-3
lines changed

4 files changed

+41
-3
lines changed

CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -73,12 +73,14 @@ INSTALL(FILES package.xml DESTINATION share/${PROJECT_NAME})
7373
INSTALL(FILES
7474
launch/controller.launch
7575
launch/sot_params.launch
76+
launch/sot_params.launch
7677
DESTINATION share/${PROJECT_NAME}/launch)
7778

7879
# Install configuration files
7980
INSTALL(FILES
8081
config/controller.yaml
8182
config/sot_params.yaml
83+
config/sot_params_simu.yaml
8284
DESTINATION share/${PROJECT_NAME}/config)
8385

8486
# Install default URDF file

config/sot_params.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,5 +28,5 @@ sot_controller:
2828
ros_control_mode: POSITION
2929
sot_control_mode: VELOCITY
3030

31-
dt: 0.01
31+
dt: 0.002
3232
jitter: 0.004

config/sot_params_simu.yaml

Lines changed: 32 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,32 @@
1+
sot_controller:
2+
libname: libsot-universal-robot-controller.so
3+
map_rc_to_sot_device:
4+
motor-angles: motor-angles
5+
joint-angles: joint-angles
6+
velocities: velocities
7+
forces: forces
8+
torques: torques
9+
control: control
10+
11+
control_mode:
12+
shoulder_pan_joint:
13+
ros_control_mode: POSITION
14+
sot_control_mode: VELOCITY
15+
shoulder_lift_joint:
16+
ros_control_mode: POSITION
17+
sot_control_mode: VELOCITY
18+
elbow_joint:
19+
ros_control_mode: POSITION
20+
sot_control_mode: VELOCITY
21+
wrist_1_joint:
22+
ros_control_mode: POSITION
23+
sot_control_mode: VELOCITY
24+
wrist_2_joint:
25+
ros_control_mode: POSITION
26+
sot_control_mode: VELOCITY
27+
wrist_3_joint:
28+
ros_control_mode: POSITION
29+
sot_control_mode: VELOCITY
30+
31+
dt: 0.01
32+
jitter: 0.004

launch/controller.launch

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,14 @@
11
<launch>
2+
<arg name="simulation" default="false"/>
23
<include file="$(find sot_universal_robot)/launch/sot_params.launch"/>
34

45
<!-- Sot Controller configuration -->
5-
<rosparam command="load"
6+
<rosparam command="load" unless="$(arg simulation)"
67
file="$(find sot_universal_robot)/config/sot_params.yaml"/>
7-
<rosparam command="load" file="$(find sot_universal_robot)/config/controller.yaml" />
8+
<rosparam command="load" if="$(arg simulation)"
9+
file="$(find sot_universal_robot)/config/sot_params_simu.yaml"/>
10+
<rosparam command="load"
11+
file="$(find sot_universal_robot)/config/controller.yaml" />
812

913
<!-- Spawn sot controller -->
1014
<node name="sot_controller_spawner"

0 commit comments

Comments
 (0)