Skip to content

Commit beb2062

Browse files
committed
Merge pull request start-jsk#136 from YoheiKakiuchi/update_staro_gazebo
Update staro gazebo
2 parents cee6dc6 + 43684fc commit beb2062

File tree

6 files changed

+161
-1
lines changed

6 files changed

+161
-1
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,40 @@
1+
hrpsys_gazebo_configuration:
2+
publish_joint_state:
3+
topic: /joint_states
4+
step: 25
5+
## velocity feedback for joint control, use parameter gains/joint_name/p_v
6+
# use_velocity_feedback: true
7+
## synchronized hrpsys and gazebo
8+
# use_synchronized_command: false
9+
# name of robot (using for namespace)
10+
robotname: L_ROBOTIQ
11+
# joint_id (order) conversion from gazebo to hrpsys, joint_id_list[gazebo_id] := hrpsys_id
12+
joint_id_list: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11]
13+
# joints list used in gazebo, sizeof(joint_id_list) == sizeof(joints)
14+
joints:
15+
- L_finger_1_joint_1
16+
- L_finger_1_joint_2
17+
- L_finger_1_joint_3
18+
- L_finger_2_joint_1
19+
- L_finger_2_joint_2
20+
- L_finger_2_joint_3
21+
- L_finger_middle_joint_1
22+
- L_finger_middle_joint_2
23+
- L_finger_middle_joint_3
24+
- L_palm_finger_1_joint
25+
- L_palm_finger_2_joint
26+
- L_palm_finger_middle_joint
27+
## jointid:
28+
gains:
29+
L_finger_1_joint_1 : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
30+
L_finger_1_joint_2 : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
31+
L_finger_1_joint_3 : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
32+
L_finger_2_joint_1 : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
33+
L_finger_2_joint_2 : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
34+
L_finger_2_joint_3 : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
35+
L_finger_middle_joint_1 : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
36+
L_finger_middle_joint_2 : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
37+
L_finger_middle_joint_3 : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
38+
L_palm_finger_1_joint : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
39+
L_palm_finger_2_joint : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
40+
L_palm_finger_middle_joint : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,40 @@
1+
hrpsys_gazebo_configuration:
2+
publish_joint_state:
3+
topic: /joint_states
4+
step: 25
5+
## velocity feedback for joint control, use parameter gains/joint_name/p_v
6+
# use_velocity_feedback: true
7+
## synchronized hrpsys and gazebo
8+
# use_synchronized_command: false
9+
# name of robot (using for namespace)
10+
robotname: R_ROBOTIQ
11+
# joint_id (order) conversion from gazebo to hrpsys, joint_id_list[gazebo_id] := hrpsys_id
12+
joint_id_list: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11]
13+
# joints list used in gazebo, sizeof(joint_id_list) == sizeof(joints)
14+
joints:
15+
- R_finger_1_joint_1
16+
- R_finger_1_joint_2
17+
- R_finger_1_joint_3
18+
- R_finger_2_joint_1
19+
- R_finger_2_joint_2
20+
- R_finger_2_joint_3
21+
- R_finger_middle_joint_1
22+
- R_finger_middle_joint_2
23+
- R_finger_middle_joint_3
24+
- R_palm_finger_1_joint
25+
- R_palm_finger_2_joint
26+
- R_palm_finger_middle_joint
27+
## jointid:
28+
gains:
29+
R_finger_1_joint_1 : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
30+
R_finger_1_joint_2 : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
31+
R_finger_1_joint_3 : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
32+
R_finger_2_joint_1 : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
33+
R_finger_2_joint_2 : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
34+
R_finger_2_joint_3 : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
35+
R_finger_middle_joint_1 : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
36+
R_finger_middle_joint_2 : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
37+
R_finger_middle_joint_3 : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
38+
R_palm_finger_1_joint : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
39+
R_palm_finger_2_joint : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
40+
R_palm_finger_middle_joint : {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}

hrpsys_gazebo_tutorials/launch/gazebo_staro_no_controllers.launch

+14-1
Original file line numberDiff line numberDiff line change
@@ -3,12 +3,25 @@
33
<arg name="WORLD" default="$(find hrpsys_gazebo_general)/worlds/empty_add_cfm.world"/>
44
<arg name="PAUSED" default="false"/>
55
<arg name="SYNCHRONIZED" default="false" />
6+
<arg name="USE_HAND" default="true" />
7+
8+
<arg if="$(arg USE_HAND)"
9+
name="USE_MODEL" value="$(find hrpsys_gazebo_tutorials)/robot_models/STARO/STARO_with_hand.urdf.xacro" />
10+
<rosparam if="$(arg USE_HAND)"
11+
command="load"
12+
file="$(find hrpsys_gazebo_tutorials)/config/L_ROBOTIQ.yaml" ns="L_ROBOTIQ" />
13+
<rosparam if="$(arg USE_HAND)"
14+
command="load"
15+
file="$(find hrpsys_gazebo_tutorials)/config/R_ROBOTIQ.yaml" ns="R_ROBOTIQ" />
16+
17+
<arg unless="$(arg USE_HAND)"
18+
name="USE_MODEL" value="$(find hrpsys_gazebo_tutorials)/robot_models/STARO/STARO.urdf.xacro" />
619

720
<include file="$(find hrpsys_gazebo_general)/launch/gazebo_robot_no_controllers.launch">
821
<arg name="ROBOT_TYPE" value="STARO" />
922
<arg name="WORLD" value="$(arg WORLD)" />
1023
<arg name="HRPSYS_GAZEBO_CONFIG" default="$(find hrpsys_gazebo_tutorials)/config/STARO.yaml" />
11-
<arg name="ROBOT_MODEL" default="$(find hrpsys_gazebo_tutorials)/robot_models/STARO/STARO.urdf.xacro" />
24+
<arg name="ROBOT_MODEL" value="$(arg USE_MODEL)" />
1225

1326
<arg name="PAUSED" value="$(arg PAUSED)"/>
1427
<arg name="SYNCHRONIZED" value="$(arg SYNCHRONIZED)" />
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="ROBOTIQ" >
2+
<xacro:include filename="$(find robotiq_hand_description)/urdf/robotiq_hand.urdf.xacro" />
3+
4+
<xacro:macro name="robotiq_hand_for_gazebo" params="prefix parent *origin" >
5+
<xacro:robotiq_hand prefix="${prefix}" parent="${parent}" reflect="-1">
6+
<insert_block name="origin"/>
7+
</xacro:robotiq_hand>
8+
<!-- add IOB plugin -->
9+
<gazebo>
10+
<plugin filename="libIOBPlugin.so" name="hrpsys_gazebo_plugin" >
11+
<robotname>${prefix}ROBOTIQ</robotname>
12+
<controller>hrpsys_gazebo_configuration</controller>
13+
</plugin>
14+
</gazebo>
15+
</xacro:macro>
16+
</robot>

hrpsys_gazebo_tutorials/robot_models/STARO/STARO.urdf.xacro

+1
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="STARO" >
22
<xacro:include filename="$(find hrpsys_gazebo_tutorials)/robot_models/STARO/STARO.urdf" />
3+
<xacro:include filename="$(find multisense_sl_description)/urdf/multisense_sl_v4.urdf" />
34
<!-- add IOB plugin -->
45
<gazebo>
56
<plugin filename="libIOBPlugin.so" name="hrpsys_gazebo_plugin" >
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,50 @@
1+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="STARO" >
2+
<xacro:include filename="$(find hrpsys_gazebo_tutorials)/robot_models/STARO/STARO.urdf" />
3+
<xacro:include filename="$(find multisense_sl_description)/urdf/multisense_sl_v4.urdf" />
4+
<xacro:include filename="$(find hrpsys_gazebo_tutorials)/robot_models/ROBOTIQ/ROBOTIQ.urdf.xacro" />
5+
6+
<joint name="staro_to_multisense" type="fixed">
7+
<parent link="HEAD_LINK1" />
8+
<child link="head" />
9+
<origin xyz="0.075 0 0.15" rpy="0 0 0"/>
10+
</joint>
11+
12+
<xacro:robotiq_hand_for_gazebo prefix="L_" parent="LARM_LINK7">
13+
<origin xyz="-0.027224 0.149 -0.027224" rpy="-1.5707963268 -0.7853981634 3.1415926536" />
14+
</xacro:robotiq_hand_for_gazebo>
15+
<xacro:robotiq_hand_for_gazebo prefix="R_" parent="RARM_LINK7">
16+
<origin xyz="-0.027224 -0.149 -0.027224" rpy="-1.5707963268 -0.7853981634 3.1415926536" />
17+
</xacro:robotiq_hand_for_gazebo>
18+
19+
<!-- add IOB plugin -->
20+
<gazebo>
21+
<plugin filename="libIOBPlugin.so" name="hrpsys_gazebo_plugin" >
22+
<robotname>STARO</robotname>
23+
<controller>hrpsys_gazebo_configuration</controller>
24+
</plugin>
25+
</gazebo>
26+
<!-- add imu sensor -->
27+
<gazebo reference="CHEST_LINK1" >
28+
<sensor name="waist_imu" type="imu">
29+
<always_on>1</always_on>
30+
<update_rate>1000.0</update_rate>
31+
<imu>
32+
<noise>
33+
<type>gaussian</type>
34+
<rate>
35+
<mean>0.0</mean>
36+
<stddev>2e-4</stddev>
37+
<bias_mean>0.0000075</bias_mean>
38+
<bias_stddev>0.0000008</bias_stddev>
39+
</rate>
40+
<accel>
41+
<mean>0.0</mean>
42+
<stddev>1.7e-2</stddev>
43+
<bias_mean>0.1</bias_mean>
44+
<bias_stddev>0.001</bias_stddev>
45+
</accel>
46+
</noise>
47+
</imu>
48+
</sensor>
49+
</gazebo>
50+
</robot>

0 commit comments

Comments
 (0)