|
From: <ei...@us...> - 2009-08-12 21:11:57
|
Revision: 21710
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21710&view=rev
Author: eitanme
Date: 2009-08-12 21:11:49 +0000 (Wed, 12 Aug 2009)
Log Message:
-----------
Changing topic remappings in some more launch files
Modified Paths:
--------------
pkg/trunk/demos/door_demos/launch/move_base_door.launch
pkg/trunk/demos/milestone2/milestone2_tests/test/move_base.launch
pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/sbpl_door_action_planner.launch
pkg/trunk/nav/nav_apps/costmap_2d_tutorials/launch_example/costmap.launch
pkg/trunk/stacks/navigation/costmap_2d/include/costmap_2d/costmap_2d_ros.h
Modified: pkg/trunk/demos/door_demos/launch/move_base_door.launch
===================================================================
--- pkg/trunk/demos/door_demos/launch/move_base_door.launch 2009-08-12 21:11:03 UTC (rev 21709)
+++ pkg/trunk/demos/door_demos/launch/move_base_door.launch 2009-08-12 21:11:49 UTC (rev 21710)
@@ -66,7 +66,7 @@
<param name="costmap/cost_scaling_factor" value="1.0" />
<param name="costmap/lethal_cost_threshold" value="100" />
<!-- End Costmap Parameters -->
- <remap from="raw_obstacles" to="~raw_obstacles" />
+ <remap from="obstacles" to="~obstacles" />
<remap from="inflated_obstacles" to="~inflated_obstacles" />
</node>
</group>
Modified: pkg/trunk/demos/milestone2/milestone2_tests/test/move_base.launch
===================================================================
--- pkg/trunk/demos/milestone2/milestone2_tests/test/move_base.launch 2009-08-12 21:11:03 UTC (rev 21709)
+++ pkg/trunk/demos/milestone2/milestone2_tests/test/move_base.launch 2009-08-12 21:11:49 UTC (rev 21710)
@@ -24,10 +24,10 @@
<node pkg="fake_localization" type="fake_localization" respawn="false" />
<node pkg="rviz" type="rviz" respawn="false">
<remap from="goal" to="/move_base/activate" />
- <remap from="raw_obstacles" to="/move_base/base_local_planner/raw_obstacles" />
+ <remap from="obstacles" to="/move_base/base_local_planner/obstacles" />
<remap from="inflated_obstacles" to="/move_base/base_local_planner/inflated_obstacles" />
- <remap from="gui_path" to="/move_base/base_local_planner/global_plan" />
- <remap from="local_path" to="/move_base/base_local_planner/local_plan" />
+ <remap from="global_plan" to="/move_base/base_local_planner/global_plan" />
+ <remap from="local_plan" to="/move_base/base_local_planner/local_plan" />
<remap from="robot_footprint" to="/move_base/base_local_planner/robot_footprint"/>
</node>
</group>
Modified: pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/sbpl_door_action_planner.launch
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/sbpl_door_action_planner.launch 2009-08-12 21:11:03 UTC (rev 21709)
+++ pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/sbpl_door_action_planner.launch 2009-08-12 21:11:49 UTC (rev 21710)
@@ -37,7 +37,7 @@
<param name="costmap/cost_scaling_factor" value="1.0" />
<param name="costmap/lethal_cost_threshold" value="100" />
<!-- End Costmap Parameters -->
- <remap from="raw_obstacles" to="~raw_obstacles" />
+ <remap from="obstacles" to="~obstacles" />
<remap from="inflated_obstacles" to="~inflated_obstacles" />
<!--param name="sbpl_action_file" textfile="$(find mpbench)/data/pr2sides.mprim" /-->
Modified: pkg/trunk/nav/nav_apps/costmap_2d_tutorials/launch_example/costmap.launch
===================================================================
--- pkg/trunk/nav/nav_apps/costmap_2d_tutorials/launch_example/costmap.launch 2009-08-12 21:11:03 UTC (rev 21709)
+++ pkg/trunk/nav/nav_apps/costmap_2d_tutorials/launch_example/costmap.launch 2009-08-12 21:11:49 UTC (rev 21710)
@@ -10,7 +10,7 @@
</node>
<node pkg="fake_localization" type="fake_localization" respawn="false" />
<node pkg="nav_view" type="nav_view" respawn="false">
- <remap from="raw_obstacles" to="/costmap_test/costmap/raw_obstacles" />
+ <remap from="obstacles" to="/costmap_test/costmap/obstacles" />
<remap from="inflated_obstacles" to="/costmap_test/costmap/inflated_obstacles" />
</node>
</launch>
Modified: pkg/trunk/stacks/navigation/costmap_2d/include/costmap_2d/costmap_2d_ros.h
===================================================================
--- pkg/trunk/stacks/navigation/costmap_2d/include/costmap_2d/costmap_2d_ros.h 2009-08-12 21:11:03 UTC (rev 21709)
+++ pkg/trunk/stacks/navigation/costmap_2d/include/costmap_2d/costmap_2d_ros.h 2009-08-12 21:11:49 UTC (rev 21710)
@@ -45,7 +45,6 @@
#include <costmap_2d/observation_buffer.h>
#include <costmap_2d/voxel_costmap_2d.h>
#include <costmap_2d/VoxelGrid.h>
-#include <visualization_msgs/Polyline.h>
#include <map>
#include <vector>
#include <string>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|