|
From: <tf...@us...> - 2009-04-21 00:38:52
|
Revision: 14107
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=14107&view=rev
Author: tfoote
Date: 2009-04-21 00:38:49 +0000 (Tue, 21 Apr 2009)
Log Message:
-----------
moving one demo/test script in to different test package and breaking dependency
Modified Paths:
--------------
pkg/trunk/demos/2dnav_stage/manifest.xml
Added Paths:
-----------
pkg/trunk/highlevel/test_highlevel_controllers/2dnav_stage_movebase_empty_room.launch
Removed Paths:
-------------
pkg/trunk/demos/2dnav_stage/2dnav_stage_movebase_empty_room.launch
Deleted: pkg/trunk/demos/2dnav_stage/2dnav_stage_movebase_empty_room.launch
===================================================================
--- pkg/trunk/demos/2dnav_stage/2dnav_stage_movebase_empty_room.launch 2009-04-21 00:30:40 UTC (rev 14106)
+++ pkg/trunk/demos/2dnav_stage/2dnav_stage_movebase_empty_room.launch 2009-04-21 00:38:49 UTC (rev 14107)
@@ -1,63 +0,0 @@
-<launch>
-
- <group name="wg">
- <node pkg="stage" type="stageros" args="$(find 2dnav_stage)/worlds/willow-gps-pr2-5cm.world" respawn="false" output="screen"/>
- <node pkg="map_server" type="map_server" args="$(find 2dnav_stage)/maps/willow-empty-0.05.pgm 0.05" respawn="false" output="screen"/>
- <param name="robot_radius" value="0.325"/>
- <!-- node pkg="wavefront_player" type="wavefront_player" respawn="false" output="screen">
- <remap from="scan" to="base_scan" />
- </node -->
- <node pkg="nav_view" type="nav_view" respawn="false" output="screen"/>
- <!--node pkg="nav_view_sdl" type="nav_view" respawn="false" output="screen"/> -->
-
- <param name="move_base/environmentList" value="2D,3DKIN"/> <!-- future extension -->
- <param name="move_base/plannerList" value="ADPlanner,ARAPlanner"/> <!-- future extension -->
- <param name="move_base/plannerType" value="ARAPlanner"/>
- <param name="move_base/environmentType" value="2D"/>
- <param name="move_base/controller_frequency" value="30.0"/>
- <param name="move_base/planner_frequency" value="0.0"/>
- <param name="move_base/plannerTimeLimit" value="0.5"/>
- <param name="move_base/map_update_frequency" value="5.0"/>
- <param name="/costmap_2d/base_laser_max_range" value="20.0"/>
- <param name="/costmap_2d/tilt_laser_max_range" value="2.0"/>
- <param name="/costmap_2d/lethal_obstacle_threshold" value="100.0"/>
- <param name="/costmap_2d/no_information_value" value="255"/>
- <param name="/costmap_2d/z_threshold_max" value="2.0"/>
- <param name="/costmap_2d/z_threshold_min" value="0.13"/>
- <param name="/costmap_2d/freespace_projection_height" value="2.0"/>
- <param name="/costmap_2d/inflation_radius" value="0.65"/>
- <param name="/costmap_2d/circumscribed_radius" value="0.46"/>
- <param name="/costmap_2d/inscribed_radius" value="0.325"/>
- <param name="/costmap_2d/raytrace_window" value="10.0"/>
- <param name="/costmap_2d/weight" value="0.1"/>
-
- <param name="/global_frame_id" value="odom"/>
-
- <!-- Forces a check that we are receiving base scans that are correctly up to date at a rate of at least 10 Hz -->
- <param name="/costmap_2d/base_laser_update_rate" value="2.0"/>
-
- <!-- Don't Forces a check that we are receiving tilt scans that are correctly up to date at a rate of at least 10 Hz -->
- <param name="/costmap_2d/tilt_laser_update_rate" value="0.0"/>
-
- <!-- we don't have stereo data yet -->
- <param name="/costmap_2d/stereo_update_rate" value="0.0"/>
-
- <!--- Don't check for ground plane obstacles -->
- <param name="/costmap_2d/low_obstacle_update_rate" value="0.0"/>
-
- <param name="/trajectory_rollout/map_size" value="4.0" />
- <param name="/trajectory_rollout/sim_time" value="1.0" />
- <param name="/trajectory_rollout/sim_steps" value="20" />
- <param name="/trajectory_rollout/samples_per_dim" value="25" />
- <param name="/trajectory_rollout/occdist_scale" value="0.2" />
- <param name="/trajectory_rollout/path_distance_bias" value="0.6" />
- <param name="/trajectory_rollout/goal_distance_bias" value="0.8" />
- <param name="/trajectory_rollout/acc_limit_x" value="2.5" />
- <param name="/trajectory_rollout/acc_limit_y" value="2.5" />
- <param name="/trajectory_rollout/acc_limit_th" value="3.2" />
-
- <node pkg="highlevel_controllers" type="move_base_navfn" respawn="true" output="screen"/>
-
- </group>
-</launch>
-
Modified: pkg/trunk/demos/2dnav_stage/manifest.xml
===================================================================
--- pkg/trunk/demos/2dnav_stage/manifest.xml 2009-04-21 00:30:40 UTC (rev 14106)
+++ pkg/trunk/demos/2dnav_stage/manifest.xml 2009-04-21 00:38:49 UTC (rev 14107)
@@ -13,5 +13,4 @@
<depend package="stage"/>
<depend package="map_server"/>
<depend package="wavefront_player"/>
- <depend package="highlevel_controllers"/>
</package>
Copied: pkg/trunk/highlevel/test_highlevel_controllers/2dnav_stage_movebase_empty_room.launch (from rev 13027, pkg/trunk/demos/2dnav_stage/2dnav_stage_movebase_empty_room.launch)
===================================================================
--- pkg/trunk/highlevel/test_highlevel_controllers/2dnav_stage_movebase_empty_room.launch (rev 0)
+++ pkg/trunk/highlevel/test_highlevel_controllers/2dnav_stage_movebase_empty_room.launch 2009-04-21 00:38:49 UTC (rev 14107)
@@ -0,0 +1,63 @@
+<launch>
+
+ <group name="wg">
+ <node pkg="stage" type="stageros" args="$(find 2dnav_stage)/worlds/willow-gps-pr2-5cm.world" respawn="false" output="screen"/>
+ <node pkg="map_server" type="map_server" args="$(find 2dnav_stage)/maps/willow-empty-0.05.pgm 0.05" respawn="false" output="screen"/>
+ <param name="robot_radius" value="0.325"/>
+ <!-- node pkg="wavefront_player" type="wavefront_player" respawn="false" output="screen">
+ <remap from="scan" to="base_scan" />
+ </node -->
+ <node pkg="nav_view" type="nav_view" respawn="false" output="screen"/>
+ <!--node pkg="nav_view_sdl" type="nav_view" respawn="false" output="screen"/> -->
+
+ <param name="move_base/environmentList" value="2D,3DKIN"/> <!-- future extension -->
+ <param name="move_base/plannerList" value="ADPlanner,ARAPlanner"/> <!-- future extension -->
+ <param name="move_base/plannerType" value="ARAPlanner"/>
+ <param name="move_base/environmentType" value="2D"/>
+ <param name="move_base/controller_frequency" value="30.0"/>
+ <param name="move_base/planner_frequency" value="0.0"/>
+ <param name="move_base/plannerTimeLimit" value="0.5"/>
+ <param name="move_base/map_update_frequency" value="5.0"/>
+ <param name="/costmap_2d/base_laser_max_range" value="20.0"/>
+ <param name="/costmap_2d/tilt_laser_max_range" value="2.0"/>
+ <param name="/costmap_2d/lethal_obstacle_threshold" value="100.0"/>
+ <param name="/costmap_2d/no_information_value" value="255"/>
+ <param name="/costmap_2d/z_threshold_max" value="2.0"/>
+ <param name="/costmap_2d/z_threshold_min" value="0.13"/>
+ <param name="/costmap_2d/freespace_projection_height" value="2.0"/>
+ <param name="/costmap_2d/inflation_radius" value="0.65"/>
+ <param name="/costmap_2d/circumscribed_radius" value="0.46"/>
+ <param name="/costmap_2d/inscribed_radius" value="0.325"/>
+ <param name="/costmap_2d/raytrace_window" value="10.0"/>
+ <param name="/costmap_2d/weight" value="0.1"/>
+
+ <param name="/global_frame_id" value="odom"/>
+
+ <!-- Forces a check that we are receiving base scans that are correctly up to date at a rate of at least 10 Hz -->
+ <param name="/costmap_2d/base_laser_update_rate" value="2.0"/>
+
+ <!-- Don't Forces a check that we are receiving tilt scans that are correctly up to date at a rate of at least 10 Hz -->
+ <param name="/costmap_2d/tilt_laser_update_rate" value="0.0"/>
+
+ <!-- we don't have stereo data yet -->
+ <param name="/costmap_2d/stereo_update_rate" value="0.0"/>
+
+ <!--- Don't check for ground plane obstacles -->
+ <param name="/costmap_2d/low_obstacle_update_rate" value="0.0"/>
+
+ <param name="/trajectory_rollout/map_size" value="4.0" />
+ <param name="/trajectory_rollout/sim_time" value="1.0" />
+ <param name="/trajectory_rollout/sim_steps" value="20" />
+ <param name="/trajectory_rollout/samples_per_dim" value="25" />
+ <param name="/trajectory_rollout/occdist_scale" value="0.2" />
+ <param name="/trajectory_rollout/path_distance_bias" value="0.6" />
+ <param name="/trajectory_rollout/goal_distance_bias" value="0.8" />
+ <param name="/trajectory_rollout/acc_limit_x" value="2.5" />
+ <param name="/trajectory_rollout/acc_limit_y" value="2.5" />
+ <param name="/trajectory_rollout/acc_limit_th" value="3.2" />
+
+ <node pkg="highlevel_controllers" type="move_base_navfn" respawn="true" output="screen"/>
+
+ </group>
+</launch>
+
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|