|
From: <ei...@us...> - 2009-06-19 03:22:14
|
Revision: 17338
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17338&view=rev
Author: eitanme
Date: 2009-06-19 01:34:11 +0000 (Fri, 19 Jun 2009)
Log Message:
-----------
Merging the navigation rework branch back into trunk. I've tested in stage, gazebo, and the robot. Hopefully, not too much breaks.
r25624@att (orig r17263): eitanme | 2009-06-17 17:17:08 -0700
Creating a branch for testing the many changes I'm making to the navstack structure
r25625@att (orig r17264): eitanme | 2009-06-17 17:21:24 -0700
Moved navstack to the NodeHandle API. Changed parameter structure a lot. Changed interface for BaseGlobalPlanner to be more generic. Updates everything above the changes accordingly. Tested in stage, needs testing on a robot.
r25666@att (orig r17299): eitanme | 2009-06-18 11:54:43 -0700
Got new navstack working in gazebo... next up the robot
r25671@att (orig r17304): eitanme | 2009-06-18 13:34:46 -0700
Adding param files that were missing
r25675@att (orig r17308): eitanme | 2009-06-18 14:30:14 -0700
Changing persistance for slower tilt
r25676@att (orig r17309): eitanme | 2009-06-18 14:31:59 -0700
Set intensity explicitly
r25695@att (orig r17323): eitanme | 2009-06-18 16:47:47 -0700
Use a globally namespaced node handle for planning goals
r25696@att (orig r17324): eitanme | 2009-06-18 16:50:49 -0700
Changing error message to be correct
r25709@att (orig r17335): eitanme | 2009-06-18 18:16:29 -0700
Moving robot footprint from action to costmap_ros which can then be queried for it
r25711@att (orig r17337): eitanme | 2009-06-18 18:31:33 -0700
Fixing Costmap2DROS upwards dependencies
Modified Paths:
--------------
pkg/trunk/demos/2dnav_erratic/config/costmap_common_params.yaml
pkg/trunk/demos/2dnav_erratic/move_base/base_local_planner_params.yaml
pkg/trunk/demos/2dnav_erratic/move_base/move_base.launch
pkg/trunk/demos/2dnav_erratic/move_base/navfn_params.yaml
pkg/trunk/demos/2dnav_gazebo/2dnav-stack-amcl.launch
pkg/trunk/demos/2dnav_gazebo/2dnav-stack-fake_localization.launch
pkg/trunk/demos/2dnav_pr2/config/costmap_common_params.yaml
pkg/trunk/demos/2dnav_pr2/move_base/2dnav_pr2.launch
pkg/trunk/demos/2dnav_pr2/move_base/base_local_planner_params.yaml
pkg/trunk/demos/2dnav_pr2/move_base/move_base.xml
pkg/trunk/demos/2dnav_pr2/move_base/navfn_params.yaml
pkg/trunk/demos/2dnav_pr2/move_base_local/base_local_planner_params.yaml
pkg/trunk/demos/2dnav_pr2/move_base_local/move_base_local.xml
pkg/trunk/demos/2dnav_pr2/nav_view/nav_view_move_base.launch
pkg/trunk/demos/2dnav_pr2/nav_view/nav_view_move_base_local.launch
pkg/trunk/demos/2dnav_pr2/rviz/move_base.vcg
pkg/trunk/demos/2dnav_pr2/rviz/move_base_local.vcg
pkg/trunk/demos/2dnav_pr2/rviz/rviz_move_base.launch
pkg/trunk/demos/2dnav_pr2/rviz/rviz_move_base_local.launch
pkg/trunk/demos/milestone2/milestone2_actions/config/navigation.xml
pkg/trunk/highlevel/doors/doors_core/src/move_base_door_action.cpp
pkg/trunk/highlevel/move_base/CMakeLists.txt
pkg/trunk/highlevel/move_base/include/move_base/move_base.h
pkg/trunk/highlevel/move_base/src/move_base.cpp
pkg/trunk/highlevel/move_base_stage/config/costmap_common_params.yaml
pkg/trunk/highlevel/move_base_stage/move_base/base_local_planner_params.yaml
pkg/trunk/highlevel/move_base_stage/move_base/move_base.launch
pkg/trunk/highlevel/move_base_stage/move_base/move_base_multi_robot.launch
pkg/trunk/highlevel/move_base_stage/move_base/navfn_params.yaml
pkg/trunk/motion_planning/navfn/include/navfn/navfn_ros.h
pkg/trunk/motion_planning/navfn/src/navfn_ros.cpp
pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/include/sbpl_door_planner_action/sbpl_door_planner_action.h
pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/src/sbpl_door_planner_action.cpp
pkg/trunk/motion_planning/planning_research/sbpl_planner_node/src/sbpl_planner_node.cpp
pkg/trunk/nav/base_local_planner/include/base_local_planner/trajectory_planner_ros.h
pkg/trunk/nav/base_local_planner/src/trajectory_planner_ros.cpp
pkg/trunk/nav/nav_robot_actions/include/nav_robot_actions/base_global_planner.h
pkg/trunk/nav/nav_robot_actions/include/nav_robot_actions/base_local_planner.h
pkg/trunk/nav/people_aware_nav/src/move_base_constrained.cpp
pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/pre.launch
pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/prf.launch
pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/prg.launch
pkg/trunk/world_models/costmap_2d/include/costmap_2d/costmap_2d_publisher.h
pkg/trunk/world_models/costmap_2d/include/costmap_2d/costmap_2d_ros.h
pkg/trunk/world_models/costmap_2d/src/costmap_2d_publisher.cpp
pkg/trunk/world_models/costmap_2d/src/costmap_2d_ros.cpp
Added Paths:
-----------
pkg/trunk/demos/2dnav_erratic/move_base/global_costmap_params.yaml
pkg/trunk/demos/2dnav_erratic/move_base/local_costmap_params.yaml
pkg/trunk/demos/2dnav_pr2/move_base/global_costmap_params.yaml
pkg/trunk/demos/2dnav_pr2/move_base/local_costmap_params.yaml
pkg/trunk/demos/2dnav_pr2/move_base_local/costmap_params.yaml
pkg/trunk/highlevel/move_base_stage/move_base/global_costmap_params.yaml
pkg/trunk/highlevel/move_base_stage/move_base/local_costmap_params.yaml
Removed Paths:
-------------
pkg/trunk/demos/2dnav_pr2/config/voxel_costmap_common_params.yaml
pkg/trunk/demos/2dnav_pr2/move_base/base_local_planner_voxel_params.yaml
pkg/trunk/demos/2dnav_pr2/move_base/move_base_voxel.xml
pkg/trunk/demos/2dnav_pr2/move_base_local/move_base_local_voxel.xml
pkg/trunk/highlevel/move_base/include/move_base/move_base_local.h
pkg/trunk/highlevel/move_base/src/move_base_local.cpp
pkg/trunk/highlevel/move_base_stage/move_base_local/
pkg/trunk/highlevel/move_base_stage/move_base_maze/
Property Changed:
----------------
pkg/trunk/
Property changes on: pkg/trunk
___________________________________________________________________
Modified: svk:merge
- 637b03a7-42c1-4bbd-8d43-e365e379942c:/prfilters:13971
637b03a7-42c1-4bbd-8d43-e365e379942c:/rosTF_to_tf:9746
920d6130-5740-4ec1-bb1a-45963d5fd813:/costmap_rework_branch:20583
920d6130-5740-4ec1-bb1a-45963d5fd813:/frameidpr:7015
920d6130-5740-4ec1-bb1a-45963d5fd813:/nav_rework:21482
920d6130-5740-4ec1-bb1a-45963d5fd813:/users/josh-pr:11755
920d6130-5740-4ec1-bb1a-45963d5fd813:/wgpkgtrunk:5865
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/josh:10136
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/milestone2:16602
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/rosbus:261
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/tags/milestone2_tags/milestone2_final:16577
+ 637b03a7-42c1-4bbd-8d43-e365e379942c:/prfilters:13971
637b03a7-42c1-4bbd-8d43-e365e379942c:/rosTF_to_tf:9746
920d6130-5740-4ec1-bb1a-45963d5fd813:/costmap_rework_branch:20583
920d6130-5740-4ec1-bb1a-45963d5fd813:/frameidpr:7015
920d6130-5740-4ec1-bb1a-45963d5fd813:/nav_rework:21482
920d6130-5740-4ec1-bb1a-45963d5fd813:/users/josh-pr:11755
920d6130-5740-4ec1-bb1a-45963d5fd813:/wgpkgtrunk:5865
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/josh:10136
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/milestone2:16602
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/nav_rework:17337
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/rosbus:261
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/tags/milestone2_tags/milestone2_final:16577
Modified: pkg/trunk/demos/2dnav_erratic/config/costmap_common_params.yaml
===================================================================
--- pkg/trunk/demos/2dnav_erratic/config/costmap_common_params.yaml 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_erratic/config/costmap_common_params.yaml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -1,12 +1,20 @@
-costmap:
- obstacle_range: 2.5
- max_obstacle_height: 2.0
- raytrace_range: 3.0
- inscribed_radius: 0.20
- circumscribed_radius: 0.25
- inflation_radius: 0.25
- cost_scaling_factor: 1.0
- lethal_cost_threshold: 100
- observation_topics: scan
- scan: {sensor_frame: frame_from_message, data_type: LaserScan, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: true, clearing: true}
+#START VOXEL STUFF
+map_type: voxel
+origin_z: 0.0
+z_resolution: 0.2
+z_voxels: 10
+unknown_threshold: 10
+mark_threshold: 0
+#END VOXEL STUFF
+transform_tolerance: 0.3
+obstacle_range: 2.5
+max_obstacle_height: 2.0
+raytrace_range: 3.0
+#inscribed_radius: 0.325
+circumscribed_radius: 0.46
+inflation_radius: 0.55
+cost_scaling_factor: 10.0
+lethal_cost_threshold: 100
+observation_topics: scan
+scan: {sensor_frame: frame_from_message, data_type: LaserScan, expected_update_rate: 0.2,
+ observation_persistance: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08}
Modified: pkg/trunk/demos/2dnav_erratic/move_base/base_local_planner_params.yaml
===================================================================
--- pkg/trunk/demos/2dnav_erratic/move_base/base_local_planner_params.yaml 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_erratic/move_base/base_local_planner_params.yaml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -1,20 +1,11 @@
-base_local_planner:
+footprint: [[-0.325, -0.325], [-0.325, 0.325], [0.325, 0.325], [0.325, -0.325]]
+TrajectoryPlannerROS:
#Independent settings for the local costmap
- costmap:
- global_frame: map
- robot_base_frame: base_link
- update_frequency: 5.0
- publish_frequency: 2.0
- static_map: false
- rolling_window: true
- width: 6.0
- height: 6.0
- resolution: 0.025
- origin_x: 0.0
- origin_y: 0.0
- world_model: freespace
+ transform_tolerance: 0.3
+ costmap_visualization_rate: 0.0
+ world_model: costmap
sim_time: 1.7
- sim_granularity: 0.05
+ sim_granularity: 0.025
dwa: true
vx_samples: 3
vtheta_samples: 20
@@ -27,13 +18,13 @@
yaw_goal_tolerance: 0.05
goal_distance_bias: 0.8
path_distance_bias: 0.6
- occdist_scale: 0.05
+ occdist_scale: 0.01
heading_lookahead: 0.325
oscillation_reset_dist: 0.05
acc_limit_th: 3.2
acc_limit_x: 2.5
- acc_limit_y: 0.0
+ acc_limit_y: 2.5
heading_scoring: false
heading_scoring_timestep: 0.8
- holonomic_robot: false
+ holonomic_robot: true
simple_attractor: false
Added: pkg/trunk/demos/2dnav_erratic/move_base/global_costmap_params.yaml
===================================================================
--- pkg/trunk/demos/2dnav_erratic/move_base/global_costmap_params.yaml (rev 0)
+++ pkg/trunk/demos/2dnav_erratic/move_base/global_costmap_params.yaml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -0,0 +1,9 @@
+#Independent settings for the planner's costmap
+global_costmap:
+ inscribed_radius: 0.325
+ global_frame: /map
+ robot_base_frame: base_link
+ update_frequency: 5.0
+ publish_frequency: 0.0
+ static_map: true
+ rolling_window: false
Added: pkg/trunk/demos/2dnav_erratic/move_base/local_costmap_params.yaml
===================================================================
--- pkg/trunk/demos/2dnav_erratic/move_base/local_costmap_params.yaml (rev 0)
+++ pkg/trunk/demos/2dnav_erratic/move_base/local_costmap_params.yaml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -0,0 +1,13 @@
+local_costmap:
+ inscribed_radius: 0.325
+ global_frame: /map
+ robot_base_frame: base_link
+ update_frequency: 5.0
+ publish_frequency: 2.0
+ static_map: false
+ rolling_window: true
+ width: 6.0
+ height: 6.0
+ resolution: 0.025
+ origin_x: 0.0
+ origin_y: 0.0
Modified: pkg/trunk/demos/2dnav_erratic/move_base/move_base.launch
===================================================================
--- pkg/trunk/demos/2dnav_erratic/move_base/move_base.launch 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_erratic/move_base/move_base.launch 2009-06-19 01:34:11 UTC (rev 17338)
@@ -1,16 +1,15 @@
<launch>
<master auto="start"/>
- <group name="wg">
- <node pkg="move_base" type="move_base" respawn="false" name="move_base_node" output="screen">
- <remap from="/move_base_node/activate" to="/goal" />
- <remap from="~base_local_planner/global_plan" to="/gui_path" />
- <remap from="~base_local_planner/local_plan" to="/local_path" />
- <remap from="~base_local_planner/robot_footprint" to="/robot_footprint" />
+ <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
- <rosparam file="$(find 2dnav_erratic)/config/costmap_common_params.yaml" command="load" ns="navfn" />
- <rosparam file="$(find 2dnav_erratic)/config/costmap_common_params.yaml" command="load" ns="base_local_planner" />
- <rosparam file="$(find 2dnav_erratic)/move_base/navfn_params.yaml" command="load" />
- <rosparam file="$(find 2dnav_erratic)/move_base/base_local_planner_params.yaml" command="load" />
- </node>
- </group>
+ <param name="footprint_padding" value="0.01" />
+
+ <rosparam file="$(find 2dnav_erratic)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
+ <rosparam file="$(find 2dnav_erratic)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
+ <rosparam file="$(find 2dnav_erratic)/move_base/local_costmap_params.yaml" command="load" />
+ <rosparam file="$(find 2dnav_erratic)/move_base/global_costmap_params.yaml" command="load" />
+ <rosparam file="$(find 2dnav_erratic)/move_base/navfn_params.yaml" command="load" />
+ <rosparam file="$(find 2dnav_erratic)/move_base/base_local_planner_params.yaml" command="load" />
+
+ </node>
</launch>
Modified: pkg/trunk/demos/2dnav_erratic/move_base/navfn_params.yaml
===================================================================
--- pkg/trunk/demos/2dnav_erratic/move_base/navfn_params.yaml 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_erratic/move_base/navfn_params.yaml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -1,9 +1,2 @@
-navfn:
- #Independent settings for the planner's costmap
- costmap:
- global_frame: map
- robot_base_frame: base_link
- update_frequency: 5.0
- publish_frequency: 0.0
- static_map: true
- rolling_window: false
+NavfnROS:
+ transform_tolerance: 0.3
Modified: pkg/trunk/demos/2dnav_gazebo/2dnav-stack-amcl.launch
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/2dnav-stack-amcl.launch 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_gazebo/2dnav-stack-amcl.launch 2009-06-19 01:34:11 UTC (rev 17338)
@@ -8,5 +8,5 @@
<!--include file="$(find 2dnav_pr2)/config/map_server.launch" /-->
<include file="$(find 2dnav_pr2)/config/ground_plane.xml" />
<!-- The naviagtion stack and associated parameters -->
- <include file="$(find 2dnav_pr2)/move_base/move_base_voxel.xml" />
+ <include file="$(find 2dnav_pr2)/move_base/move_base.xml" />
</launch>
Modified: pkg/trunk/demos/2dnav_gazebo/2dnav-stack-fake_localization.launch
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/2dnav-stack-fake_localization.launch 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_gazebo/2dnav-stack-fake_localization.launch 2009-06-19 01:34:11 UTC (rev 17338)
@@ -8,5 +8,5 @@
<!--include file="$(find 2dnav_pr2)/config/map_server.launch" /-->
<include file="$(find 2dnav_pr2)/config/ground_plane.xml" />
<!-- The navigation stack and associated parameters -->
- <include file="$(find 2dnav_pr2)/move_base/move_base_voxel.xml" />
+ <include file="$(find 2dnav_pr2)/move_base/move_base.xml" />
</launch>
Modified: pkg/trunk/demos/2dnav_pr2/config/costmap_common_params.yaml
===================================================================
--- pkg/trunk/demos/2dnav_pr2/config/costmap_common_params.yaml 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_pr2/config/costmap_common_params.yaml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -1,21 +1,32 @@
-costmap:
- map_type: costmap
- transform_tolerance: 0.2
- obstacle_range: 2.5
- max_obstacle_height: 2.0
- raytrace_range: 3.0
- circumscribed_radius: 0.46
- inflation_radius: 0.55
- cost_scaling_factor: 10.0
- lethal_cost_threshold: 100
+#BEGIN VOXEL STUFF
+map_type: voxel
+origin_z: 0.0
+z_voxels: 6
+z_resolution: 0.23
+unknown_threshold: 7
+mark_threshold: 0
+#END VOXEL STUFF
+transform_tolerance: 0.2
+obstacle_range: 2.5
+raytrace_range: 3.0
+# inscribed_radius: 0.325
+circumscribed_radius: 0.46
+inflation_radius: 0.55
+cost_scaling_factor: 10.0
+lethal_cost_threshold: 100
- observation_topics: base_scan_marking base_scan ground_object_cloud
+# BEGIN VOXEL STUFF
+observation_topics: base_scan_marking base_scan tilt_scan ground_object_cloud
- base_scan_marking: {sensor_frame: base_laser, data_type: PointCloud, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: true, clearing: false, min_obstacle_height: 0.08, max_obstacle_height: 2.0}
+base_scan_marking: {sensor_frame: base_laser, data_type: PointCloud, expected_update_rate: 0.2,
+ observation_persistance: 0.0, marking: true, clearing: false, min_obstacle_height: 0.08, max_obstacle_height: 2.0}
- base_scan: {sensor_frame: base_laser, data_type: LaserScan, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: false, clearing: true, min_obstacle_height: -0.10, max_obstacle_height: 2.0}
+base_scan: {sensor_frame: base_laser, data_type: LaserScan, expected_update_rate: 0.2,
+ observation_persistance: 0.0, marking: false, clearing: true, min_obstacle_height: -0.10, max_obstacle_height: 2.0}
- ground_object_cloud: {sensor_frame: laser_tilt_link, data_type: PointCloud, expected_update_rate: 0.2,
- observation_persistance: 2.0, marking: true, clearing: false, min_obstacle_height: -0.10, max_obstacle_height: 2.0}
+tilt_scan: {sensor_frame: laser_tilt_link, data_type: LaserScan, expected_update_rate: 0.2,
+ observation_persistance: 0.2, marking: false, clearing: true, min_obstacle_height: -20.00, max_obstacle_height: 40.0}
+
+ground_object_cloud: {sensor_frame: laser_tilt_link, data_type: PointCloud, expected_update_rate: 0.2,
+ observation_persistance: 3.0, marking: true, clearing: false, min_obstacle_height: -0.10, max_obstacle_height: 2.0}
+# END VOXEL STUFF
Deleted: pkg/trunk/demos/2dnav_pr2/config/voxel_costmap_common_params.yaml
===================================================================
--- pkg/trunk/demos/2dnav_pr2/config/voxel_costmap_common_params.yaml 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_pr2/config/voxel_costmap_common_params.yaml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -1,33 +0,0 @@
-costmap:
- #BEGIN VOXEL STUFF
- map_type: voxel
- origin_z: 0.0
- z_voxels: 6
- z_resolution: 0.23
- unknown_threshold: 7
- mark_threshold: 0
- #END VOXEL STUFF
- transform_tolerance: 0.2
- obstacle_range: 2.5
- raytrace_range: 3.0
-# inscribed_radius: 0.325
- circumscribed_radius: 0.46
- inflation_radius: 0.55
- cost_scaling_factor: 10.0
- lethal_cost_threshold: 100
-
-# BEGIN VOXEL STUFF
- observation_topics: base_scan_marking base_scan tilt_scan ground_object_cloud
-
- base_scan_marking: {sensor_frame: base_laser, data_type: PointCloud, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: true, clearing: false, min_obstacle_height: 0.08, max_obstacle_height: 2.0}
-
- base_scan: {sensor_frame: base_laser, data_type: LaserScan, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: false, clearing: true, min_obstacle_height: -0.10, max_obstacle_height: 2.0}
-
- tilt_scan: {sensor_frame: laser_tilt_link, data_type: LaserScan, expected_update_rate: 0.2,
- observation_persistance: 0.2, marking: false, clearing: true, min_obstacle_height: -20.00, max_obstacle_height: 40.0}
-
- ground_object_cloud: {sensor_frame: laser_tilt_link, data_type: PointCloud, expected_update_rate: 0.2,
- observation_persistance: 2.5, marking: true, clearing: false, min_obstacle_height: -0.10, max_obstacle_height: 2.0}
-# END VOXEL STUFF
Modified: pkg/trunk/demos/2dnav_pr2/move_base/2dnav_pr2.launch
===================================================================
--- pkg/trunk/demos/2dnav_pr2/move_base/2dnav_pr2.launch 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_pr2/move_base/2dnav_pr2.launch 2009-06-19 01:34:11 UTC (rev 17338)
@@ -8,6 +8,6 @@
<include file="$(find 2dnav_pr2)/config/ground_plane.xml" />
<!-- The naviagtion stack and associated parameters -->
- <include file="$(find 2dnav_pr2)/move_base/move_base_voxel.xml" />
+ <include file="$(find 2dnav_pr2)/move_base/move_base.xml" />
</group>
</launch>
Modified: pkg/trunk/demos/2dnav_pr2/move_base/base_local_planner_params.yaml
===================================================================
--- pkg/trunk/demos/2dnav_pr2/move_base/base_local_planner_params.yaml 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_pr2/move_base/base_local_planner_params.yaml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -1,19 +1,4 @@
-base_local_planner:
- #Independent settings for the local costmap
- costmap:
- inscribed_radius: 0.325
- publish_voxel_map: true
- global_frame: odom_combined
- robot_base_frame: base_link
- update_frequency: 5.0
- publish_frequency: 2.0
- static_map: false
- rolling_window: true
- width: 6.0
- height: 6.0
- resolution: 0.025
- origin_x: 0.0
- origin_y: 0.0
+TrajectoryPlannerROS:
transform_tolerance: 0.2
costmap_visualization_rate: 0.0
world_model: costmap
@@ -27,8 +12,8 @@
max_vel_th: 1.0
min_vel_th: -1.0
min_in_place_vel_th: 0.4
- xy_goal_tolerance: 0.1
- yaw_goal_tolerance: 0.05
+ xy_goal_tolerance: 0.2
+ yaw_goal_tolerance: 0.17
goal_distance_bias: 0.8
path_distance_bias: 0.6
occdist_scale: 0.01
Deleted: pkg/trunk/demos/2dnav_pr2/move_base/base_local_planner_voxel_params.yaml
===================================================================
--- pkg/trunk/demos/2dnav_pr2/move_base/base_local_planner_voxel_params.yaml 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_pr2/move_base/base_local_planner_voxel_params.yaml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -1,45 +0,0 @@
-base_local_planner:
- #Independent settings for the local costmap
- costmap:
- inscribed_radius: 0.325
- publish_voxel_map: true
- global_frame: odom_combined
- robot_base_frame: base_link
- update_frequency: 5.0
- publish_frequency: 2.0
- static_map: false
- rolling_window: true
- width: 6.0
- height: 6.0
- resolution: 0.025
- origin_x: 0.0
- origin_y: 0.0
- transform_tolerance: 0.2
- costmap_visualization_rate: 0.0
- world_model: costmap
- sim_time: 1.7
- sim_granularity: 0.025
- dwa: true
- vx_samples: 3
- vtheta_samples: 20
- max_vel_x: 0.45
- min_vel_x: 0.1
- max_vel_th: 1.0
- min_vel_th: -1.0
- min_in_place_vel_th: 0.4
- xy_goal_tolerance: 0.2
- yaw_goal_tolerance: 0.17
- goal_distance_bias: 0.8
- path_distance_bias: 0.6
- occdist_scale: 0.01
- heading_lookahead: 0.325
- oscillation_reset_dist: 0.05
- escape_reset_dist: 0.15
- escape_reset_theta: 0.30
- acc_limit_th: 3.2
- acc_limit_x: 2.5
- acc_limit_y: 2.5
- heading_scoring: false
- heading_scoring_timestep: 0.8
- holonomic_robot: true
- simple_attractor: false
Added: pkg/trunk/demos/2dnav_pr2/move_base/global_costmap_params.yaml
===================================================================
--- pkg/trunk/demos/2dnav_pr2/move_base/global_costmap_params.yaml (rev 0)
+++ pkg/trunk/demos/2dnav_pr2/move_base/global_costmap_params.yaml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -0,0 +1,9 @@
+#Independent settings for the planner's costmap
+global_costmap:
+ inscribed_radius: 0.325
+ global_frame: /map
+ robot_base_frame: base_link
+ update_frequency: 5.0
+ publish_frequency: 0.0
+ static_map: true
+ rolling_window: false
Added: pkg/trunk/demos/2dnav_pr2/move_base/local_costmap_params.yaml
===================================================================
--- pkg/trunk/demos/2dnav_pr2/move_base/local_costmap_params.yaml (rev 0)
+++ pkg/trunk/demos/2dnav_pr2/move_base/local_costmap_params.yaml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -0,0 +1,15 @@
+local_costmap:
+ #Independent settings for the local costmap
+ inscribed_radius: 0.325
+ publish_voxel_map: true
+ global_frame: odom_combined
+ robot_base_frame: base_link
+ update_frequency: 5.0
+ publish_frequency: 2.0
+ static_map: false
+ rolling_window: true
+ width: 6.0
+ height: 6.0
+ resolution: 0.025
+ origin_x: 0.0
+ origin_y: 0.0
Modified: pkg/trunk/demos/2dnav_pr2/move_base/move_base.xml
===================================================================
--- pkg/trunk/demos/2dnav_pr2/move_base/move_base.xml 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_pr2/move_base/move_base.xml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -1,6 +1,7 @@
<launch>
<include file="$(find pr2_alpha)/$(env ROBOT).machine" />
+<node pkg="mux" type="throttle" args="3.0 /move_base/local_costmap/voxel_grid /move_base/local_costmap/voxel_grid_throttled" />
<node pkg="move_base" type="move_base" respawn="true" name="move_base" output="screen" machine="three">
<!--
<remap from="cmd_vel" to="/bs" />
@@ -10,8 +11,10 @@
<param name="controller_patience" value="15.0" />
<param name="clearing_radius" value="0.59" />
- <rosparam file="$(find 2dnav_pr2)/config/costmap_common_params.yaml" command="load" ns="navfn" />
- <rosparam file="$(find 2dnav_pr2)/config/costmap_common_params.yaml" command="load" ns="base_local_planner" />
+ <rosparam file="$(find 2dnav_pr2)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
+ <rosparam file="$(find 2dnav_pr2)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
+ <rosparam file="$(find 2dnav_pr2)/move_base/local_costmap_params.yaml" command="load" />
+ <rosparam file="$(find 2dnav_pr2)/move_base/global_costmap_params.yaml" command="load" />
<rosparam file="$(find 2dnav_pr2)/move_base/navfn_params.yaml" command="load" />
<rosparam file="$(find 2dnav_pr2)/move_base/base_local_planner_params.yaml" command="load" />
</node>
Deleted: pkg/trunk/demos/2dnav_pr2/move_base/move_base_voxel.xml
===================================================================
--- pkg/trunk/demos/2dnav_pr2/move_base/move_base_voxel.xml 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_pr2/move_base/move_base_voxel.xml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -1,20 +0,0 @@
-<launch>
-<include file="$(find pr2_alpha)/$(env ROBOT).machine" />
-
-<node pkg="mux" type="throttle" args="3.0 /move_base/base_local_planner/costmap/voxel_grid /move_base/base_local_planner/costmap/voxel_grid_throttled" />
-<node pkg="move_base" type="move_base" respawn="true" name="move_base" output="screen" machine="three">
- <!--
- <remap from="cmd_vel" to="/bs" />
- -->
- <param name="controller_frequency" value="10.0" />
- <param name="controller_patience" value="15.0" />
- <param name="planner_patience" value="5.0" />
- <param name="footprint_padding" value="0.015" />
- <param name="clearing_radius" value="0.59" />
-
- <rosparam file="$(find 2dnav_pr2)/config/voxel_costmap_common_params.yaml" command="load" ns="navfn" />
- <rosparam file="$(find 2dnav_pr2)/config/voxel_costmap_common_params.yaml" command="load" ns="base_local_planner" />
- <rosparam file="$(find 2dnav_pr2)/move_base/navfn_params.yaml" command="load" />
- <rosparam file="$(find 2dnav_pr2)/move_base/base_local_planner_voxel_params.yaml" command="load" />
-</node>
-</launch>
Modified: pkg/trunk/demos/2dnav_pr2/move_base/navfn_params.yaml
===================================================================
--- pkg/trunk/demos/2dnav_pr2/move_base/navfn_params.yaml 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_pr2/move_base/navfn_params.yaml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -1,12 +1,2 @@
navfn:
transform_tolerance: 0.2
- #Independent settings for the planner's costmap
- costmap:
-#inscribed_radius: 0.387
- inscribed_radius: 0.325
- global_frame: /map
- robot_base_frame: base_link
- update_frequency: 5.0
- publish_frequency: 0.0
- static_map: true
- rolling_window: false
Modified: pkg/trunk/demos/2dnav_pr2/move_base_local/base_local_planner_params.yaml
===================================================================
--- pkg/trunk/demos/2dnav_pr2/move_base_local/base_local_planner_params.yaml 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_pr2/move_base_local/base_local_planner_params.yaml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -1,18 +1,6 @@
-base_local_planner:
- costmap:
- inscribed_radius: 0.325
- publish_voxel_map: true
- global_frame: odom_combined
- robot_base_frame: base_link
- update_frequency: 5.0
- publish_frequency: 2.0
- static_map: false
- rolling_window: true
- width: 10.0
- height: 10.0
- resolution: 0.025
- origin_x: 0.0
- origin_y: 0.0
+footprint: [[-0.325, -0.325], [-0.325, 0.325], [0.325, 0.325], [0.325, -0.325]]
+shutdown_costmaps: true
+TrajectoryPlannerROS:
transform_tolerance: 0.2
costmap_visualization_rate: 0.0
world_model: costmap
Added: pkg/trunk/demos/2dnav_pr2/move_base_local/costmap_params.yaml
===================================================================
--- pkg/trunk/demos/2dnav_pr2/move_base_local/costmap_params.yaml (rev 0)
+++ pkg/trunk/demos/2dnav_pr2/move_base_local/costmap_params.yaml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -0,0 +1,13 @@
+inscribed_radius: 0.325
+publish_voxel_map: true
+global_frame: odom_combined
+robot_base_frame: base_link
+update_frequency: 5.0
+publish_frequency: 2.0
+static_map: false
+rolling_window: true
+width: 10.0
+height: 10.0
+resolution: 0.025
+origin_x: 0.0
+origin_y: 0.0
Modified: pkg/trunk/demos/2dnav_pr2/move_base_local/move_base_local.xml
===================================================================
--- pkg/trunk/demos/2dnav_pr2/move_base_local/move_base_local.xml 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_pr2/move_base_local/move_base_local.xml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -1,10 +1,14 @@
<launch>
<include file="$(find pr2_alpha)/$(env ROBOT).machine" />
-<node pkg="move_base" type="move_base_local" respawn="false" name="move_base_local" output="screen" machine="three">
+<node pkg="mux" type="throttle" args="3.0 /move_base_local/local_costmap/voxel_grid /move_base_local/local_costmap/voxel_grid_throttled" />
+<node pkg="move_base" type="move_base" respawn="false" name="move_base_local" output="screen" machine="three">
<param name="controller_frequency" value="10.0" />
- <rosparam file="$(find 2dnav_pr2)/config/costmap_common_params.yaml" command="load" ns="base_local_planner" />
+ <rosparam file="$(find 2dnav_pr2)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
+ <rosparam file="$(find 2dnav_pr2)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
+ <rosparam file="$(find 2dnav_pr2)/move_base_local/costmap_params.yaml" command="load" ns="global_costmap" />
+ <rosparam file="$(find 2dnav_pr2)/move_base_local/costmap_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find 2dnav_pr2)/move_base_local/base_local_planner_params.yaml" command="load" />
</node>
</launch>
Deleted: pkg/trunk/demos/2dnav_pr2/move_base_local/move_base_local_voxel.xml
===================================================================
--- pkg/trunk/demos/2dnav_pr2/move_base_local/move_base_local_voxel.xml 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_pr2/move_base_local/move_base_local_voxel.xml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -1,11 +0,0 @@
-<launch>
-<include file="$(find pr2_alpha)/$(env ROBOT).machine" />
-
-<node pkg="mux" type="throttle" args="3.0 /move_base_local/base_local_planner/costmap/voxel_grid /move_base_local/base_local_planner/costmap/voxel_grid_throttled" />
-<node pkg="move_base" type="move_base_local" respawn="false" name="move_base_local" output="screen" machine="three">
- <param name="controller_frequency" value="10.0" />
-
- <rosparam file="$(find 2dnav_pr2)/config/costmap_common_params.yaml" command="load" ns="base_local_planner" />
- <rosparam file="$(find 2dnav_pr2)/move_base_local/base_local_planner_params.yaml" command="load" />
-</node>
-</launch>
Modified: pkg/trunk/demos/2dnav_pr2/nav_view/nav_view_move_base.launch
===================================================================
--- pkg/trunk/demos/2dnav_pr2/nav_view/nav_view_move_base.launch 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_pr2/nav_view/nav_view_move_base.launch 2009-06-19 01:34:11 UTC (rev 17338)
@@ -2,10 +2,10 @@
<master auto="start"/>
<node pkg="nav_view" type="nav_view" respawn="false">
<remap from="goal" to="/move_base/activate" />
- <remap from="raw_obstacles" to="/move_base/base_local_planner/costmap/raw_obstacles" />
- <remap from="inflated_obstacles" to="/move_base/base_local_planner/costmap/inflated_obstacles" />
- <remap from="gui_path" to="/move_base/navfn/plan" />
- <remap from="local_path" to="/move_base/base_local_planner/local_plan" />
- <remap from="robot_footprint" to="/move_base/base_local_planner/robot_footprint"/>
+ <remap from="raw_obstacles" to="/move_base/local_costmap/raw_obstacles" />
+ <remap from="inflated_obstacles" to="/move_base/local_costmap/inflated_obstacles" />
+ <remap from="gui_path" to="/move_base/NavfnROS/plan" />
+ <remap from="local_path" to="/move_base/TrajectoryPlannerROS/local_plan" />
+ <remap from="robot_footprint" to="/move_base/TrajectoryPlannerROS/robot_footprint"/>
</node>
</launch>
Modified: pkg/trunk/demos/2dnav_pr2/nav_view/nav_view_move_base_local.launch
===================================================================
--- pkg/trunk/demos/2dnav_pr2/nav_view/nav_view_move_base_local.launch 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_pr2/nav_view/nav_view_move_base_local.launch 2009-06-19 01:34:11 UTC (rev 17338)
@@ -2,10 +2,10 @@
<master auto="start"/>
<node pkg="nav_view" type="nav_view" respawn="false">
<remap from="goal" to="/move_base_local/activate" />
- <remap from="raw_obstacles" to="/move_base_local/base_local_planner/costmap/raw_obstacles" />
- <remap from="inflated_obstacles" to="/move_base_local/base_local_planner/costmap/inflated_obstacles" />
- <remap from="gui_path" to="/move_base_local/navfn/plan" />
- <remap from="local_path" to="/move_base_local/base_local_planner/local_plan" />
- <remap from="robot_footprint" to="/move_base_local/base_local_planner/robot_footprint"/>
+ <remap from="raw_obstacles" to="/move_base_local/local_costmap/raw_obstacles" />
+ <remap from="inflated_obstacles" to="/move_base_local/local_costmap/inflated_obstacles" />
+ <remap from="gui_path" to="/move_base_local/NavfnROS/plan" />
+ <remap from="local_path" to="/move_base_local/TrajectoryPlannerROS/local_plan" />
+ <remap from="robot_footprint" to="/move_base_local/TrajectoryPlannerROS/robot_footprint"/>
</node>
</launch>
Modified: pkg/trunk/demos/2dnav_pr2/rviz/move_base.vcg
===================================================================
--- pkg/trunk/demos/2dnav_pr2/rviz/move_base.vcg 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_pr2/rviz/move_base.vcg 2009-06-19 01:34:11 UTC (rev 17338)
@@ -31,11 +31,11 @@
FilteredTiltCloud.Max\ ColorR=0.980392
FilteredTiltCloud.Max\ ColorG=0.721569
FilteredTiltCloud.Max\ ColorB=0.235294
-FilteredTiltCloud.Max\ Intensity=2533
+FilteredTiltCloud.Max\ Intensity=2000.01
FilteredTiltCloud.Min\ ColorR=0.988235
FilteredTiltCloud.Min\ ColorG=0.643137
FilteredTiltCloud.Min\ ColorB=0.156863
-FilteredTiltCloud.Min\ Intensity=0
+FilteredTiltCloud.Min\ Intensity=1999.99
FilteredTiltCloud.Selectable=1
FilteredTiltCloud.Style=1
FilteredTiltCloud.Topic=/tilt_scan_filtered
@@ -64,7 +64,7 @@
Global\ Plan.Loop=0
Global\ Plan.Override\ Color=0
Global\ Plan.Render\ Operation=0
-Global\ Plan.Topic=/move_base/base_local_planner/global_plan
+Global\ Plan.Topic=/move_base/TrajectoryPlannerROS/global_plan
Global\ Plan.Z\ Position=0
Grid.Alpha=0.5
Grid.Cell\ Size=1
@@ -105,7 +105,7 @@
Inflated\ Obstacles.Loop=0
Inflated\ Obstacles.Override\ Color=0
Inflated\ Obstacles.Render\ Operation=1
-Inflated\ Obstacles.Topic=/move_base/base_local_planner/costmap/inflated_obstacles
+Inflated\ Obstacles.Topic=/move_base/local_costmap/inflated_obstacles
Inflated\ Obstacles.Z\ Position=0
Local\ Plan.Alpha=1
Local\ Plan.ColorR=0.1
@@ -115,7 +115,7 @@
Local\ Plan.Loop=0
Local\ Plan.Override\ Color=0
Local\ Plan.Render\ Operation=0
-Local\ Plan.Topic=/move_base/base_local_planner/local_plan
+Local\ Plan.Topic=/move_base/TrajectoryPlannerROS/local_plan
Local\ Plan.Z\ Position=0
Map.Alpha=0.7
Map.Enabled=1
@@ -149,7 +149,7 @@
Planner\ Plan.Loop=0
Planner\ Plan.Override\ Color=1
Planner\ Plan.Render\ Operation=0
-Planner\ Plan.Topic=/move_base/navfn/plan
+Planner\ Plan.Topic=/move_base/NavfnROS/plan
Planner\ Plan.Z\ Position=0
Raw\ Obstacles.Alpha=1
Raw\ Obstacles.ColorR=0.1
@@ -159,7 +159,7 @@
Raw\ Obstacles.Loop=0
Raw\ Obstacles.Override\ Color=0
Raw\ Obstacles.Render\ Operation=1
-Raw\ Obstacles.Topic=/move_base/base_local_planner/costmap/raw_obstacles
+Raw\ Obstacles.Topic=/move_base/local_costmap/raw_obstacles
Raw\ Obstacles.Z\ Position=0
Robot\ Footprint.Alpha=1
Robot\ Footprint.ColorR=0.1
@@ -169,7 +169,7 @@
Robot\ Footprint.Loop=0
Robot\ Footprint.Override\ Color=0
Robot\ Footprint.Render\ Operation=0
-Robot\ Footprint.Topic=/move_base/base_local_planner/robot_footprint
+Robot\ Footprint.Topic=/move_base/TrajectoryPlannerROS/robot_footprint
Robot\ Footprint.Z\ Position=0
Robot\ Model.Alpha=0.5
Robot\ Model.Collision\ Enabled=0
@@ -315,8 +315,8 @@
Transforms.Update\ Rate=1
Visualization\ Markers.Enabled=1
Camera\ Type=Orbit
-Camera\ Config=0.260797 1.8658 59.4391 -20.4919 1.74112 -13.0454
-Property\ Grid\ State=selection=Target Frame;expanded=.Global Options,Visualization Markers,Robot Model,Map,Head Scan,Floor Scan,Transforms.Frames,Transforms.Tree,FilteredTiltCloud,New Ground Plane Cloud,AMCL Cloud,Raw Obstacles,Robot Footprint,Local Plan,Global Plan,Inflated Obstacles,Planner Plan;scrollpos=0,0;splitterpos=248,483;ispageselected=1
+Camera\ Config=0.510797 1.5408 17.9393 -25.91 2.90947 -25.9677
+Property\ Grid\ State=selection=FilteredTiltCloud.Enabled;expanded=.Global Options,Visualization Markers,Robot Model,Map,Head Scan,Floor Scan,Transforms.Frames,Transforms.Tree,FilteredTiltCloud,New Ground Plane Cloud,AMCL Cloud,Raw Obstacles,Inflated Obstacles,Robot Footprint,Local Plan,Global Plan,Planner Plan;scrollpos=0,88;splitterpos=248,483;ispageselected=1
[Display0]
Type=Grid
Name=Grid
@@ -364,16 +364,16 @@
Name=Raw Obstacles
[Display15]
Type=PolyLine
-Name=Robot Footprint
+Name=Inflated Obstacles
[Display16]
Type=PolyLine
-Name=Local Plan
+Name=Robot Footprint
[Display17]
Type=PolyLine
-Name=Global Plan
+Name=Local Plan
[Display18]
Type=PolyLine
-Name=Inflated Obstacles
+Name=Global Plan
[Display19]
Type=PolyLine
Name=Planner Plan
Modified: pkg/trunk/demos/2dnav_pr2/rviz/move_base_local.vcg
===================================================================
--- pkg/trunk/demos/2dnav_pr2/rviz/move_base_local.vcg 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_pr2/rviz/move_base_local.vcg 2009-06-19 01:34:11 UTC (rev 17338)
@@ -64,7 +64,7 @@
Global\ Plan.Loop=0
Global\ Plan.Override\ Color=0
Global\ Plan.Render\ Operation=0
-Global\ Plan.Topic=/move_base_local/base_local_planner/global_plan
+Global\ Plan.Topic=/move_base_local/TrajectoryPlannerROS/global_plan
Global\ Plan.Z\ Position=0
Grid.Alpha=0.5
Grid.Cell\ Size=1
@@ -89,7 +89,7 @@
Head\ Scan.Max\ ColorR=1
Head\ Scan.Max\ ColorG=0
Head\ Scan.Max\ ColorB=0.901961
-Head\ Scan.Max\ Intensity=2000.02
+Head\ Scan.Max\ Intensity=2000.01
Head\ Scan.Min\ ColorR=0.972549
Head\ Scan.Min\ ColorG=0
Head\ Scan.Min\ ColorB=0.870588
@@ -105,7 +105,7 @@
Inflated\ Obstacles.Loop=0
Inflated\ Obstacles.Override\ Color=0
Inflated\ Obstacles.Render\ Operation=1
-Inflated\ Obstacles.Topic=/move_base_local/base_local_planner/costmap/inflated_obstacles
+Inflated\ Obstacles.Topic=/move_base_local/local_costmap/inflated_obstacles
Inflated\ Obstacles.Z\ Position=0
Local\ Plan.Alpha=1
Local\ Plan.ColorR=0.1
@@ -115,7 +115,7 @@
Local\ Plan.Loop=0
Local\ Plan.Override\ Color=0
Local\ Plan.Render\ Operation=0
-Local\ Plan.Topic=/move_base_local/base_local_planner/local_plan
+Local\ Plan.Topic=/move_base_local/TrajectoryPlannerROS/local_plan
Local\ Plan.Z\ Position=0
Map.Alpha=0.7
Map.Enabled=1
@@ -149,7 +149,7 @@
Planner\ Plan.Loop=0
Planner\ Plan.Override\ Color=0
Planner\ Plan.Render\ Operation=0
-Planner\ Plan.Topic=/move_base_local/navfn/plan
+Planner\ Plan.Topic=/move_base_local/NavfnROS/plan
Planner\ Plan.Z\ Position=0
Raw\ Obstacles.Alpha=1
Raw\ Obstacles.ColorR=0.1
@@ -159,7 +159,7 @@
Raw\ Obstacles.Loop=0
Raw\ Obstacles.Override\ Color=0
Raw\ Obstacles.Render\ Operation=1
-Raw\ Obstacles.Topic=/move_base_local/base_local_planner/costmap/raw_obstacles
+Raw\ Obstacles.Topic=/move_base_local/local_costmap/raw_obstacles
Raw\ Obstacles.Z\ Position=0
Robot\ Footprint.Alpha=1
Robot\ Footprint.ColorR=0.1
@@ -169,7 +169,7 @@
Robot\ Footprint.Loop=0
Robot\ Footprint.Override\ Color=0
Robot\ Footprint.Render\ Operation=0
-Robot\ Footprint.Topic=/move_base_local/base_local_planner/robot_footprint
+Robot\ Footprint.Topic=/move_base_local/TrajectoryPlannerROS/robot_footprint
Robot\ Footprint.Z\ Position=0
Robot\ Model.Alpha=1
Robot\ Model.Collision\ Enabled=0
@@ -313,10 +313,10 @@
Transforms.Show\ Axes=1
Transforms.Show\ Names=1
Transforms.Update\ Rate=1
-Visualization\ Markers.Enabled=0
+Visualization\ Markers.Enabled=1
Camera\ Type=Orbit
-Camera\ Config=0.455797 1.7058 40.3208 0 0 0
-Property\ Grid\ State=selection=Target Frame;expanded=.Global Options,Visualization Markers,Robot Model,Map,Head Scan,Floor Scan,Transforms.Frames,Transforms.Tree,FilteredTiltCloud,New Ground Plane Cloud,AMCL Cloud,Raw Obstacles,Robot Footprint,Local Plan,Global Plan,Inflated Obstacles,Planner Plan;scrollpos=0,0;splitterpos=248,483;ispageselected=1
+Camera\ Config=0.936 1.7208 12.0025 0 0 0
+Property\ Grid\ State=selection=Visualization Markers.Enabled;expanded=.Global Options,Visualization Markers,Robot Model,Map,Head Scan,Floor Scan,Transforms.Frames,Transforms.Tree,FilteredTiltCloud,New Ground Plane Cloud,AMCL Cloud,Raw Obstacles,Inflated Obstacles,Robot Footprint,Local Plan,Global Plan,Planner Plan;scrollpos=0,0;splitterpos=248,483;ispageselected=1
[Display0]
Type=Grid
Name=Grid
@@ -364,16 +364,16 @@
Name=Raw Obstacles
[Display15]
Type=PolyLine
-Name=Robot Footprint
+Name=Inflated Obstacles
[Display16]
Type=PolyLine
-Name=Local Plan
+Name=Robot Footprint
[Display17]
Type=PolyLine
-Name=Global Plan
+Name=Local Plan
[Display18]
Type=PolyLine
-Name=Inflated Obstacles
+Name=Global Plan
[Display19]
Type=PolyLine
Name=Planner Plan
Modified: pkg/trunk/demos/2dnav_pr2/rviz/rviz_move_base.launch
===================================================================
--- pkg/trunk/demos/2dnav_pr2/rviz/rviz_move_base.launch 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_pr2/rviz/rviz_move_base.launch 2009-06-19 01:34:11 UTC (rev 17338)
@@ -3,6 +3,6 @@
<remap from="goal" to="/move_base/activate" />
</node>
<node pkg="costmap_2d" type="costmap_2d_markers" name="voxel_visualizer">
- <remap from="voxel_grid" to="/move_base/base_local_planner/costmap/voxel_grid_throttled"/>
+ <remap from="voxel_grid" to="/move_base/local_costmap/voxel_grid_throttled"/>
</node>
</launch>
Modified: pkg/trunk/demos/2dnav_pr2/rviz/rviz_move_base_local.launch
===================================================================
--- pkg/trunk/demos/2dnav_pr2/rviz/rviz_move_base_local.launch 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/2dnav_pr2/rviz/rviz_move_base_local.launch 2009-06-19 01:34:11 UTC (rev 17338)
@@ -3,6 +3,6 @@
<remap from="goal" to="/move_base_local/activate" />
</node>
<node pkg="costmap_2d" type="costmap_2d_markers" name="voxel_visualizer">
- <remap from="voxel_grid" to="/move_base_local/base_local_planner/costmap/voxel_grid_throttled"/>
+ <remap from="voxel_grid" to="/move_base_local/local_costmap/voxel_grid_throttled"/>
</node>
</launch>
Modified: pkg/trunk/demos/milestone2/milestone2_actions/config/navigation.xml
===================================================================
--- pkg/trunk/demos/milestone2/milestone2_actions/config/navigation.xml 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/demos/milestone2/milestone2_actions/config/navigation.xml 2009-06-19 01:34:11 UTC (rev 17338)
@@ -10,11 +10,11 @@
<node pkg="pr2_mechanism_controllers" type="base_trajectory_controller"/>
<!-- Local navigation in odom_combined -->
- <include file="$(find 2dnav_pr2)/move_base_local/move_base_local_voxel.xml" />
+ <include file="$(find 2dnav_pr2)/move_base_local/move_base_local.xml" />
<!-- Navstack in map-->
<include file="$(find 2dnav_pr2)/config/new_amcl_node.xml" />
<!-- <include file="$(find 2dnav_pr2)/config/amcl_node.xml" />-->
<include file="$(find 2dnav_pr2)/config/map_server.xml" />
- <include file="$(find 2dnav_pr2)/move_base/move_base_voxel.xml" />
+ <include file="$(find 2dnav_pr2)/move_base/move_base.xml" />
</launch>
Modified: pkg/trunk/highlevel/doors/doors_core/src/move_base_door_action.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/src/move_base_door_action.cpp 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/highlevel/doors/doors_core/src/move_base_door_action.cpp 2009-06-19 01:34:11 UTC (rev 17338)
@@ -90,7 +90,7 @@
if(!ros_node_.hasParam("~costmap/robot_base_frame")) ros_node_.setParam("~costmap/robot_base_frame", std::string("base_link"));
//create the ros wrapper for the planner's costmap... and initializer a pointer we'll use with the underlying map
- planner_cost_map_ros_ = new Costmap2DROS(ros_node_, tf_, "");
+ planner_cost_map_ros_ = new Costmap2DROS("costmap", tf_);
planner_cost_map_ros_->getCostmapCopy(planner_cost_map_);
//we'll stop our costmap from running until we are activated
Modified: pkg/trunk/highlevel/move_base/CMakeLists.txt
===================================================================
--- pkg/trunk/highlevel/move_base/CMakeLists.txt 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/highlevel/move_base/CMakeLists.txt 2009-06-19 01:34:11 UTC (rev 17338)
@@ -14,6 +14,3 @@
# move_base
rospack_add_executable(bin/move_base src/move_base.cpp)
-
-#local controller
-rospack_add_executable(bin/move_base_local src/move_base_local.cpp)
Modified: pkg/trunk/highlevel/move_base/include/move_base/move_base.h
===================================================================
--- pkg/trunk/highlevel/move_base/include/move_base/move_base.h 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/highlevel/move_base/include/move_base/move_base.h 2009-06-19 01:34:11 UTC (rev 17338)
@@ -61,10 +61,10 @@
public:
/**
* @brief Constructor for the actions
- * @param ros_node A reference to the ros node used
+ * @param name The name of the action
* @param tf A reference to a TransformListener
*/
- MoveBase(ros::Node& ros_node, tf::TransformListener& tf);
+ MoveBase(std::string name, tf::TransformListener& tf);
/**
* @brief Destructor - Cleans up
@@ -118,14 +118,13 @@
bool tryPlan(robot_msgs::PoseStamped goal);
- ros::Node& ros_node_;
+ ros::NodeHandle ros_node_;
tf::TransformListener& tf_;
nav_robot_actions::BaseLocalPlanner* tc_;
costmap_2d::Costmap2DROS* planner_costmap_ros_, *controller_costmap_ros_;
nav_robot_actions::BaseGlobalPlanner* planner_;
std::vector<robot_msgs::PoseStamped> global_plan_;
- std::vector<robot_msgs::Point> footprint_;
std::string robot_base_frame_, global_frame_;
bool valid_plan_, new_plan_;
boost::recursive_mutex lock_;
@@ -137,6 +136,8 @@
bool done_half_rotation_, done_full_rotation_;
bool escaping_;
ros::Time last_valid_control_;
+ ros::Publisher vis_pub_, vel_pub_;
+ bool shutdown_costmaps_;
};
};
Deleted: pkg/trunk/highlevel/move_base/include/move_base/move_base_local.h
===================================================================
--- pkg/trunk/highlevel/move_base/include/move_base/move_base_local.h 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/highlevel/move_base/include/move_base/move_base_local.h 2009-06-19 01:34:11 UTC (rev 17338)
@@ -1,116 +0,0 @@
-/*********************************************************************
-*
-* Software License Agreement (BSD License)
-*
-* Copyright (c) 2008, Willow Garage, Inc.
-* All rights reserved.
-*
-* Redistribution and use in source and binary forms, with or without
-* modification, are permitted provided that the following conditions
-* are met:
-*
-* * Redistributions of source code must retain the above copyright
-* notice, this list of conditions and the following disclaimer.
-* * Redistributions in binary form must reproduce the above
-* copyright notice, this list of conditions and the following
-* disclaimer in the documentation and/or other materials provided
-* with the distribution.
-* * Neither the name of the Willow Garage nor the names of its
-* contributors may be used to endorse or promote products derived
-* from this software without specific prior written permission.
-*
-* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
-* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-* POSSIBILITY OF SUCH DAMAGE.
-*
-* Author: Eitan Marder-Eppstein
-*********************************************************************/
-#ifndef NAV_MOVE_BASE_ACTION_H_
-#define NAV_MOVE_BASE_ACTION_H_
-#include <robot_actions/action.h>
-#include <robot_actions/action_runner.h>
-#include <nav_robot_actions/MoveBaseState.h>
-#include <robot_msgs/PoseStamped.h>
-#include <ros/node.h>
-#include <costmap_2d/costmap_2d_ros.h>
-#include <costmap_2d/costmap_2d.h>
-#include <base_local_planner/trajectory_planner_ros.h>
-#include <vector>
-#include <string>
-#include <visualization_msgs/Marker.h>
-
-namespace move_base {
- /**
- * @class MoveBaseLocal
- * @brief A class adhering to the robot_actions::Action interface that moves the robot base to a goal location.
- */
- class MoveBaseLocal : public robot_actions::Action<robot_msgs::PoseStamped, robot_msgs::PoseStamped> {
- public:
- /**
- * @brief Constructor for the actions
- * @param ros_node A reference to the ros node used
- * @param tf A reference to a TransformListener
- * @return
- */
- MoveBaseLocal(ros::Node& ros_node, tf::TransformListener& tf);
-
- /**
- * @brief Destructor - Cleans up
- */
- virtual ~MoveBaseLocal();
-
- /**
- * @brief Runs whenever a new goal is sent to the move_base
- * @param goal The goal to pursue
- * @param feedback Feedback that the action gives to a higher-level monitor, in this case, the position of the robot
- * @return The result of the execution, ie: Success, Preempted, Aborted, etc.
- */
- virtual robot_actions::ResultStatus execute(const robot_msgs::PoseStamped& goal, robot_msgs::PoseStamped& feedback);
-
- /**
- * @brief Publish a goal to the visualizer
- * @param goal The goal to visualize
- */
- void publishGoal(const robot_msgs::PoseStamped& goal);
-
- private:
- /**
- * @brief Get the current pose of the robot in the specified frame
- * @param frame The frame to get the pose in
- * @param pose The pose returned
- */
- void getRobotPose(std::string frame, tf::Stamped<tf::Pose>& pose);
-
- /**
- * @brief Resets the costmaps to the static map outside a given window
- */
- void resetCostmaps();
- ros::Node& ros_node_;
- tf::TransformListener& tf_;
-
- base_local_planner::TrajectoryPlannerROS* tc_;
- costmap_2d::Costmap2DROS* controller_costmap_ros_;
- costmap_2d::Costmap2D controller_costmap_;
-
- std::vector<robot_msgs::Point> footprint_;
- std::string robot_base_frame_;
-
- double controller_frequency_;
-
- std::string action_name_;
- ros::Duration controller_patience_;
- double circumscribed_radius_;
-
- };
-};
-#endif
-
Modified: pkg/trunk/highlevel/move_base/src/move_base.cpp
===================================================================
--- pkg/trunk/highlevel/move_base/src/move_base.cpp 2009-06-19 01:31:33 UTC (rev 17337)
+++ pkg/trunk/highlevel/move_base/src/move_base.cpp 2009-06-19 01:34:11 UTC (rev 17338)
@@ -43,12 +43,8 @@
namespace move_base {
- double sign(double x){
- return x < 0.0 ? -1.0 : 1.0;
- }
-
- MoveBase::MoveBase(ros::Node& ros_node, tf::TransformListener& tf) :
- Action<robot_msgs::PoseStamped, robot_msgs::PoseStamped>(ros_node.getName()), ros_node_(ros_node), tf_(tf),
+ MoveBase::MoveBase(std::string name, tf::TransformListener& tf) :
+ Action<robot_msgs::PoseStamped, robot_msgs::PoseStamped>(name), tf_(tf),
tc_(NULL), planner_costmap_ros_(NULL), controller_costmap_ros_(NULL),
planner_(NULL), valid_plan_(false), new_plan_(false), attempted_rotation_(false), attempted_costmap_reset_(false),
done_half_rotation_(false), done_full_rotation_(false), escaping_(false) {
@@ -57,78 +53,29 @@
std::string global_planner, local_planner;
ros_node_.param("~base_global_planner", global_planner, std::string("NavfnROS"));
ros_node_.param("~base_local_planner", local_planner, std::string("TrajectoryPlannerROS"));
- ros_node_.param("~navfn/costmap/robot_base_frame", robot_base_frame_, std::string("base_link"));
- ros_node_.param("~navfn/costmap/global_frame", global_frame_, std::string("/map"));
+ ros_node_.param("~global_costmap/robot_base_frame", robot_base_frame_, std::string("base_link"));
+ ros_node_.param("~global_costmap/global_frame", global_frame_, std::string("/map"));
ros_node_.param("~controller_frequency", controller_frequency_, 20.0);
ros_node_.param("~planner_patience", planner_patience_, 5.0);
ros_node_.param("~controller_patience", controller_patience_, 15.0);
//for comanding the base
- ros_node_.advertise<robot_msgs::PoseDot>("cmd_vel", 1);
- ros_node_.advertise<visualization_msgs::Marker>( "visualization_marker", 0 );
+ vel_pub_ = ros_node_.advertise<robot_msgs::PoseDot>("cmd_vel", 1);
+ vis_pub_ = ros_node_.advertise<visualization_msgs::Marker>( "visualization_marker", 0 );
//we'll assume the radius of the robot to be consistent with what's specified for the costmaps
- ros_node_.param("~base_local_planner/costmap/inscribed_radius", inscribed_radius_, 0.325);
- ros_node_.param("~base_local_planner/costmap/circumscribed_radius", circumscribed_radius_, 0.46);
+ ros_node_.param("~local_costmap/inscribed_radius", inscribed_radius_, 0.325);
+ ros_node_.param("~local_costmap/circumscribed_radius", circumscribed_radius_, 0.46);
ros_node_.param("~clearing_radius", clearing_radius_, circumscribed_radius_);
- robot_msgs::Point pt;
- double padding;
- ros_node_.param("~footprint_padding", padding, 0.01);
+ ros_node_.param("~shutdown_costmaps", shutdown_costmaps_, false);
- //grab the footprint from the parameter server if possible
- XmlRpc::XmlRpcValue footprint_list;
- if(ros_node_.getParam("~footprint", footprint_list)){
- //make sure we have a list of lists
- ROS_ASSERT_MSG(footprint_list.getType() == XmlRpcValue::TypeArray && footprint_list.size() > 2,
- "The footprint must be specified as list of lists on the parameter server eg: [[x1, y1], [x2, y2], ..., [xn, yn]]");
- for(int i = 0; i < footprint_list.size(); ++i){
- //make sure we have a list of lists of size 2
- XmlRpc::XmlRpcValue point = footprint_list[i];
- ROS_ASSERT_MSG(point.getType() == XmlRpc::XmlRpcValue::TypeArray && point.size() == 2,
- "The footprint must be specified as list of lists on the parameter server eg: [[x1, y1], [x2, y2], ..., [xn, yn]]");
-
- //make sure that the value we're looking at is either a double or an int
- ROS_ASSERT(point[0].getType() == XmlRpc::XmlRpcValue::TypeInt || point[0].getType() == XmlRpc::XmlRpcValue::TypeDouble);
- pt.x = point[0].getType() == XmlRpc::XmlRpcValue::TypeInt ? (int)(point[0]) : (double)(point[0]);
- pt.x += sign(pt.x) * padding;
-
- //make sure that the value we're looking at is either a double or an int
- ROS_ASSERT(point[1].getType() == XmlRpc::XmlRpcValue::TypeInt || point[1].getType() == XmlRpc::XmlRpcValue::TypeDouble);
- pt.y = point[1].getType() == XmlRpc::XmlRpcValue::TypeInt ? (int)(point[1]) : (double)(point[1]);
- pt.y += sign(pt.y) * padding;
-
- footprint_.push_back(pt);
-
- }
- }
- else{
- //if no explicit footprint is set on the param server... create a square footprint
- pt.x = inscribed_radius_ + padding;
- pt.y = -1 * (inscribed_radius_ + padding);
- footprint_.push_back(pt);
- pt.x = -1 * (inscribed_radius_ + padding);
- pt.y = -1 * (inscribed_radius_ + padding);
- footprint_.push_back(pt);
- pt.x = -1 * (inscribed_radius_ + padding);
- pt.y = inscribed_radius_ + padding;
- footprint_.push_back(pt);
- pt.x = inscribed_radius_ + padding;
- pt.y = inscribed_radius_ + padding;
- footprint_.push_back(pt);
-
- //give the robot a nose
- pt.x = circumscribed_radius_;
- pt.y = 0;
- footprint_.push_back(pt);
- }
-
//create the ros wrapper for the planner's costmap... and initializer a pointer we'll use with the underlying map
- planner_costmap_ros_ = new Costmap2DROS(ros_node_, tf_, std::string("navfn"), footprint_);
+ planner_costmap_ros_ = new Costmap2DROS("global_costmap", tf_);
//initialize the global planner
try {
- planner_ = nav_robot_actions::BGPFactory::Instance().CreateObject(global_planner, ros_node_, tf_, *planner_costmap_ros_);
+ planner_ = nav_robot_actions::BGPFactory::Instance().CreateObject(global_planner, global_planner, *planner_costmap_ros_);
} catch (Loki::DefaultFactoryError<std::string, nav_robot_actions::BaseGlobalPlanner>::Exception)
{
ROS_ASSERT_MSG(false, "Cannot create the desired global planner because it is not registered with the factory");
@@ -137,12 +84,12 @@
ROS_INFO("MAP SIZE: %d, %d", planner_costmap_ros_->cellSizeX(), planner_costmap_ros_->cellSizeY());
//create the ros wrapper for the controller's costmap... and initializer a pointer we'll use with the underlying map
- controller_costmap_ros_ = new Costmap2DROS(ros_node_, tf_, std::string("base_local_planner"), footprint_);
+ controller_costmap_ros_ = new Costmap2DROS("local_costmap", tf_);
//create a local planner
try {
tc_ = nav_robot_actions::BLPFactory::Instance().CreateObject(local_planner,
- ros_node_, tf_, *controller_costmap_ros_, footprint_);
+ local_planner, tf_, *controller_costmap_ros_);
} catch (Loki::DefaultFactoryError<std::string, nav_robot_actions::BaseLocalPlanner>::Exception)
{
ROS_ASSERT_MSG(false, "Cannot create the desired local planner because it is not regist...
[truncated message content] |