-
Notifications
You must be signed in to change notification settings - Fork 10
/
robotino.launch
268 lines (216 loc) · 11.9 KB
/
robotino.launch
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
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
<launch>
<arg name="sim" default="true"/>
<arg name="x" default="0"/>
<arg name="y" default="0"/>
<group if="$(arg sim)">
<param name="robot_description"
command="$(find xacro)/xacro.py $(find robotino_description)/urdf/robotino_sim.urdf.xacro"/>
<node name="spawn_gazebo_model" pkg="gazebo_ros" type="spawn_model"
args="-urdf -param robot_description -model rrbot -x $(arg x) -y $(arg y)" respawn="false" output="screen"/>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" ns="rrbot"/>
<node pkg="robotino_gazebo_plugin" type="imu_republish.py" name="imu_republish"/>
<node pkg="robot_localization" type="ekf_localization_node" name="camera_ekf" clear_params="true"
output="screen">
<remap from="/set_pose" to="/camera/set_pose"/>
<param name="frequency" value="100"/>
<param name="sensor_timeout" value="0.05"/>
<param name="two_d_mode" value="true"/>
<param name="publish_tf" value="true"/>
<param name="base_link_frame" value="cameraholder_link"/>
<param name="odom_frame" value="pantilt_link"/>
<param name="world_frame" value="pantilt_link"/>
<param name="transform_time_offset" value="0.05"/>
<remap from="/odometry/filtered" to="/camera/odometry/filtered"/>
<param name="odom0" value="/camera/odometry"/>
<param name="imu0" value="/imu_cam_filtered/data"/>
<!-- The values are ordered as x, y, z, roll, pitch, yaw, vx, vy, vz,
vroll, vpitch, vyaw, ax, ay, az. -->
<rosparam param="odom0_config">[true, true, true,
false, false, false,
false, false, false,
false, false, true,
false, false, false]
</rosparam>
<rosparam param="imu0_config">[false, false, false,
false, false, false,
false, false, false,
false, false, true,
false, false, false]
</rosparam>
<rosparam param="initial_state">
[0, 0, 0.32,
0, 0, 0,
0, 0, 0,
0, 0, 0,
0, 0, 0]
</rosparam>
<param name="imu0_differential" value="false"/>
<param name="odom0_differential" value="false"/>
<param name="odom0_relative" value="false"/>
<param name="imu0_relative" value="false"/>
<param name="imu0_remove_gravitational_acceleration" value="true"/>
<param name="print_diagnostics" value="false"/>
<param name="odom0_queue_size" value="100"/>
<param name="imu0_queue_size" value="100"/>
<param name="dynamic_process_noise_covariance" value="true"/>
<param name="odom0_nodelay" value="true"/>
<param name="smooth_lagged_data" value="true"/>
<param name="history_length" value="50"/>
<rosparam param="process_noise_covariance">[0.002, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
<!--y --> 0, 0.002, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
<!--z --> 0, 0, 0.006, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
<!--r --> 0, 0, 0, 0.003, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
<!--p --> 0, 0, 0, 0, 0.003, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
<!--ya --> 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0,
<!--vx --> 0, 0, 0, 0, 0, 0, 0.005, 0, 0, 0, 0, 0, 0, 0, 0,
<!--vy --> 0, 0, 0, 0, 0, 0, 0, 0.005, 0, 0, 0, 0, 0, 0, 0,
<!--vz --> 0, 0, 0, 0, 0, 0, 0, 0, 0.001, 0, 0, 0, 0, 0, 0,
<!--vr --> 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.001, 0, 0, 0, 0, 0,
<!--vp --> 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.001, 0, 0, 0, 0,
<!--vya --> 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0,
<!--ax --> 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.001, 0, 0,
<!--ay --> 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.001, 0,
<!--az --> 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.001]
</rosparam>
<rosparam param="initial_estimate_covariance">[1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9]
</rosparam>
</node>
<node pkg="robot_localization" type="ekf_localization_node" name="robot_ekf" clear_params="true"
output="screen">
<remap from="/set_pose" to="/robot/set_pose"/>
<param name="frequency" value="50"/>
<param name="sensor_timeout" value="0.05"/>
<param name="two_d_mode" value="true"/>
<param name="publish_tf" value="true"/>
<param name="base_link_frame" value="base_link"/>
<param name="odom_frame" value="odom"/>
<param name="world_frame" value="odom"/>
<param name="map_frame" value="map"/>
<param name="transform_time_offset" value="0.05"/>
<param name="odom0" value="/odom_calc"/>
<param name="odom1" value="/rtabmap/odom"/>
<param name="imu0" value="/imu_cam/data"/>
<param name="imu1" value="/imu_body/data"/>
<param name="pose0" value="/rtabmap/localization_pose"/>
<!-- The order of the values is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. -->
<rosparam param="odom0_config">[false, false, false,
false, false, false,
true, true, false,
false, false, true,
false, false, false]
</rosparam>
<rosparam param="odom1_config">[false, false, false,
false, false, false,
true, true, false,
false, false, true,
false, false, false]
</rosparam>
<!-- Not fusing heading angle for the IMU of the camera-->
<rosparam param="imu0_config">[false, false, false,
false, false, false,
false, false, false,
false, false, false,
true, true, false]
</rosparam>
<rosparam param="imu1_config">[false, false, false,
false, false, false,
false, false, false,
false, false, true,
true, true, false]
</rosparam>
<rosparam param="pose0_config">[true, true, false,
false, false, false,
false, false, false,
false, false, false,
false, false, false]
</rosparam>
<rosparam param="initial_state">
[0, 0, 0,
0, 0, 0,
0, 0, 0,
0, 0, 0,
0, 0, 0]
</rosparam>
<param name="smooth_lagged_data" value="true"/>
<param name="history_length" value="50"/>
<param name="imu0_differential" value="false"/>
<param name="imu1_differential" value="false"/>
<param name="odom0_differential" value="false"/>
<param name="odom1_differential" value="false"/>
<param name="pose0_differential" value="false"/>
<param name="imu0_relative" value="false"/>
<param name="imu1_relative" value="false"/>
<param name="odom0_relative" value="false"/>
<param name="odom1_relative" value="false"/>
<param name="pose0_relative" value="false"/>
<param name="odom0_nodelay" value="true"/>
<param name="odom1_nodelay" value="true"/>
<!-- todo true or false -->
<param name="imu0_remove_gravitational_acceleration" value="true"/>
<param name="print_diagnostics" value="false"/>
<!-- ======== ADVANCED PARAMETERS ======== -->
<param name="odom0_queue_size" value="100"/>
<param name="odom1_queue_size" value="100"/>
<param name="imu0_queue_size" value="100"/>
<param name="imu1_queue_size" value="100"/>
<param name="pose0_queue_size" value="1"/>
<param name="dynamic_process_noise_covariance" value="true"/>
<!-- The values are ordered as x, y, z, roll, pitch, yaw, vx, vy, vz,
vroll, vpitch, vyaw, ax, ay, az.-->
<rosparam param="process_noise_covariance">[0.002, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
<!--y --> 0, 0.002, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
<!--z --> 0, 0, 0.006, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
<!--r --> 0, 0, 0, 0.003, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
<!--p --> 0, 0, 0, 0, 0.003, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
<!--ya --> 0, 0, 0, 0, 0, 0.005, 0, 0, 0, 0, 0, 0, 0, 0, 0,
<!--vx --> 0, 0, 0, 0, 0, 0, 0.005, 0, 0, 0, 0, 0, 0, 0, 0,
<!--vy --> 0, 0, 0, 0, 0, 0, 0, 0.005, 0, 0, 0, 0, 0, 0, 0,
<!--vz --> 0, 0, 0, 0, 0, 0, 0, 0, 0.001, 0, 0, 0, 0, 0, 0,
<!--vr --> 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.001, 0, 0, 0, 0, 0,
<!--vp --> 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.001, 0, 0, 0, 0,
<!--vya --> 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.005, 0, 0, 0,
<!--ax --> 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.001, 0, 0,
<!--ay --> 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.001, 0,
<!--az --> 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.001]
</rosparam>
<!-- The values are ordered as x, y,
z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. -->
<rosparam param="initial_estimate_covariance">[1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9]
</rosparam>
</node>
</group>
<group unless="$(arg sim)">
<param name="robot_description"
command="$(find xacro)/xacro.py $(find robotino_description)/urdf/robotino.urdf.xacro"/>
<!--<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" output="screen"
args="-urdf -param robot_description -model robotino" />-->
</group>
</launch>