13
13
<arg name="laser_topic" default="robot0/laser_0"/> default laser topic in stdr for 1 robot
14
14
<arg name="odom_topic" default="robot0/odom"/> -->
15
15
16
+ <arg name =" move_base_flex" default =" true" />
17
+
16
18
<!-- Frames: I subvert stdr frames system to into our old good map -> odom -> base, but here odom
17
19
is named map_static and base robot0. To make this work, I must prevent stdr_server to publish
18
20
map -> map_static, as amcl already does:
19
21
Comment https://github.com/stdr-simulator-ros-pkg/stdr_simulator/blob/indigo-devel/stdr_server/src/map_server.cpp#L93 -->
20
- <arg name =" odom_frame_id" default =" map_static" />
21
- <arg name =" base_frame_id" default =" robot0" />
22
+ <arg name =" odom_frame_id" default =" map_static" />
23
+ <arg name =" base_frame_id" default =" robot0" />
22
24
<arg name =" global_frame_id" default =" map" />
25
+
23
26
<!-- Name of the map to use (without path nor extension) and initial position -->
24
- <arg name =" map_file" default =" $(env TURTLEBOT_STDR_MAP_FILE)" />
25
- <arg name =" initial_pose_x" default =" 2.0" />
26
- <arg name =" initial_pose_y" default =" 2.0" />
27
- <arg name =" initial_pose_a" default =" 0.0" />
27
+ <arg name =" map_file" default =" $(env TURTLEBOT_STDR_MAP_FILE)" />
28
+ <arg name =" initial_pose_x" default =" 2.0" />
29
+ <arg name =" initial_pose_y" default =" 2.0" />
30
+ <arg name =" initial_pose_a" default =" 0.0" />
31
+
28
32
<arg name =" min_obstacle_height" default =" 0.0" />
29
33
<arg name =" max_obstacle_height" default =" 5.0" />
30
34
31
35
<!-- ******************** STDR ******************** -->
36
+ <param name =" robot0/odometry_rate" value =" 50.0" />
37
+
32
38
<include file =" $(find stdr_robot)/launch/robot_manager.launch" />
33
39
34
40
<!--
@@ -84,13 +90,13 @@ TODO: I can recover this if I can rename the robot and once I start using a thor
84
90
<param name =" yaml_cfg_file" value =" $(find thorp_bringup)/param/vel_multiplexer.yaml" />
85
91
</node >
86
92
87
- <!-- ******************** Maps ********************* -->
88
- <node name = " map_server " pkg = " map_server " type = " map_server " args = " $(arg map_file) " >
89
- <param name =" frame_id " value =" $(arg global_frame_id )" />
90
- </ node >
91
-
92
- <!-- **************** Move base flex *************** -- >
93
- < include file = " $(find thorp_bringup)/launch/includes/move_base_flex.launch.xml " >
93
+ <!-- ***************** Navigation ****************** -->
94
+ <include file = " $(find thorp_bringup)/launch/includes/navigation.launch.xml " >
95
+ <arg name =" move_base_flex " value =" $(arg move_base_flex )" />
96
+ < arg name = " map_file " value = " $(arg map_file) " />
97
+ < arg name = " initial_pose_x " value = " $(arg initial_pose_x) " />
98
+ < arg name = " initial_pose_y " value = " $(arg initial_pose_y) " / >
99
+ < arg name = " initial_pose_a " value = " $(arg initial_pose_a) " / >
94
100
<arg name =" odom_frame_id" value =" $(arg odom_frame_id)" />
95
101
<arg name =" base_frame_id" value =" $(arg base_frame_id)" />
96
102
<arg name =" global_frame_id" value =" $(arg global_frame_id)" />
@@ -101,21 +107,10 @@ TODO: I can recover this if I can rename the robot and once I start using a thor
101
107
<param name =" move_base/local_costmap/obstacle_layer/scan/max_obstacle_height" value =" $(arg max_obstacle_height)" />
102
108
<param name =" move_base/global_costmap/obstacle_layer/scan/min_obstacle_height" value =" $(arg min_obstacle_height)" />
103
109
<param name =" move_base/global_costmap/obstacle_layer/scan/max_obstacle_height" value =" $(arg max_obstacle_height)" />
104
-
105
- <!-- ******************** Amcl ********************* -->
106
- <include file =" $(find thorp_bringup)/launch/includes/amcl.launch.xml" >
107
- <!-- <arg name="scan_topic" value="$(arg laser_topic)"/> -->
108
- <arg name =" use_map_topic" value =" true" />
109
- <arg name =" odom_frame_id" value =" $(arg odom_frame_id)" />
110
- <arg name =" base_frame_id" value =" $(arg base_frame_id)" />
111
- <arg name =" global_frame_id" value =" $(arg global_frame_id)" />
112
- <arg name =" initial_pose_x" value =" $(arg initial_pose_x)" />
113
- <arg name =" initial_pose_y" value =" $(arg initial_pose_y)" />
114
- <arg name =" initial_pose_a" value =" $(arg initial_pose_a)" />
115
- </include >
116
-
117
- <!-- ***** Watchdog to keep the pose on reboot ***** -->
118
- <node name =" save_amcl_pose" pkg =" thorp_toolkit" type =" save_pose_node" />
110
+ <param name =" move_base_flex/local_costmap/obstacle_layer/scan/min_obstacle_height" value =" $(arg min_obstacle_height)" />
111
+ <param name =" move_base_flex/local_costmap/obstacle_layer/scan/max_obstacle_height" value =" $(arg max_obstacle_height)" />
112
+ <param name =" move_base_flex/global_costmap/obstacle_layer/scan/min_obstacle_height" value =" $(arg min_obstacle_height)" />
113
+ <param name =" move_base_flex/global_costmap/obstacle_layer/scan/max_obstacle_height" value =" $(arg max_obstacle_height)" />
119
114
120
115
<!-- **************** Visualization **************** -->
121
116
<node name =" rviz" pkg =" rviz" type =" rviz" args =" -d $(find thorp_bringup)/rviz/view_nav.rviz" />
0 commit comments