racecar.urdf.xacro 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516
  1. <?xml version="1.0"?>
  2. <!-- racecar.urdf.xacro
  3. This file defines a model of a Traxxas(R) E-Maxx(R) #3905 RC (Radio Controlled)
  4. truck.
  5. Lengths are measured in meters, angles are measured in radians, and masses are
  6. measured in kilograms. All of these values are approximations(近似值).
  7. To work with Gazebo, each link must have an inertial element, even if
  8. the link only serves to connect two joints. To be visible in Gazebo, a link
  9. must have a collision element. Furthermore, the link must have a Gazebo
  10. material.
  11. Traxxas(R), E-Maxx(R), and Titan(R) are registered trademarks of Traxxas
  12. Management, LLC. em_3905.urdf.xacro was independently created by Wunderkammer
  13. Laboratory, and neither em_3905.urdf.xacro nor Wunderkammer Laboratory is
  14. affiliated with, sponsored by, approved by, or endorsed by Traxxas Management,
  15. LLC. Mabuchi Motor(R) is a registered trademark of Mabuchi Motor Co., Ltd.
  16. Corporation Japan. All other trademarks and service marks are the property of
  17. their respective owners.
  18. Copyright (c) 2011-2014 Wunderkammer Laboratory
  19. Licensed under the Apache License, Version 2.0 (the "License");
  20. you may not use this file except in compliance with the License.
  21. You may obtain a copy of the License at
  22. http://www.apache.org/licenses/LICENSE-2.0
  23. Unless required by applicable law or agreed to in writing, software
  24. distributed under the License is distributed on an "AS IS" BASIS,
  25. WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  26. See the License for the specific language governing permissions and
  27. limitations under the License.
  28. -->
  29. <robot name="racecar" xmlns:xacro="http://www.ros.org/wiki/xacro">
  30. <!-- include sensors -->
  31. <xacro:include filename="$(find racecar_description)/urdf/sensors/lidar.xacro" />
  32. <xacro:include filename="$(find racecar_description)/urdf/sensors/imu.xacro" />
  33. <xacro:include filename="$(find racecar_description)/urdf/sensors/camera.xacro" />
  34. <!-- Degree-to-radian conversions 度数到弧度的转换 -->
  35. <xacro:property name="degrees_45" value="0.785398163"/>
  36. <xacro:property name="degrees_90" value="1.57079633"/>
  37. <!-- chassis_length is measured along the x axis, chassis_width
  38. along the y axis, and chassis_height along the z axis. -->
  39. <!-- 底盘长度沿 x 轴测量,底盘宽度沿 y 轴测量,底盘高度沿 z 轴测量。 -->
  40. <xacro:property name="chassis_length" value="0.258"/> <!-- 底盘长 -->
  41. <xacro:property name="chassis_width" value="0.168"/> <!-- 底盘宽 -->
  42. <xacro:property name="chassis_height" value="0.01"/> <!-- 底盘高 -->
  43. <xacro:property name="chassis_mass" value="2.788"/> <!-- 底盘重量 -->
  44. <!-- battery_dist is the distance between the inner edges of the
  45. batteries. battery_comp_depth is the battery compartment depth.
  46. battery_length is measured along the x axis, battery_width
  47. along the y axis, and battery_height along the z axis. -->
  48. <!-- Battery_dist 是电池内边缘之间的距离。
  49. Battery_comp_depth 是电池盒深度。
  50. Battery_length 沿 x 轴测量,
  51. Battery_width 沿 y 轴,battery_height 沿 z 轴。 -->
  52. <xacro:property name="battery_x_offset" value="0.055"/>
  53. <xacro:property name="battery_dist" value="0.065"/>
  54. <xacro:property name="battery_comp_depth" value="0.02"/>
  55. <xacro:property name="battery_comp_angle" value="0.34906585"/>
  56. <xacro:property name="battery_length" value="0.16"/>
  57. <xacro:property name="battery_width" value="0.047"/>
  58. <xacro:property name="battery_height" value="0.024"/>
  59. <xacro:property name="battery_mass" value="0.5025"/>
  60. <!-- hub_dia and tire_dia are the diameters of the hub and tire,
  61. respectively. hex_hub_depth is the distance that the hex hub is
  62. inset from the outer edge of the tire. It is set so that each wheel
  63. is a "zero offset" wheel. hex_hub_depth = tire_width / 2 -
  64. axle_length. -->
  65. <!-- hub_dia和tire_dia分别是轮毂和轮胎的直径。
  66. hex_hub_depth 是六角轮毂从轮胎外边缘插入的距离。
  67. 它被设置为使得每个轮子都是“零偏移”轮子。 hex_hub_深度 = 轮胎宽度 / 2 - 轴长度。 -->
  68. <xacro:property name="hub_dia" value="0.09652"/>
  69. <xacro:property name="tire_dia" value="0.14605"/>
  70. <xacro:property name="tire_width" value="0.0889"/>
  71. <xacro:property name="hex_hub_depth" value="0.01445"/>
  72. <xacro:property name="wheel_mass" value="0.29"/>
  73. <!-- hex_hub_dist is the distance between left and right hex hubs when
  74. the shock absorbers are fully extended. axle_length is the distance
  75. from a U joint to the corresponding hex hub. wheel_travel is the
  76. vertical wheel travel. -->
  77. <!-- hex_hub_dist 是减震器完全伸展时左右六角轮毂之间的距离。 axis_length 是从 U 形接头到相应六角轮毂的距离。 wheel_travel 是垂直轮行程。 -->
  78. <xacro:property name="wheelbase" value="0.335"/>
  79. <xacro:property name="hex_hub_dist" value="0.365"/>
  80. <xacro:property name="axle_length" value="0.03"/>
  81. <xacro:property name="wheel_travel" value="0.084"/>
  82. <xacro:property name="shock_z_offset" value="0.0655"/>
  83. <!-- shock_eff_limit is 2 * ((shock_stroke / 2) * shock_spring_constant) N.
  84. shock_stroke is 0.028575 meters. shock_spring_constant, an approximation
  85. of a Traxxas Ultra Shock shock absorber spring's constant, is
  86. 437.817 N/m. -->
  87. <xacro:property name="shock_eff_limit" value="12.5106"/>
  88. <xacro:property name="shock_vel_limit" value="1000"/>
  89. <!-- The specifications for a Titan(R) 550 motor could not be found, so the
  90. stall torque of a Mabuchi Motor(R) RS-550VC-7525 motor was used instead.
  91. num_spur_gear_teeth = 68
  92. num_pinion_gear_teeth = 19
  93. final_gear_ratio = (num_spur_gear_teeth / num_pinion_gear_teeth) *
  94. 5.22 = 18.68
  95. stall_torque = 0.549 N m
  96. axle_eff_limit = ((2 * stall_torque) * final_gear_ratio) / 4 =
  97. 5.12766 N m
  98. max_speed = 40 mph (30+ mph) = 17.8816 m/s
  99. axle_vel_limit = (2 * pi) * (max_speed / (pi * tire_dia)) =
  100. 244.8696 rad/s -->
  101. <xacro:property name="axle_eff_limit" value="5.12766"/>
  102. <xacro:property name="axle_vel_limit" value="244.8696"/>
  103. <!-- These constants are used to simulate a Traxxas 2056 servo operated at
  104. 6 V. servo_stall_torque is measured in N m. servo_no_load_speed is
  105. measured in rad/s. -->
  106. <xacro:property name="servo_stall_torque" value="0.5649"/>
  107. <xacro:property name="servo_no_load_speed" value="4.553"/>
  108. <xacro:property name="layer_mass" value="0.0" />
  109. <xacro:property name="layer_x" value="0.40"/>
  110. <xacro:property name="layer_y" value="0.18"/>
  111. <xacro:property name="layer_z" value="0.01"/>
  112. <xacro:property name="layer_height" value="0.08"/>
  113. <material name="battery_mat"> <!-- 电池颜色 -->
  114. <color rgba="0 0 1 1"/>
  115. </material>
  116. <material name="chassis_mat"> <!-- 地盘颜色 -->
  117. <color rgba="0.5 0.5 0.5 1"/>
  118. </material>
  119. <material name="tire_mat"> <!-- 轮胎颜色 -->
  120. <color rgba="0 0 0 1"/>
  121. </material>
  122. <material name="yellow"> <!-- 黄色, 这个是小车上层底盘的颜色! -->
  123. <!-- 黄色 -->
  124. <color rgba="1 0.4 0 1"/>
  125. <!-- 黑色 -->
  126. <!-- <color rgba="0 0 0 1"/> -->
  127. </material>
  128. <!-- Null inertial element. This is needed to make the model work with
  129. Gazebo. -->
  130. <xacro:macro name="null_inertial">
  131. <inertial>
  132. <mass value="0.001"/>
  133. <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
  134. </inertial>
  135. </xacro:macro>
  136. <!-- Inertia of a solid cuboid. Width is measured along the x axis, depth
  137. along the y axis, and height along the z axis. -->
  138. <xacro:macro name="solid_cuboid_inertial"
  139. params="width depth height mass *origin">
  140. <inertial>
  141. <xacro:insert_block name="origin"/>
  142. <mass value="${mass}"/>
  143. <inertia ixx="${mass * (depth * depth + height * height) / 12}"
  144. ixy="0" ixz="0"
  145. iyy="${mass * (width * width + height * height) / 12}"
  146. iyz="0"
  147. izz="${mass * (width * width + depth * depth) / 12}"/>
  148. </inertial>
  149. </xacro:macro>
  150. <!-- Inertia of a thick-walled cylindrical tube with open ends. Height is
  151. measured along the z axis, which is the tube's axis. inner_rad and
  152. outer_rad are the tube's inner and outer radii, respectively. -->
  153. <xacro:macro name="thick_walled_tube_inertial"
  154. params="inner_rad outer_rad height mass">
  155. <inertial>
  156. <mass value="${mass}"/>
  157. <inertia ixx="${(1 / 12) * mass * (3 * (inner_rad * inner_rad +
  158. outer_rad * outer_rad) + height * height)}"
  159. ixy="0" ixz="0"
  160. iyy="${(1 / 12) * mass * (3 * (inner_rad * inner_rad +
  161. outer_rad * outer_rad) + height * height)}"
  162. iyz="0"
  163. izz="${mass * (inner_rad * inner_rad +
  164. outer_rad * outer_rad) / 2}"/>
  165. </inertial>
  166. </xacro:macro>
  167. <!-- Battery -->
  168. <xacro:macro name="battery" params="prefix reflect">
  169. <joint name="chassis_to_${prefix}_battery" type="fixed">
  170. <parent link="chassis"/>
  171. <child link="${prefix}_battery_offset"/>
  172. <origin xyz="${battery_x_offset - battery_length / 2}
  173. ${reflect * battery_dist / 2}
  174. 0"
  175. rpy="${reflect * battery_comp_angle} 0 0"/>
  176. </joint>
  177. <link name="${prefix}_battery_offset">
  178. <xacro:null_inertial/>
  179. </link>
  180. <joint name="offset_to_${prefix}_battery" type="fixed">
  181. <parent link="${prefix}_battery_offset"/>
  182. <child link="${prefix}_battery"/>
  183. <origin xyz="0
  184. ${reflect * battery_width / 2}
  185. ${(battery_height / 2) - battery_comp_depth}"/>
  186. </joint>
  187. <link name="${prefix}_battery">
  188. <visual>
  189. <geometry>
  190. <box size="${battery_length} ${battery_width} ${battery_height}"/>
  191. </geometry>
  192. <material name="battery_mat"/>
  193. </visual>
  194. <collision>
  195. <geometry>
  196. <box size="${battery_length} ${battery_width} ${battery_height}"/>
  197. </geometry>
  198. </collision>
  199. <xacro:solid_cuboid_inertial
  200. width="${battery_length}" depth="${battery_width}"
  201. height="${battery_height}" mass="${battery_mass}">
  202. <origin/>
  203. </xacro:solid_cuboid_inertial>
  204. </link>
  205. <gazebo reference="${prefix}_battery">
  206. <material>Gazebo/Blue</material>
  207. </gazebo>
  208. </xacro:macro>
  209. <!-- Shock absorber -->
  210. <xacro:macro name="shock"
  211. params="lr_prefix fr_prefix lr_reflect fr_reflect child">
  212. <joint name="${lr_prefix}_${fr_prefix}_shock" type="prismatic">
  213. <parent link="chassis"/>
  214. <child link="${child}"/>
  215. <origin xyz="${fr_reflect * wheelbase / 2}
  216. ${lr_reflect * ((hex_hub_dist / 2) - axle_length)}
  217. ${(wheel_travel / 2) - shock_z_offset}"/>
  218. <axis xyz="0 0 -1"/>
  219. <limit lower="${-wheel_travel / 2}" upper="${wheel_travel / 2}"
  220. effort="${shock_eff_limit}" velocity="${shock_vel_limit}"/>
  221. </joint>
  222. <transmission name="${lr_prefix}_${fr_prefix}_shock_trans">
  223. <type>transmission_interface/SimpleTransmission</type>
  224. <joint name="${lr_prefix}_${fr_prefix}_shock">
  225. <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
  226. </joint>
  227. <actuator name="${lr_prefix}_${fr_prefix}_shock_act">
  228. <!-- This hardwareInterface element exists for compatibility
  229. with ROS Hydro. -->
  230. <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
  231. <mechanicalReduction>1</mechanicalReduction>
  232. </actuator>
  233. </transmission>
  234. </xacro:macro>
  235. <!-- The "wheel" macro defines an axle carrier, axle, and wheel. -->
  236. <xacro:macro name="wheel" params="lr_prefix fr_prefix lr_reflect">
  237. <link name="${lr_prefix}_${fr_prefix}_axle_carrier">
  238. <xacro:null_inertial/>
  239. </link>
  240. <!-- The left and right axles have the same axis so that identical
  241. rotation values cause the wheels to rotate in the same direction. -->
  242. <joint name="${lr_prefix}_${fr_prefix}_axle" type="continuous">
  243. <parent link="${lr_prefix}_${fr_prefix}_axle_carrier"/>
  244. <child link="${lr_prefix}_${fr_prefix}_wheel"/>
  245. <origin rpy="${degrees_90} 0 0"/>
  246. <axis xyz="0 0 -1"/>
  247. <limit effort="${axle_eff_limit}" velocity="${axle_vel_limit}"/>
  248. </joint>
  249. <transmission name="${lr_prefix}_${fr_prefix}_axle_trans">
  250. <type>transmission_interface/SimpleTransmission</type>
  251. <joint name="${lr_prefix}_${fr_prefix}_axle">
  252. <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
  253. </joint>
  254. <actuator name="${lr_prefix}_${fr_prefix}_axle_act">
  255. <!-- This hardwareInterface element exists for compatibility
  256. with ROS Hydro. -->
  257. <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
  258. <mechanicalReduction>1</mechanicalReduction>
  259. </actuator>
  260. </transmission>
  261. <link name="${lr_prefix}_${fr_prefix}_wheel">
  262. <visual>
  263. <origin xyz="0
  264. ${lr_reflect * (axle_length - (tire_width /
  265. 2 - hex_hub_depth))}
  266. 0"/>
  267. <geometry>
  268. <cylinder radius="${tire_dia / 2}" length="${tire_width}"/>
  269. </geometry>
  270. <material name="tire_mat"/>
  271. </visual>
  272. <collision>
  273. <origin xyz="0
  274. ${lr_reflect * (axle_length - (tire_width /
  275. 2 - hex_hub_depth))}
  276. 0"/>
  277. <geometry>
  278. <cylinder radius="${tire_dia / 2}" length="${tire_width}"/>
  279. </geometry>
  280. </collision>
  281. <xacro:thick_walled_tube_inertial
  282. inner_rad="${hub_dia / 2}" outer_rad="${tire_dia / 2}"
  283. height="${tire_width}" mass="${wheel_mass}"/>
  284. </link>
  285. <gazebo reference="${lr_prefix}_${fr_prefix}_wheel">
  286. <material>Gazebo/Black</material>
  287. </gazebo>
  288. </xacro:macro>
  289. <!-- Front wheel -->
  290. <xacro:macro name="front_wheel"
  291. params="lr_prefix fr_prefix lr_reflect fr_reflect">
  292. <xacro:shock lr_prefix="${lr_prefix}" fr_prefix="${fr_prefix}"
  293. lr_reflect="${lr_reflect}" fr_reflect="${fr_reflect}"
  294. child="${lr_prefix}_steering_link"/>
  295. <link name="${lr_prefix}_steering_link">
  296. <xacro:null_inertial/>
  297. </link>
  298. <joint name="${lr_prefix}_steering_joint" type="revolute">
  299. <parent link="${lr_prefix}_steering_link"/>
  300. <child link="${lr_prefix}_${fr_prefix}_axle_carrier"/>
  301. <axis xyz="0 0 1"/>
  302. <limit lower="${-degrees_45}" upper="${degrees_45}"
  303. effort="${servo_stall_torque}" velocity="${servo_no_load_speed}"/>
  304. </joint>
  305. <transmission name="${lr_prefix}_steering_trans">
  306. <type>transmission_interface/SimpleTransmission</type>
  307. <joint name="${lr_prefix}_steering_joint">
  308. <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
  309. </joint>
  310. <actuator name="${lr_prefix}_steering_act">
  311. <!-- This hardwareInterface element exists for compatibility
  312. with ROS Hydro. -->
  313. <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
  314. <mechanicalReduction>1</mechanicalReduction>
  315. </actuator>
  316. </transmission>
  317. <xacro:wheel lr_prefix="${lr_prefix}" fr_prefix="${fr_prefix}"
  318. lr_reflect="${lr_reflect}"/>
  319. </xacro:macro>
  320. <!-- Rear wheel -->
  321. <xacro:macro name="rear_wheel"
  322. params="lr_prefix fr_prefix lr_reflect fr_reflect">
  323. <xacro:shock lr_prefix="${lr_prefix}" fr_prefix="${fr_prefix}"
  324. lr_reflect="${lr_reflect}" fr_reflect="${fr_reflect}"
  325. child="${lr_prefix}_${fr_prefix}_axle_carrier"/>
  326. <xacro:wheel lr_prefix="${lr_prefix}" fr_prefix="${fr_prefix}"
  327. lr_reflect="${lr_reflect}"/>
  328. </xacro:macro>
  329. <!-- chassis for sensors -->
  330. <xacro:macro name="layer" params="layer parent m x y z *joint_pose">
  331. <joint name="${layer}_joint" type="fixed">
  332. <xacro:insert_block name="joint_pose"/>
  333. <parent link="${parent}"/>
  334. <child link="${layer}_link" />
  335. </joint>
  336. <link name="${layer}_link">
  337. <visual>
  338. <origin xyz="0 0 0" rpy="0 0 0" />
  339. <geometry>
  340. <box size="${x} ${y} ${z}" />
  341. </geometry>
  342. <material name="yellow" />
  343. </visual>
  344. <collision>
  345. <origin xyz="0 0 0" rpy="0 0 0" />
  346. <geometry>
  347. <box size="${x} ${y} ${z}" />
  348. </geometry>
  349. </collision>
  350. <xacro:solid_cuboid_inertial
  351. width="${x}" depth="${y}"
  352. height="${z}" mass="${m}">
  353. <origin xyz="0 0 ${-z / 2}"/>
  354. </xacro:solid_cuboid_inertial>
  355. </link>
  356. <gazebo reference="${layer}_link">
  357. <material>Gazebo/Orange</material>
  358. </gazebo>
  359. </xacro:macro>
  360. <link name="base_footprint"/>
  361. <!-- base_link must have geometry so that its axes can be displayed in
  362. rviz. -->
  363. <link name="base_link">
  364. <visual>
  365. <geometry>
  366. <box size="0.01 0.01 0.01"/>
  367. </geometry>
  368. <material name="chassis_mat"/>
  369. </visual>
  370. </link>
  371. <gazebo reference="base_link">
  372. <material>Gazebo/Grey</material>
  373. </gazebo>
  374. <joint name="base_footprint_to_base_link" type="fixed">
  375. <parent link="base_footprint"/>
  376. <child link="base_link"/>
  377. <origin xyz="0 0 ${(wheel_travel/2)+shock_z_offset}" />
  378. </joint>
  379. <!-- Chassis -->
  380. <link name="chassis">
  381. <visual>
  382. <origin xyz="0 0 ${-chassis_height / 2}"/>
  383. <geometry>
  384. <box size="${chassis_length} ${chassis_width} ${chassis_height}"/>
  385. </geometry>
  386. <material name="chassis_mat"/>
  387. </visual>
  388. <collision>
  389. <origin xyz="0 0 ${-chassis_height / 2}"/>
  390. <geometry>
  391. <box size="${chassis_length} ${chassis_width} ${chassis_height}"/>
  392. </geometry>
  393. </collision>
  394. <xacro:solid_cuboid_inertial
  395. width="${chassis_length}" depth="${chassis_width}"
  396. height="${chassis_height}" mass="${chassis_mass}">
  397. <origin xyz="0 0 ${-chassis_height / 2}"/>
  398. </xacro:solid_cuboid_inertial>
  399. </link>
  400. <gazebo reference="chassis">
  401. <material>Gazebo/Grey</material>
  402. </gazebo>
  403. <joint name="base_link_to_chassis" type="fixed">
  404. <parent link="base_link"/>
  405. <child link="chassis"/>
  406. </joint>
  407. <!-- Batteries -->
  408. <xacro:battery prefix="left" reflect="1"/>
  409. <xacro:battery prefix="right" reflect="-1"/>
  410. <!-- Wheels -->
  411. <xacro:front_wheel lr_prefix="left" fr_prefix="front"
  412. lr_reflect="1" fr_reflect="1"/>
  413. <xacro:front_wheel lr_prefix="right" fr_prefix="front"
  414. lr_reflect="-1" fr_reflect="1"/>
  415. <xacro:rear_wheel lr_prefix="left" fr_prefix="rear"
  416. lr_reflect="1" fr_reflect="-1"/>
  417. <xacro:rear_wheel lr_prefix="right" fr_prefix="rear"
  418. lr_reflect="-1" fr_reflect="-1"/>
  419. <gazebo>
  420. <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
  421. <legacyModeNS>true</legacyModeNS>
  422. <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
  423. <robotNamespace>/racecar</robotNamespace>
  424. </plugin>
  425. </gazebo>
  426. <!-- layers -->
  427. <xacro:layer layer="platform" parent="chassis" m="${layer_mass}" x="${layer_x}" y="${layer_y}" z="${layer_z}">
  428. <origin xyz="0 0 ${layer_height}" rpy="0 0 0" />
  429. </xacro:layer>
  430. <xacro:layer layer="lidar_platform" parent="platform_link" m="${layer_mass}" x="0.12" y="0.10" z="0.01">
  431. <origin xyz="0.08 0 ${layer_height}" rpy="0 0 0" />
  432. </xacro:layer>
  433. <joint name="lidar_joint" type="fixed">
  434. <origin xyz="0 0 0.03" rpy="0 0 0" />
  435. <parent link="lidar_platform_link"/>
  436. <child link="laser_link"/>
  437. </joint>
  438. <lidar prefix="laser"/>
  439. <joint name="imu_joint" type="fixed">
  440. <origin xyz="0.16 0 0.015" rpy="0 0 0" />
  441. <parent link="platform_link"/>
  442. <child link="imu_link"/>
  443. </joint>
  444. <imu prefix="imu"/>
  445. <joint name="camera_joint" type="fixed">
  446. <origin xyz="0.16 0 0.05" rpy="0 0 0" />
  447. <parent link="platform_link"/>
  448. <child link="camera_link"/>
  449. </joint>
  450. <camera prefix="camera"/>
  451. </robot>