-
Notifications
You must be signed in to change notification settings - Fork 61
/
HRP2JSKNTS.urdf.xacro
149 lines (149 loc) · 5.09 KB
/
HRP2JSKNTS.urdf.xacro
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="HRP2JSKNTS" >
<xacro:include filename="$(find hrpsys_ros_bridge_tutorials)/models/HRP2JSKNTS_WH_SENSORS.urdf" />
<!-- add IOB plugin -->
<gazebo>
<plugin filename="libIOBPlugin.so" name="hrpsys_gazebo_plugin">
<robotname>HRP2JSKNTS</robotname>
<controller>hrpsys_gazebo_configuration</controller>
</plugin>
</gazebo>
<!-- add imu sensor -->
<gazebo reference="CHEST_LINK1">
<sensor name="waist_imu" type="imu">
<always_on>1</always_on>
<update_rate>1000.0</update_rate>
<imu>
<noise>
<type>gaussian</type>
<rate>
<mean>0.0</mean>
<stddev>2e-4</stddev>
<bias_mean>0.0000075</bias_mean>
<bias_stddev>0.0000008</bias_stddev>
</rate>
<accel>
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
<bias_mean>0.1</bias_mean>
<bias_stddev>0.001</bias_stddev>
</accel>
</noise>
</imu>
<pose>-0.13 0 0.118 0 0 0</pose>
</sensor>
</gazebo>
<!-- add force sensor -->
<gazebo reference="LLEG_JOINT5">
<provideFeedback>1</provideFeedback>
</gazebo>
<gazebo reference="RLEG_JOINT5">
<provideFeedback>1</provideFeedback>
</gazebo>
<gazebo reference="LARM_JOINT6">
<provideFeedback>1</provideFeedback>
</gazebo>
<gazebo reference="RARM_JOINT6">
<provideFeedback>1</provideFeedback>
</gazebo>
<!-- add Kinect plugin, link and joint without visual and collision -->
<joint name="xtion_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.1120 0.0 0.1255"/>
<parent link="HEAD_LINK1"/>
<child link="xtion_link"/>
</joint>
<link name="xtion_link">
<inertial>
<mass value="0.200"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4"/>
</inertial>
</link>
<joint name="xtion_depth_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.0 0.049 0.0"/>
<parent link="xtion_link"/>
<child link="xtion_depth_frame"/>
</joint>
<link name="xtion_depth_frame"/>
<joint name="xtion_depth_optical_joint" type="fixed">
<origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/>
<parent link="xtion_depth_frame"/>
<child link="xtion_depth_optical_frame"/>
</joint>
<link name="xtion_depth_optical_frame"/>
<joint name="xtion_rgb_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.0 0.022 0.0"/>
<parent link="xtion_link"/>
<child link="xtion_rgb_frame"/>
</joint>
<link name="xtion_rgb_frame"/>
<joint name="xtion_rgb_optical_joint" type="fixed">
<origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/>
<parent link="xtion_rgb_frame"/>
<child link="xtion_rgb_optical_frame"/>
</joint>
<link name="xtion_rgb_optical_frame"/>
<gazebo reference="xtion_depth_frame">
<sensor name="xtion" type="depth">
<update_rate>20</update_rate>
<camera>
<horizontal_fov>1.09606677025</horizontal_fov>
<image>
<format>R8G8B8</format>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.5</near>
<far>9</far>
</clip>
</camera>
<plugin filename="libgazebo_ros_openni_kinect.so" name="xtion_camera_controller">
<alwaysOn>true</alwaysOn>
<updateRate>20</updateRate>
<imageTopicName>xtion/rgb/image_raw</imageTopicName>
<cameraInfoTopicName>xtion/rgb/camera_info</cameraInfoTopicName>
<depthImageTopicName>xtion/depth/image_raw</depthImageTopicName>
<depthImageCameraInfoTopicName>xtion/depth/camera_info</depthImageCameraInfoTopicName>
<pointCloudTopicName>xtion/depth/points</pointCloudTopicName>
<frameName>xtion_depth_optical_frame</frameName>
<distortion_k1>0.0</distortion_k1>
<distortion_k2>0.0</distortion_k2>
<distortion_k3>0.0</distortion_k3>
<distortion_t1>0.0</distortion_t1>
<distortion_t2>0.0</distortion_t2>
</plugin>
</sensor>
</gazebo>
<!-- added end-effector virtual joints and links -->
<link name="RARM_EEF_PARENT" />
<link name="RARM_EEF_CHILD" />
<joint name="rarm_eef_1" type="fixed">
<origin rpy="0 1.5708 0" xyz="-0.0042 0.0392 -0.1245"/>
<parent link="RARM_LINK6"/>
<child link="RARM_EEF_PARENT"/>
</joint>
<joint name="rarm_eef_2" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="RARM_EEF_PARENT"/>
<child link="RARM_EEF_CHILD"/>
</joint>
<link name="LARM_EEF_PARENT" />
<link name="LARM_EEF_CHILD" />
<joint name="larm_eef_1" type="fixed">
<origin rpy="0 1.5708 0" xyz="-0.0042 -0.0392 -0.1245"/>
<parent link="LARM_LINK6"/>
<child link="LARM_EEF_PARENT"/>
</joint>
<joint name="larm_eef_2" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="LARM_EEF_PARENT"/>
<child link="LARM_EEF_CHILD"/>
</joint>
<!-- add SetVelPlugin -->
<gazebo>
<plugin filename="libSetVelPlugin.so" name="set_vel_plugin" >
<objname>ROBOT</objname>
<linkname>BODY</linkname>
</plugin>
</gazebo>
</robot>