<?xml version="1.0" encoding="utf-8"?> <!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com) Commit Version: 1.6.0-4-g7f85cfe Build Version: 1.6.7995.38578 For more information, please see http://wiki.ros.org/sw_urdf_exporter --> <robot name="go2_description"> <link name="base"> <inertial> <origin xyz="0.021112 0 -0.005366" rpy="0 0 0" /> <mass value="6.921" /> <inertia ixx="0.02448" ixy="0.00012166" ixz="0.0014849" iyy="0.098077" iyz="-3.12E-05" izz="0.107" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/visuals/base.dae" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/base_body_convex.stl" /> </geometry></collision> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/base_neck_convex.stl" /> </geometry></collision> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/base_head_convex.stl" /> </geometry></collision> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/base_fl_support_convex.stl" /> </geometry></collision> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/base_fr_support_convex.stl" /> </geometry></collision> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/base_rl_support_convex.stl" /> </geometry></collision> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/base_rr_support_convex.stl" /> </geometry></collision> </link> <link name="FL_hip"> <inertial> <origin xyz="-0.0054 0.00194 -0.000105" rpy="0 0 0" /> <mass value="0.678" /> <inertia ixx="0.00048" ixy="-3.01E-06" ixz="1.11E-06" iyy="0.000884" iyz="-1.42E-06" izz="0.000596" /> </inertial> <visual> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/visuals/hip.dae" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/hip_convex.stl" /> </geometry></collision> </link> <joint name="FL_hip_joint" type="revolute"> <origin xyz="0.1934 0.0465 0" rpy="0 0 0" /> <parent link="base" /> <child link="FL_hip" /> <axis xyz="1 0 0" /> <limit lower="-1.0472" upper="1.0472" effort="23.7" velocity="30.1" /> </joint> <link name="FL_hip_rotor"> <inertial> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <mass value="0.089"/> <inertia ixx="0.000111842" ixy="0.0" ixz="0.0" iyy="0.000059647" iyz="0.0" izz="0.000059647"/> </inertial> </link> <joint name="FL_hip_rotor_joint" type="fixed"> <origin rpy="0 0 0" xyz="0.11215 0.04675 0"/> <parent link="base"/> <child link="FL_hip_rotor"/> </joint> <link name="FL_thigh"> <inertial> <origin xyz="-0.00374 -0.0223 -0.0327" rpy="0 0 0" /> <mass value="1.152" /> <inertia ixx="0.00584" ixy="8.72E-05" ixz="-0.000289" iyy="0.0058" iyz="0.000808" izz="0.00103" /> </inertial> <visual> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/visuals/thigh.dae" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/thigh_convex.stl" /> </geometry></collision> </link> <joint name="FL_thigh_joint" type="revolute"> <origin xyz="0 0.0955 0" rpy="0 0 0" /> <parent link="FL_hip" /> <child link="FL_thigh" /> <axis xyz="0 1 0" /> <limit lower="-1.5708" upper="3.4907" effort="23.7" velocity="30.1" /> </joint> <link name="FL_thigh_rotor"> <inertial> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <mass value="0.089"/> <inertia ixx="0.000059647" ixy="0.0" ixz="0.0" iyy="0.000111842" iyz="0.0" izz="0.000059647"/> </inertial> </link> <joint name="FL_thigh_rotor_joint" type="fixed"> <origin rpy="0 0 0" xyz="0 -0.00015 0"/> <parent link="FL_hip"/> <child link="FL_thigh_rotor"/> </joint> <link name="FL_calf"> <inertial> <origin xyz="0.00548 -0.000975 -0.115" rpy="0 0 0" /> <mass value="0.154" /> <inertia ixx="0.00108" ixy="3.4E-07" ixz="1.72E-05" iyy="0.0011" iyz="8.28E-06" izz="3.29E-05" /> </inertial> <visual> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/visuals/calf.dae" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/calf_upper_convex.stl" /> </geometry></collision> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/calf_lower_convex.stl" /> </geometry></collision> </link> <joint name="FL_calf_joint" type="revolute"> <origin xyz="0 0 -0.213" rpy="0 0 0" /> <parent link="FL_thigh" /> <child link="FL_calf" /> <axis xyz="0 1 0" /> <limit lower="-2.7227" upper="-0.83776" effort="45.43" velocity="15.70" /> </joint> <link name="FL_calf_rotor"> <inertial> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <mass value="0.089"/> <inertia ixx="0.000059647" ixy="0.0" ixz="0.0" iyy="0.000111842" iyz="0.0" izz="0.000059647"/> </inertial> </link> <joint name="FL_calf_rotor_joint" type="fixed"> <origin rpy="0 0 0" xyz="0 -0.03235 0"/> <parent link="FL_thigh"/> <child link="FL_calf_rotor"/> </joint> <link name="FL_foot"> <inertial> <origin xyz="0 0 0" rpy="0 0 0" /> <mass value="0.04" /> <inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06" /> </inertial> <visual> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/visuals/foot.dae" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/foot_convex.stl" /> </geometry></collision> </link> <joint name="FL_foot_joint" type="fixed" dont_collapse="true"> <origin xyz="0 0 -0.213" rpy="0 0 0" /> <parent link="FL_calf" /> <child link="FL_foot" /> <axis xyz="0 0 0" /> </joint> <link name="FR_hip"> <inertial> <origin xyz="-0.0054 -0.00194 -0.000105" rpy="0 0 0" /> <mass value="0.678" /> <inertia ixx="0.00048" ixy="3.01E-06" ixz="1.11E-06" iyy="0.000884" iyz="1.42E-06" izz="0.000596" /> </inertial> <visual> <origin xyz="0 0 0" rpy="3.1415 0 0" /> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/visuals/hip.dae" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="3.1415 0 0" /> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/hip_convex.stl" /> </geometry> </collision> </link> <joint name="FR_hip_joint" type="revolute"> <origin xyz="0.1934 -0.0465 0" rpy="0 0 0" /> <parent link="base" /> <child link="FR_hip" /> <axis xyz="1 0 0" /> <limit lower="-1.0472" upper="1.0472" effort="23.7" velocity="30.1" /> </joint> <link name="FR_hip_rotor"> <inertial> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <mass value="0.089"/> <inertia ixx="0.000111842" ixy="0.0" ixz="0.0" iyy="0.000059647" iyz="0.0" izz="0.000059647"/> </inertial> </link> <joint name="FR_hip_rotor_joint" type="fixed"> <origin rpy="0 0 0" xyz="0.11215 -0.04675 0"/> <parent link="base"/> <child link="FR_hip_rotor"/> </joint> <link name="FR_thigh"> <inertial> <origin xyz="-0.00374 0.0223 -0.0327" rpy="0 0 0" /> <mass value="1.152" /> <inertia ixx="0.00584" ixy="-8.72E-05" ixz="-0.000289" iyy="0.0058" iyz="-0.000808" izz="0.00103" /> </inertial> <visual> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/visuals/thigh_mirror.dae" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/thigh_mirror_convex.stl" /> </geometry></collision> </link> <joint name="FR_thigh_joint" type="revolute"> <origin xyz="0 -0.0955 0" rpy="0 0 0" /> <parent link="FR_hip" /> <child link="FR_thigh" /> <axis xyz="0 1 0" /> <limit lower="-1.5708" upper="3.4907" effort="23.7" velocity="30.1" /> </joint> <link name="FR_thigh_rotor"> <inertial> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <mass value="0.089"/> <inertia ixx="0.000059647" ixy="0.0" ixz="0.0" iyy="0.000111842" iyz="0.0" izz="0.000059647"/> </inertial> </link> <joint name="FR_thigh_rotor_joint" type="fixed"> <origin rpy="0 0 0" xyz="0 0.00015 0"/> <parent link="FR_hip"/> <child link="FR_thigh_rotor"/> </joint> <link name="FR_calf"> <inertial> <origin xyz="0.00548 0.000975 -0.115" rpy="0 0 0" /> <mass value="0.154" /> <inertia ixx="0.00108" ixy="-3.4E-07" ixz="1.72E-05" iyy="0.0011" iyz="-8.28E-06" izz="3.29E-05" /> </inertial> <visual> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/visuals/calf_mirror.dae" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/calf_upper_mirror_convex.stl" /> </geometry></collision> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/calf_lower_mirror_convex.stl" /> </geometry></collision> </link> <joint name="FR_calf_joint" type="revolute"> <origin xyz="0 0 -0.213" rpy="0 0 0" /> <parent link="FR_thigh" /> <child link="FR_calf" /> <axis xyz="0 1 0" /> <limit lower="-2.7227" upper="-0.83776" effort="45.43" velocity="15.70" /> </joint> <link name="FR_calf_rotor"> <inertial> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <mass value="0.089"/> <inertia ixx="0.000059647" ixy="0.0" ixz="0.0" iyy="0.000111842" iyz="0.0" izz="0.000059647"/> </inertial> </link> <joint name="FR_calf_rotor_joint" type="fixed"> <origin rpy="0 0 0" xyz="0 0.03235 0"/> <parent link="FR_thigh"/> <child link="FR_calf_rotor"/> </joint> <link name="FR_foot"> <inertial> <origin xyz="0 0 0" rpy="0 0 0" /> <mass value="0.04" /> <inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06" /> </inertial> <visual> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/visuals/foot.dae" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/foot_convex.stl" /> </geometry></collision> </link> <joint name="FR_foot_joint" type="fixed" dont_collapse="true"> <origin xyz="0 0 -0.213" rpy="0 0 0" /> <parent link="FR_calf" /> <child link="FR_foot" /> <axis xyz="0 0 0" /> </joint> <link name="RL_hip"> <inertial> <origin xyz="0.0054 0.00194 -0.000105" rpy="0 0 0" /> <mass value="0.678" /> <inertia ixx="0.00048" ixy="3.01E-06" ixz="-1.11E-06" iyy="0.000884" iyz="-1.42E-06" izz="0.000596" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 3.1415 0" /> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/visuals/hip.dae" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 3.1415 0" /> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/hip_convex.stl" /> </geometry> </collision> </link> <joint name="RL_hip_joint" type="revolute"> <origin xyz="-0.1934 0.0465 0" rpy="0 0 0" /> <parent link="base" /> <child link="RL_hip" /> <axis xyz="1 0 0" /> <limit lower="-1.0472" upper="1.0472" effort="23.7" velocity="30.1" /> </joint> <link name="RL_hip_rotor"> <inertial> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <mass value="0.089"/> <inertia ixx="0.000111842" ixy="0.0" ixz="0.0" iyy="0.000059647" iyz="0.0" izz="0.000059647"/> </inertial> </link> <joint name="RL_hip_rotor_joint" type="fixed"> <origin rpy="0 0 0" xyz="-0.11215 0.04675 0"/> <parent link="base"/> <child link="RL_hip_rotor"/> </joint> <link name="RL_thigh"> <inertial> <origin xyz="-0.00374 -0.0223 -0.0327" rpy="0 0 0" /> <mass value="1.152" /> <inertia ixx="0.00584" ixy="8.72E-05" ixz="-0.000289" iyy="0.0058" iyz="0.000808" izz="0.00103" /> </inertial> <visual> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/visuals/thigh.dae" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/thigh_convex.stl" /> </geometry></collision> </link> <joint name="RL_thigh_joint" type="revolute"> <origin xyz="0 0.0955 0" rpy="0 0 0" /> <parent link="RL_hip" /> <child link="RL_thigh" /> <axis xyz="0 1 0" /> <limit lower="-0.5236" upper="4.5379" effort="23.7" velocity="30.1" /> </joint> <link name="RL_thigh_rotor"> <inertial> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <mass value="0.089"/> <inertia ixx="0.000059647" ixy="0.0" ixz="0.0" iyy="0.000111842" iyz="0.0" izz="0.000059647"/> </inertial> </link> <joint name="RL_thigh_rotor_joint" type="fixed"> <origin rpy="0 0 0" xyz="0 -0.00015 0"/> <parent link="RL_hip"/> <child link="RL_thigh_rotor"/> </joint> <link name="RL_calf"> <inertial> <origin xyz="0.00548 -0.000975 -0.115" rpy="0 0 0" /> <mass value="0.154" /> <inertia ixx="0.00108" ixy="3.4E-07" ixz="1.72E-05" iyy="0.0011" iyz="8.28E-06" izz="3.29E-05" /> </inertial> <visual> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/visuals/calf.dae" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/calf_upper_convex.stl" /> </geometry></collision> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/calf_lower_convex.stl" /> </geometry></collision> </link> <joint name="RL_calf_joint" type="revolute"> <origin xyz="0 0 -0.213" rpy="0 0 0" /> <parent link="RL_thigh" /> <child link="RL_calf" /> <axis xyz="0 1 0" /> <limit lower="-2.7227" upper="-0.83776" effort="45.43" velocity="15.70" /> </joint> <link name="RL_calf_rotor"> <inertial> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <mass value="0.089"/> <inertia ixx="0.000059647" ixy="0.0" ixz="0.0" iyy="0.000111842" iyz="0.0" izz="0.000059647"/> </inertial> </link> <joint name="RL_calf_rotor_joint" type="fixed"> <origin rpy="0 0 0" xyz="0 -0.03235 0"/> <parent link="RL_thigh"/> <child link="RL_calf_rotor"/> </joint> <link name="RL_foot"> <inertial> <origin xyz="0 0 0" rpy="0 0 0" /> <mass value="0.04" /> <inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06" /> </inertial> <visual> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/visuals/foot.dae" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/foot_convex.stl" /> </geometry></collision> </link> <joint name="RL_foot_joint" type="fixed" dont_collapse="true"> <origin xyz="0 0 -0.213" rpy="0 0 0" /> <parent link="RL_calf" /> <child link="RL_foot" /> <axis xyz="0 0 0" /> </joint> <link name="RR_hip"> <inertial> <origin xyz="0.0054 -0.00194 -0.000105" rpy="0 0 0" /> <mass value="0.678" /> <inertia ixx="0.00048" ixy="-3.01E-06" ixz="-1.11E-06" iyy="0.000884" iyz="1.42E-06" izz="0.000596" /> </inertial> <visual> <origin xyz="0 0 0" rpy="3.1415 3.1415 0" /> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/visuals/hip.dae" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="3.1415 3.1415 0" /> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/hip_convex.stl" /> </geometry> </collision> </link> <joint name="RR_hip_joint" type="revolute"> <origin xyz="-0.1934 -0.0465 0" rpy="0 0 0" /> <parent link="base" /> <child link="RR_hip" /> <axis xyz="1 0 0" /> <limit lower="-1.0472" upper="1.0472" effort="23.7" velocity="30.1" /> </joint> <link name="RR_hip_rotor"> <inertial> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <mass value="0.089"/> <inertia ixx="0.000111842" ixy="0.0" ixz="0.0" iyy="0.000059647" iyz="0.0" izz="0.000059647"/> </inertial> </link> <joint name="RR_hip_rotor_joint" type="fixed"> <origin rpy="0 0 0" xyz="-0.11215 -0.04675 0"/> <parent link="base"/> <child link="RR_hip_rotor"/> </joint> <link name="RR_thigh"> <inertial> <origin xyz="-0.00374 0.0223 -0.0327" rpy="0 0 0" /> <mass value="1.152" /> <inertia ixx="0.00584" ixy="-8.72E-05" ixz="-0.000289" iyy="0.0058" iyz="-0.000808" izz="0.00103" /> </inertial> <visual> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/visuals/thigh_mirror.dae" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/thigh_mirror_convex.stl" /> </geometry></collision> </link> <joint name="RR_thigh_joint" type="revolute"> <origin xyz="0 -0.0955 0" rpy="0 0 0" /> <parent link="RR_hip" /> <child link="RR_thigh" /> <axis xyz="0 1 0" /> <limit lower="-0.5236" upper="4.5379" effort="23.7" velocity="30.1" /> </joint> <link name="RR_thigh_rotor"> <inertial> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <mass value="0.089"/> <inertia ixx="0.000059647" ixy="0.0" ixz="0.0" iyy="0.000111842" iyz="0.0" izz="0.000059647"/> </inertial> </link> <joint name="RR_thigh_rotor_joint" type="fixed"> <origin rpy="0 0 0" xyz="0 0.00015 0"/> <parent link="RR_hip"/> <child link="RR_thigh_rotor"/> </joint> <link name="RR_calf"> <inertial> <origin xyz="0.00548 0.000975 -0.115" rpy="0 0 0" /> <mass value="0.154" /> <inertia ixx="0.00108" ixy="-3.4E-07" ixz="1.72E-05" iyy="0.0011" iyz="-8.28E-06" izz="3.29E-05" /> </inertial> <visual> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/visuals/calf_mirror.dae" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/calf_upper_mirror_convex.stl" /> </geometry></collision> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/calf_lower_mirror_convex.stl" /> </geometry></collision> </link> <joint name="RR_calf_joint" type="revolute"> <origin xyz="0 0 -0.213" rpy="0 0 0" /> <parent link="RR_thigh" /> <child link="RR_calf" /> <axis xyz="0 1 0" /> <limit lower="-2.7227" upper="-0.83776" effort="45.43" velocity="15.70" /> </joint> <link name="RR_calf_rotor"> <inertial> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <mass value="0.089"/> <inertia ixx="0.000059647" ixy="0.0" ixz="0.0" iyy="0.000111842" iyz="0.0" izz="0.000059647"/> </inertial> </link> <joint name="RR_calf_rotor_joint" type="fixed"> <origin rpy="0 0 0" xyz="0 0.03235 0"/> <parent link="RR_thigh"/> <child link="RR_calf_rotor"/> </joint> <link name="RR_foot"> <inertial> <origin xyz="0 0 0" rpy="0 0 0" /> <mass value="0.04" /> <inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06" /> </inertial> <visual> <geometry> <mesh filename="package://example-robot-data/robots/go2_description/visuals/foot.dae" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision><geometry> <mesh filename="package://example-robot-data/robots/go2_description/collisions/foot_convex.stl" /> </geometry></collision> </link> <joint name="RR_foot_joint" type="fixed" dont_collapse="true"> <origin xyz="0 0 -0.213" rpy="0 0 0" /> <parent link="RR_calf" /> <child link="RR_foot" /> <axis xyz="0 0 0" /> </joint> <link name="imu"> <inertial> <origin xyz="0 0 0" rpy="0 0 0" /> <mass value="0" /> <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" /> </inertial> </link> <joint name="imu_joint" type="fixed"> <origin xyz="-0.02557 0 0.04232" rpy="0 0 0" /> <parent link="base" /> <child link="imu" /> <axis xyz="0 0 0" /> </joint> <link name="radar"> <inertial> <origin xyz="0 0 0" rpy="0 0 0" /> <mass value="0" /> <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" /> </inertial> </link> <joint name="radar_joint" type="fixed"> <origin xyz="0.28945 0 -0.046825" rpy="0 2.8782 0" /> <parent link="base" /> <child link="radar" /> <axis xyz="0 0 0" /> </joint> </robot>