123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110 |
- <?xml version="1.0"?>
- <robot name="turtlebot_kinect" xmlns:xacro="http://ros.org/wiki/xacro">
- <property name="M_PI" value="3.14159"/>
- <property name="MESH_SCALE" value="100"/>
- <xacro:include filename="$(find rbx1_description)/urdf/gazebo.urdf.xacro"/>
- <xacro:include filename="$(find rbx1_description)/urdf/turtlebot_calibration.xacro" />
- <xacro:macro name="turtlebot_kinect">
- <joint name="base_camera_joint" type="fixed">
- <origin xyz="${turtlebot_calib_cam_x} ${turtlebot_calib_cam_y} ${turtlebot_calib_cam_z}"
- rpy="${turtlebot_calib_cam_rr} ${turtlebot_calib_cam_rp} ${turtlebot_calib_cam_ry}" />
- <parent link="${turtlebot_camera_parent_name}" />
- <child link="camera_link" />
- </joint>
- <link name="camera_link">
- <inertial>
- <mass value="0.01" />
- <origin xyz="0 0 0" />
- <inertia ixx="0.001" ixy="0.0" ixz="0.0"
- iyy="0.001" iyz="0.0"
- izz="0.001" />
- </inertial>
- <visual>
- <origin xyz=" 0 0 0 " rpy="0 0 0" />
- <geometry>
- <mesh filename="package://rbx1_description/meshes/kinect.dae" scale="${MESH_SCALE} ${MESH_SCALE} ${MESH_SCALE}"/>
- </geometry>
- </visual>
- <collision>
- <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
- <geometry>
- <box size="0.0730 .2760 0.0720"/>
- </geometry>
- </collision>
- </link>
- <joint name="camera_depth_joint" type="fixed">
- <origin xyz="0 0.018 0" rpy="0 0 0" />
- <parent link="camera_link" />
- <child link="camera_depth_frame" />
- </joint>
- <link name="camera_depth_frame">
- <inertial>
- <mass value="0.01" />
- <origin xyz="0 0 0" />
- <inertia ixx="0.001" ixy="0.0" ixz="0.0"
- iyy="0.001" iyz="0.0"
- izz="0.001" />
- </inertial>
- </link>
- <joint name="camera_depth_optical_joint" type="fixed">
- <origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
- <parent link="camera_depth_frame" />
- <child link="camera_depth_optical_frame" />
- </joint>
- <link name="camera_depth_optical_frame">
- <inertial>
- <mass value="0.001" />
- <origin xyz="0 0 0" />
- <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
- iyy="0.0001" iyz="0.0"
- izz="0.0001" />
- </inertial>
- </link>
- <joint name="camera_rgb_joint" type="fixed">
- <origin xyz="0 -0.005 0" rpy="0 0 0" />
- <parent link="camera_link" />
- <child link="camera_rgb_frame" />
- </joint>
- <link name="camera_rgb_frame">
- <inertial>
- <mass value="0.001" />
- <origin xyz="0 0 0" />
- <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
- iyy="0.0001" iyz="0.0"
- izz="0.0001" />
- </inertial>
- </link>
- <joint name="camera_rgb_optical_joint" type="fixed">
- <origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
- <parent link="camera_rgb_frame" />
- <child link="camera_rgb_optical_frame" />
- </joint>
- <link name="camera_rgb_optical_frame">
- <inertial>
- <mass value="0.001" />
- <origin xyz="0 0 0" />
- <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
- iyy="0.0001" iyz="0.0"
- izz="0.0001" />
- </inertial>
- </link>
- <!-- Kinect sensor for simulation -->
- <turtlebot_sim_kinect/>
- </xacro:macro>
- </robot>
|