diff --git a/robots/talos_data/robots/talos_full_v2.urdf b/robots/talos_data/robots/talos_full_v2.urdf index 42afc05a167215d6ea6e9de24b5ab9bfd9518471..532ca16ecfb2ece8c16f3981e3a2358eb367afa2 100644 --- a/robots/talos_data/robots/talos_full_v2.urdf +++ b/robots/talos_data/robots/talos_full_v2.urdf @@ -304,26 +304,50 @@ <parent link="rgbd_link"/> <child link="rgbd_depth_frame"/> </joint> - <link name="rgbd_depth_frame"/> + <link name="rgbd_depth_frame"> + <inertial> + <mass value="0.0"/> + <inertia ixx="0" ixy="0.0" ixz="0.0" iyy="0" iyz="0.0" izz="0"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + </inertial> + </link> <joint name="rgbd_depth_optical_joint" type="fixed"> <origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/> <parent link="rgbd_depth_frame"/> <child link="rgbd_depth_optical_frame"/> </joint> - <link name="rgbd_depth_optical_frame"/> + <link name="rgbd_depth_optical_frame"> + <inertial> + <mass value="0.0"/> + <inertia ixx="0" ixy="0.0" ixz="0.0" iyy="0" iyz="0.0" izz="0"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + </inertial> + </link> <!-- frames of the rgb sensor --> <joint name="rgbd_rgb_joint" type="fixed"> <origin rpy="0 0 0" xyz="0.0 0.01251 0.0"/> <parent link="rgbd_link"/> <child link="rgbd_rgb_frame"/> </joint> - <link name="rgbd_rgb_frame"/> + <link name="rgbd_rgb_frame"> + <inertial> + <mass value="0.0"/> + <inertia ixx="0" ixy="0.0" ixz="0.0" iyy="0" iyz="0.0" izz="0"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + </inertial> + </link> <joint name="rgbd_rgb_optical_joint" type="fixed"> <origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/> <parent link="rgbd_rgb_frame"/> <child link="rgbd_rgb_optical_frame"/> </joint> - <link name="rgbd_rgb_optical_frame"/> + <link name="rgbd_rgb_optical_frame"> + <inertial> + <mass value="0.0"/> + <inertia ixx="0" ixy="0.0" ixz="0.0" iyy="0" iyz="0.0" izz="0"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + </inertial> + </link> <gazebo reference="rgbd_link"> <!-- IR + depth --> <sensor name="rgbd_frame_sensor" type="depth">