|
1 | 1 | <?xml version="1.0"?>
|
2 | 2 | <robot name="gazebo_d405" xmlns:xacro="http://www.ros.org/wiki/xacro" xmlns:ignition="http://gazebosim.org/schema">
|
3 | 3 |
|
4 |
| -<!-- |
5 |
| -Gazebo plugins can only be included once so this xacro assumes that a parent will include and configure them. |
6 |
| -This xacro requires Gazebo plugin: |
7 |
| - - ignition::gazebo::systems::Sensors |
8 |
| - to publish simulated RGBD camera data |
| 4 | +<xacro:include filename="$(find realsense2_gz_description)/urdf/rgb_camera.gazebo.xacro" /> |
| 5 | +<xacro:include filename="$(find realsense2_gz_description)/urdf/rgbd_camera.gazebo.xacro" /> |
9 | 6 |
|
10 |
| -For example: |
11 |
| -<gazebo> |
12 |
| - <plugin filename="libignition-gazebo-sensors-system.so" name="ignition::gazebo::systems::Sensors"> |
13 |
| - <render_engine>ogre2</render_engine> |
14 |
| - </plugin> |
15 |
| -</gazebo> |
| 7 | +<!-- Xacro args |
| 8 | + name: should match the name value passed to realsense2_description sensor xacro |
| 9 | + type: valid values [rgb or rgbd]. Sensor type you would like to simulate |
| 10 | + fps: the target frame rate of the camera images |
| 11 | + gz_topic_name: the topic name the image and camera_info are published to Gazebo topics |
| 12 | + image_width: See Realsense documentation for what the physical sensor supports |
| 13 | + image_height: See Realsense documentation for what the physical sensor supports |
| 14 | + trigger: valid values [true, false]. Only supported with 'type=rgb' and will only publish a single image when triggered on Gazebo topic '${name}/trigger' |
| 15 | + example command line trigger |
| 16 | + ign topic -t "/name/trigger" -m Boolean -p "data: true" -n 1 |
16 | 17 | -->
|
17 | 18 | <xacro:macro name="gazebo_d405" params="
|
18 | 19 | name:=camera
|
| 20 | + type:=rgbd |
19 | 21 | fps:=15
|
20 | 22 | gz_topic_name:=camera
|
21 | 23 | image_width:=1280
|
22 |
| - image_height:=720"> |
| 24 | + image_height:=720 |
| 25 | + triggered:=false"> |
23 | 26 |
|
24 | 27 | <!-- Realsense D405 RGB properties
|
25 | 28 | Assumptions:
|
| 29 | + Parent system (URDF or sdf) will start the Gazebo Sensors plugin. See notes in the camera.gazebo.xacros. |
26 | 30 | Simulated RGB and Depth sensors are in the same location as the RGB sensor of the physical camera.
|
27 | 31 | Simulated RGB and Depth sensors and have the same FOV as the RGB physical sensor.
|
28 | 32 | Note: physical hardware publishes pointcloud in `camera_depth_optical_frame` where this sensor will use
|
29 | 33 | the referenced camera color_frame. -->
|
30 |
| - <xacro:property name="realsense_h_fov" value="${69 * pi/180}" /> |
31 |
| - <xacro:property name="realsense_v_fov" value="${42 * pi/180}" /> |
32 |
| - <xacro:property name="fx" value="${image_width * 0.5 / tan(realsense_h_fov * 0.5)}" /> |
33 |
| - <xacro:property name="fy" value="${image_height * 0.5 / tan(realsense_v_fov * 0.5)}" /> |
34 |
| - <xacro:property name="cx" value="${image_width * 0.5}" /> |
35 |
| - <xacro:property name="cy" value="${image_height * 0.5}" /> |
| 34 | + <xacro:property name="realsense_h_fov" value="${87 * pi/180}" /> |
| 35 | + <xacro:property name="realsense_v_fov" value="${58 * pi/180}" /> |
| 36 | + <xacro:property name="min_depth" value="0.07" /> |
| 37 | + <xacro:property name="max_depth" value="0.5" /> |
36 | 38 |
|
37 |
| - <gazebo reference="${name}_color_frame"> |
38 |
| - <sensor name="${name}" type="rgbd_camera"> |
39 |
| - <camera> |
40 |
| - <horizontal_fov>${realsense_h_fov}</horizontal_fov> |
41 |
| - <image> |
42 |
| - <width>${image_width}</width> |
43 |
| - <height>${image_height}</height> |
44 |
| - <format>RGB_INT8</format> |
45 |
| - </image> |
46 |
| - <clip> |
47 |
| - <near>0.028</near> |
48 |
| - <far>5</far> |
49 |
| - </clip> |
50 |
| - <distortion> |
51 |
| - <k1>0.0</k1> |
52 |
| - <k2>0.0</k2> |
53 |
| - <k3>0.0</k3> |
54 |
| - <p1>0.0</p1> |
55 |
| - <p2>0.0</p2> |
56 |
| - <center>0.5 0.5</center> |
57 |
| - </distortion> |
58 |
| - <lens> |
59 |
| - <intrinsics> |
60 |
| - <fx>${fx}</fx> |
61 |
| - <fy>${fy}</fy> |
62 |
| - <cx>${cx}</cx> |
63 |
| - <cy>${cy}</cy> |
64 |
| - <s>0</s> |
65 |
| - </intrinsics> |
66 |
| - <projection> |
67 |
| - <p_fx>${fx}</p_fx> |
68 |
| - <p_fy>${fy}</p_fy> |
69 |
| - <p_cx>${cx}</p_cx> |
70 |
| - <p_cy>${cy}</p_cy> |
71 |
| - <tx>0</tx> |
72 |
| - <ty>0</ty> |
73 |
| - </projection> |
74 |
| - </lens> |
75 |
| - <noise> |
76 |
| - <type>gaussian</type> |
77 |
| - <mean>0</mean> |
78 |
| - <stddev>0.00</stddev> |
79 |
| - </noise> |
80 |
| - <depth_camera> |
81 |
| - <clip> |
82 |
| - <near>0.028</near> |
83 |
| - <far>5</far> |
84 |
| - </clip> |
85 |
| - </depth_camera> |
86 |
| - <optical_frame_id>${name}_color_optical_frame</optical_frame_id> |
87 |
| - </camera> |
88 |
| - <ignition_frame_id>${name}_color_frame</ignition_frame_id> |
89 |
| - <always_on>1</always_on> |
90 |
| - <update_rate>${fps}</update_rate> |
91 |
| - <visualize>false</visualize> |
92 |
| - <topic>${gz_topic_name}</topic> |
93 |
| - <enable_metrics>false</enable_metrics> |
94 |
| - </sensor> |
95 |
| - </gazebo> |
| 39 | + <xacro:if value="${type == 'rgbd'}"> |
| 40 | + <xacro:gazebo_rgbd name="${name}" |
| 41 | + fps="${fps}" |
| 42 | + gz_topic_name="${gz_topic_name}" |
| 43 | + image_width="${image_width}" |
| 44 | + image_height="${image_height}" |
| 45 | + h_fov="${realsense_h_fov}" |
| 46 | + v_fov="${realsense_v_fov}" |
| 47 | + min_depth="${min_depth}" |
| 48 | + max_depth="${max_depth}"/> |
| 49 | + </xacro:if> |
| 50 | + <xacro:if value="${type == 'rgb'}"> |
| 51 | + <xacro:gazebo_rgb name="${name}" |
| 52 | + fps="${fps}" |
| 53 | + gz_topic_name="${gz_topic_name}" |
| 54 | + image_width="${image_width}" |
| 55 | + image_height="${image_height}" |
| 56 | + h_fov="${realsense_h_fov}" |
| 57 | + v_fov="${realsense_v_fov}" |
| 58 | + triggered="${triggered}"/> |
| 59 | + </xacro:if> |
96 | 60 |
|
97 | 61 | </xacro:macro>
|
98 | 62 | </robot>
|
0 commit comments