forked from IntelRealSense/realsense-ros
-
Notifications
You must be signed in to change notification settings - Fork 38
/
Copy path_d435.gazebo.xacro
146 lines (139 loc) · 4.93 KB
/
_d435.gazebo.xacro
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
<?xml version="1.0"?>
<!--
License: Apache 2.0. See LICENSE file in root directory.
Copyright(c) 2017 PAL Robotics, S.L. All Rights Reserved
This is the Gazebo URDF model for the Intel RealSense D435 camera
-->
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="gazebo_d435" params="camera_name reference_link topics_ns depth_optical_frame color_optical_frame infrared1_optical_frame infrared2_optical_frame" >
<!-- Load parameters to model's main link-->
<xacro:property name="deg_to_rad" value="0.01745329251994329577" />
<gazebo reference="${reference_link}">
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
<gravity>1</gravity>
<!--<mu>1</mu>-->
<mu2>1</mu2>
<fdir1>0 0 0</fdir1>
<!--<slip1>0</slip1>
<slip2>0</slip2>-->
<kp>1e+13</kp>
<kd>1</kd>
<!--<max_vel>0.01</max_vel>
<min_depth>0</min_depth>-->
<sensor name="${camera_name}color" type="camera">
<camera name="${camera_name}">
<horizontal_fov>${69.4*deg_to_rad}</horizontal_fov>
<image>
<width>1920</width>
<height>1080</height>
<format>RGB_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>1</visualize>
</sensor>
<sensor name="${camera_name}ired1" type="camera">
<camera name="${camera_name}">
<horizontal_fov>${85.2*deg_to_rad}</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
<format>L_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.05</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>90</update_rate>
<visualize>0</visualize>
</sensor>
<sensor name="${camera_name}ired2" type="camera">
<camera name="${camera_name}">
<horizontal_fov>${85.2*deg_to_rad}</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
<format>L_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.05</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>90</update_rate>
<visualize>0</visualize>
</sensor>
<sensor name="${camera_name}depth" type="depth">
<camera name="${camera_name}">
<horizontal_fov>${85.2*deg_to_rad}</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.100</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>90</update_rate>
<visualize>0</visualize>
</sensor>
</gazebo>
<gazebo>
<plugin name="${topics_ns}" filename="librealsense_gazebo_plugin.so">
<prefix>${camera_name}</prefix>
<depthUpdateRate>60.0</depthUpdateRate>
<colorUpdateRate>60.0</colorUpdateRate>
<infraredUpdateRate>60.0</infraredUpdateRate>
<depthTopicName>depth/image_raw</depthTopicName>
<depthCameraInfoTopicName>depth/camera_info</depthCameraInfoTopicName>
<colorTopicName>color/image_raw</colorTopicName>
<colorCameraInfoTopicName>color/camera_info</colorCameraInfoTopicName>
<infrared1TopicName>infra1/image_raw</infrared1TopicName>
<infrared1CameraInfoTopicName>infra1/camera_info</infrared1CameraInfoTopicName>
<infrared2TopicName>infra2/image_raw</infrared2TopicName>
<infrared2CameraInfoTopicName>infra2/camera_info</infrared2CameraInfoTopicName>
<colorOpticalframeName>${color_optical_frame}</colorOpticalframeName>
<depthOpticalframeName>${depth_optical_frame}</depthOpticalframeName>
<infrared1OpticalframeName>${infrared1_optical_frame}</infrared1OpticalframeName>
<infrared2OpticalframeName>${infrared2_optical_frame}</infrared2OpticalframeName>
<rangeMinDepth>0.2</rangeMinDepth>
<rangeMaxDepth>10.0</rangeMaxDepth>
<pointCloud>false</pointCloud>
<pointCloudTopicName>depth/points</pointCloudTopicName>
<pointCloudCutoff>0.5</pointCloudCutoff>
</plugin>
</gazebo>
</xacro:macro>
</robot>