|
| 1 | +<?xml version="1.0"?> |
| 2 | +<robot name="sensor_orbbec_astra_pro" xmlns:xacro="http://wiki.ros.org/Sensors/OrbbecAstra"> |
| 3 | + |
| 4 | + <xacro:macro name="sensor_orbbec_astra_pro" params="prefix parent prefix_topic:='front_rgbd_camera' *origin depth_offset_x:=0 depth_offset_y:=0 depth_offset_z:=0"> |
| 5 | + |
| 6 | + <joint name="${prefix}_joint" type="fixed"> |
| 7 | + <xacro:insert_block name="origin" /> |
| 8 | + <parent link="${parent}"/> |
| 9 | + <child link="${prefix}_link"/> |
| 10 | + </joint> |
| 11 | + |
| 12 | + <link name="${prefix}_link"> |
| 13 | + <visual> |
| 14 | + <origin xyz="0 0 0" rpy="0 0 0"/> |
| 15 | + <geometry> |
| 16 | + <mesh filename="package://robotnik_sensors/meshes/orbbec_astra.dae"/> |
| 17 | + </geometry> |
| 18 | + </visual> |
| 19 | + <collision> |
| 20 | + <geometry> |
| 21 | + <mesh filename="package://robotnik_sensors/meshes/orbbec_astra.dae"/> |
| 22 | + </geometry> |
| 23 | + </collision> |
| 24 | + <inertial> |
| 25 | + <mass value="0.001" /> |
| 26 | + <origin xyz="0.0 0.0 0.0" /> |
| 27 | + <xacro:solid_cuboid_inertia m="0.001" w="0.04" h="0.165" d="0.03" /> |
| 28 | + </inertial> |
| 29 | + </link> |
| 30 | + |
| 31 | + <joint name="${prefix}_color_joint" type="fixed"> |
| 32 | + <origin xyz="0.0 0.0125 0.0150" rpy="0.0 0.0 0.0"/> |
| 33 | + <parent link="${prefix}_link"/> |
| 34 | + <child link="${prefix}_color_frame" /> |
| 35 | + </joint> |
| 36 | + |
| 37 | + <link name="${prefix}_color_frame"> |
| 38 | + <inertial> |
| 39 | + <mass value="0.297" /> |
| 40 | + <origin xyz="-0.02 -0.0125 0.0" /> |
| 41 | + <xacro:solid_cuboid_inertia m="0.297" w="0.04" h="0.165" d="0.03" /> |
| 42 | + </inertial> |
| 43 | + </link> |
| 44 | + |
| 45 | + <joint name="${prefix}_color_optical_joint" type="fixed"> |
| 46 | + <origin xyz="0.0 0.0 0.0" rpy="${-M_PI/2} 0 ${-M_PI/2}" /> |
| 47 | + <parent link="${prefix}_color_frame" /> |
| 48 | + <child link="${prefix}_color_optical_frame" /> |
| 49 | + </joint> |
| 50 | + |
| 51 | + <link name="${prefix}_color_optical_frame"> |
| 52 | + <inertial> |
| 53 | + <mass value="0.001" /> |
| 54 | + <origin xyz="0 0 0" rpy="${M_PI/2} 0 ${M_PI/2}"/> |
| 55 | + <xacro:solid_cuboid_inertia m="0.001" w="0.04" h="0.165" d="0.03" /> |
| 56 | + </inertial> |
| 57 | + </link> |
| 58 | + |
| 59 | + <joint name="${prefix}_depth_joint" type="fixed"> |
| 60 | + <origin xyz="0.0 0.0375 0.0150" rpy="0 0 0" /> |
| 61 | + <parent link="${prefix}_link" /> |
| 62 | + <child link="${prefix}_depth_frame" /> |
| 63 | + </joint> |
| 64 | + |
| 65 | + <link name="${prefix}_depth_frame"> |
| 66 | + <inertial> |
| 67 | + <mass value="0.001" /> |
| 68 | + <origin xyz="0 0 0" /> |
| 69 | + <xacro:solid_cuboid_inertia m="0.001" w="0.04" h="0.165" d="0.03" /> |
| 70 | + </inertial> |
| 71 | + </link> |
| 72 | + |
| 73 | + <joint name="${prefix}_depth_optical_joint" type="fixed"> |
| 74 | + <origin xyz="${depth_offset_x} ${depth_offset_y} ${depth_offset_z}" rpy="${-M_PI/2} 0 ${-M_PI/2}" /> |
| 75 | + <parent link="${prefix}_depth_frame" /> |
| 76 | + <child link="${prefix}_depth_optical_frame" /> |
| 77 | + </joint> |
| 78 | + |
| 79 | + <link name="${prefix}_depth_optical_frame"> |
| 80 | + <inertial> |
| 81 | + <mass value="0.001" /> |
| 82 | + <origin xyz="0 0 0" /> |
| 83 | + <xacro:solid_cuboid_inertia m="0.001" w="0.04" h="0.165" d="0.03" /> |
| 84 | + </inertial> |
| 85 | + </link> |
| 86 | + |
| 87 | + <!-- RGBD sensor for simulation, same as Kinect --> |
| 88 | + <xacro:sensor_orbbec_astra_pro_gazebo/> |
| 89 | + |
| 90 | + </xacro:macro> |
| 91 | + |
| 92 | + <xacro:macro name="sensor_orbbec_astra_pro_gazebo"> |
| 93 | + |
| 94 | + <gazebo reference="${prefix}_link"> |
| 95 | + <sensor type="depth" name="${prefix}_depth_sensor"> |
| 96 | + <always_on>true</always_on> |
| 97 | + <update_rate>20.0</update_rate> |
| 98 | + <camera> |
| 99 | + <horizontal_fov>${60.0*M_PI/180.0}</horizontal_fov> |
| 100 | + <image> |
| 101 | + <format>R8G8B8</format> |
| 102 | + <width>640</width> |
| 103 | + <height>480</height> |
| 104 | + </image> |
| 105 | + <clip> |
| 106 | + <near>0.05</near> |
| 107 | + <far>3.5</far> |
| 108 | + </clip> |
| 109 | + </camera> |
| 110 | + <plugin name="${prefix}_controller" filename="libgazebo_ros_openni_kinect.so"> |
| 111 | + <cameraName>${prefix_topic}</cameraName> |
| 112 | + <alwaysOn>true</alwaysOn> |
| 113 | + <updateRate>10</updateRate> |
| 114 | + <imageTopicName>color/image_raw</imageTopicName> |
| 115 | + <depthImageTopicName>depth/image_raw</depthImageTopicName> |
| 116 | + <pointCloudTopicName>depth/points</pointCloudTopicName> |
| 117 | + <cameraInfoTopicName>color/camera_info</cameraInfoTopicName> |
| 118 | + <depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName> |
| 119 | + <frameName>/${prefix}_depth_optical_frame</frameName> |
| 120 | + <baseline>0.1</baseline> |
| 121 | + <distortion_k1>0.0</distortion_k1> |
| 122 | + <distortion_k2>0.0</distortion_k2> |
| 123 | + <distortion_k3>0.0</distortion_k3> |
| 124 | + <distortion_t1>0.0</distortion_t1> |
| 125 | + <distortion_t2>0.0</distortion_t2> |
| 126 | + <pointCloudCutoff>0.4</pointCloudCutoff> |
| 127 | + </plugin> |
| 128 | + </sensor> |
| 129 | + </gazebo> |
| 130 | + </xacro:macro> |
| 131 | +</robot> |
0 commit comments