/
az3_nav.launch
151 lines (122 loc) · 7.48 KB
/
az3_nav.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
<launch>
<!-- Localization-only mode -->
<arg name="localization" default="false"/>
<arg if="$(arg localization)" name="rtabmap_args" default=""/>
<arg unless="$(arg localization)" name="rtabmap_args" default="--delete_db_on_start"/>
<!-- AZIMUT 3 bringup: launch motors/odometry, laser scan and openni -->
<include file="$(find az3_bringup)/az3_standalone.launch"/>
<!-- OpenNI -->
<include file="$(find rtabmap_ros)/launch/azimut3/az3_openni.launch"/>
<!-- SLAM (robot side) -->
<group ns="rtabmap">
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="$(arg rtabmap_args)">
<param name="frame_id" type="string" value="base_footprint"/>
<param name="subscribe_scan" type="bool" value="true"/>
<param name="use_action_for_goal" type="bool" value="true"/>
<param name="cloud_decimation" type="int" value="1"/> <!-- we already decimate in memory below -->
<param name="grid_eroded" type="bool" value="true"/>
<param name="grid_cell_size" type="double" value="0.05"/>
<remap from="odom" to="/base_controller/odom"/>
<remap from="scan" to="/base_scan"/>
<remap from="mapData" to="mapData"/>
<remap from="rgb/image" to="/camera/rgb/image_rect_color"/>
<remap from="depth/image" to="/camera/depth_registered/image_raw"/>
<remap from="rgb/camera_info" to="/camera/depth_registered/camera_info"/>
<remap from="goal_out" to="current_goal"/>
<remap from="move_base" to="/planner/move_base"/>
<remap from="grid_map" to="/map"/>
<!-- RTAB-Map's parameters -->
<param name="RGBD/NeighborLinkRefining" type="string" value="true"/>
<param name="RGBD/ProximityBySpace" type="string" value="true"/>
<param name="Reg/Strategy" type="string" value="1"/>
<param name="RGBD/AngularUpdate" type="string" value="0.1"/>
<param name="RGBD/LinearUpdate" type="string" value="0.1"/>
<param name="RGBD/LocalRadius" type="string" value="5"/>
<param name="Mem/RehearsalSimilarity" type="string" value="0.45"/>
<param name="Mem/NotLinkedNodesKept" type="string" value="false"/>
<param name="Mem/ImagePostDecimation" type="string" value="4"/>
<param name="Rtabmap/StartNewMapOnLoopClosure" type="string" value="false"/>
<param name="Rtabmap/TimeThr" type="string" value="600"/>
<param name="Rtabmap/DetectionRate" type="string" value="1"/>
<param name="Bayes/PredictionLC" type="string" value="0.1 0.36 0.30 0.16 0.062 0.0151 0.00255 0.00035"/>
<param name="Optimizer/Slam2D" type="string" value="true"/>
<param name="RGBD/OptimizeFromGraphEnd" type="string" value="true"/>
<param name="Optimizer/Strategy" type="string" value="0"/>
<param name="Kp/DetectorStrategy" type="string" value="0"/>
<param name="Kp/MaxFeatures" type="string" value="200"/>
<param name="SURF/HessianThreshold" type="string" value="500"/>
<param name="Reg/Force3DoF" type="string" value="true"/>
<param name="Vis/MaxDepth" type="string" value="5"/>
<param name="Vis/MinInliers" type="string" value="5"/>
<param name="Icp/CorrespondenceRatio" type="string" value="0.3"/>
<!-- localization mode -->
<param if="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="false"/>
<param unless="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="true"/>
<param name="Mem/InitWMWithAllNodes" type="string" value="$(arg localization)"/>
</node>
</group>
<!-- teleop -->
<node name="joy" pkg="joy" type="joy_node"/>
<group ns="teleop">
<remap from="joy" to="/joy"/>
<node name="teleop" pkg="nodelet" type="nodelet" args="standalone azimut_tools/Teleop"/>
<param name="cmd_eta/abtr_priority" value="50"/>
</group>
<!-- ROS navigation stack move_base -->
<group ns="planner">
<remap from="scan" to="/base_scan"/>
<remap from="obstacles_cloud" to="/obstacles_cloud"/>
<remap from="ground_cloud" to="/ground_cloud"/>
<remap from="map" to="/map"/>
<remap from="move_base_simple/goal" to="/planner_goal"/>
<node pkg="move_base" type="move_base" respawn="true" name="move_base" output="screen">
<param name="base_global_planner" value="navfn/NavfnROS"/>
<rosparam file="$(find rtabmap_ros)/launch/azimut3/config/costmap_common_params_2d.yaml" command="load" ns="global_costmap"/>
<rosparam file="$(find rtabmap_ros)/launch/azimut3/config/costmap_common_params_2d.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find rtabmap_ros)/launch/azimut3/config/local_costmap_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find rtabmap_ros)/launch/azimut3/config/global_costmap_params.yaml" command="load" ns="global_costmap"/>
<rosparam file="$(find rtabmap_ros)/launch/azimut3/config/base_local_planner_params.yaml" command="load" />
</node>
<param name="cmd_vel/abtr_priority" value="10"/>
</group>
<node name="az3_abtr" pkg="azimut_tools" type="azimut_abtr_priority_node">
<remap from="abtr_cmd_eta" to="/base_controller/cmd_eta"/>
</node>
<!-- Arbitration between teleop and planner -->
<node name="register_cmd_eta" pkg="abtr_priority" type="register"
args="/cmd_eta /teleop/cmd_eta"/>
<node name="register_cmd_vel" pkg="abtr_priority" type="register"
args="/cmd_vel /planner/cmd_vel"/>
<!-- Throttling messages -->
<group ns="camera">
<node pkg="nodelet" type="nodelet" name="data_throttle" args="load rtabmap_ros/data_throttle camera_nodelet_manager">
<param name="rate" type="double" value="5"/>
<param name="decimation" type="int" value="2"/>
<remap from="rgb/image_in" to="rgb/image_rect_color"/>
<remap from="depth/image_in" to="depth_registered/image_raw"/>
<remap from="rgb/camera_info_in" to="depth_registered/camera_info"/>
<remap from="rgb/image_out" to="data_resized_image"/>
<remap from="depth/image_out" to="data_resized_image_depth"/>
<remap from="rgb/camera_info_out" to="data_resized_camera_info"/>
</node>
<!-- for the planner -->
<node pkg="nodelet" type="nodelet" name="points_xyz_planner" args="load rtabmap_ros/point_cloud_xyz camera_nodelet_manager">
<remap from="depth/image" to="data_resized_image_depth"/>
<remap from="depth/camera_info" to="data_resized_camera_info"/>
<remap from="cloud" to="cloudXYZ" />
<param name="decimation" type="int" value="1"/> <!-- already decimated above -->
<param name="max_depth" type="double" value="3.0"/>
<param name="voxel_size" type="double" value="0.02"/>
</node>
<node pkg="nodelet" type="nodelet" name="obstacles_detection" args="load rtabmap_ros/obstacles_detection camera_nodelet_manager">
<remap from="cloud" to="cloudXYZ"/>
<remap from="obstacles" to="/obstacles_cloud"/>
<remap from="ground" to="/ground_cloud"/>
<param name="frame_id" type="string" value="base_footprint"/>
<param name="map_frame_id" type="string" value="map"/>
<param name="wait_for_transform" type="bool" value="true"/>
<param name="min_cluster_size" type="int" value="20"/>
<param name="max_obstacles_height" type="double" value="0.4"/>
</node>
</group>
</launch>