|
From: <is...@us...> - 2009-07-29 01:58:53
|
Revision: 19960
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=19960&view=rev
Author: isucan
Date: 2009-07-29 01:58:46 +0000 (Wed, 29 Jul 2009)
Log Message:
-----------
moved launch files
Modified Paths:
--------------
pkg/trunk/highlevel/move_arm/src/arm_cmd_line.cpp
pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp
Added Paths:
-----------
pkg/trunk/sandbox/3dnav_pr2/launch/collision_map_occ.launch
pkg/trunk/sandbox/3dnav_pr2/launch/laser+stereo-perception.launch
pkg/trunk/sandbox/3dnav_pr2/launch/laser-perception.launch
pkg/trunk/sandbox/3dnav_pr2/launch/narrow_stereoproc.launch
pkg/trunk/sandbox/3dnav_pr2/launch/stereo-perception.launch
Removed Paths:
-------------
pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/laser+stereo-perception.launch
pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/laser-perception.launch
pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/stereo-perception.launch
pkg/trunk/mapping/collision_map/collision_map_occ.launch
Deleted: pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/laser+stereo-perception.launch
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/laser+stereo-perception.launch 2009-07-29 01:53:44 UTC (rev 19959)
+++ pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/laser+stereo-perception.launch 2009-07-29 01:58:46 UTC (rev 19960)
@@ -1,97 +0,0 @@
-<launch>
-
- <!-- send additional description parameters -->
- <include file="$(find 3dnav_pr2)/launch/pr2_planning_environment.launch" />
-
- <!-- start controller -->
- <node pkg="mechanism_control" type="spawner.py" args="$(find pr2_default_controllers)/laser_tilt_controller.xml" />
- <node pkg="pr2_mechanism_controllers" type="send_periodic_cmd_srv.py" args="laser_tilt_controller linear 8 .75 .25" />
-
- <!-- convert laser scan to pointcloud -->
- <node pkg="laser_scan" type="scan_to_cloud" output="screen">
- <param name="scan_topic" type="string" value="tilt_scan" />
- <param name="scan_filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
- <param name="high_fidelity" type="bool" value="true" />
- <param name="cloud_topic" type="string" value="tilt_scan_cloud" />
- </node>
-
- <!-- remove points corresponding to known objects -->
- <node pkg="planning_environment" type="clear_known_objects" respawn="false" output="screen">
- <remap from="robot_description" to="robot_description" />
-
-<!-- define a frame that stays fixed for the known objects -->
-<!-- <param name="fixed_frame" type="string" value="/odom_combined" /> -->
-
- <remap from="cloud_in" to="tilt_scan_cloud" />
- <remap from="cloud_out" to="tilt_scan_cloud_without_known_objects" />
- <param name="object_scale" type="double" value="1.0" />
- <param name="object_padd" type="double" value="0.05" />
- </node>
-
- <!-- add a channel that marks points that are on the robot -->
- <node pkg="robot_self_filter" type="self_filter" respawn="true" output="screen">
- <remap from="robot_description" to="robot_description" />
- <remap from="cloud_in" to="tilt_scan_cloud_without_known_objects" />
- <remap from="cloud_out" to="tilt_scan_cloud_annotated" />
- <param name="annotate" type="string" value="on_self" />
- <param name="sensor_frame" type="string" value="laser_tilt_mount_link" />
- </node>
-
- <!-- assemble pointcloud into a full world view -->
- <node pkg="point_cloud_assembler" type="point_cloud_assembler_srv" output="screen" name="point_cloud_assembler">
- <remap from="scan_in" to="tilt_scan_cloud_annotated"/>
- <param name="tf_cache_time_secs" type="double" value="10.0" />
- <param name="tf_tolerance_secs" type="double" value="0.0" />
- <param name="max_scans" type="int" value="400" />
- <param name="ignore_laser_skew" type="bool" value="true" />
- <param name="fixed_frame" type="string" value="torso_lift_link" />
- <param name="downsample_factor" type="int" value="2" />
- </node>
-
- <node pkg="point_cloud_assembler" type="point_cloud_snapshotter" output="screen" name="snapshotter">
- <remap from="laser_scanner_signal" to="laser_tilt_controller/laser_scanner_signal"/>
- <remap from="build_cloud" to="point_cloud_assembler/build_cloud" />
- <remap from="full_cloud" to="full_laser_cloud_annotated" />
- </node>
-
- <include file="$(find stereo_image_proc)/narrow_stereoproc.launch" />
-
- <!-- remove points corresponding to known objects -->
- <node pkg="planning_environment" type="clear_known_objects" respawn="false" output="screen">
- <remap from="robot_description" to="robot_description" />
-
-<!-- define a frame that stays fixed for the known objects -->
-<!-- <param name="fixed_frame" type="string" value="/odom_combined" /> -->
-
- <remap from="cloud_in" to="/narrow_stereo/cloud" />
- <remap from="cloud_out" to="stereo_cloud_without_known_objects" />
- </node>
-
- <!-- add a channel that marks points that are on the robot -->
- <node pkg="robot_self_filter" type="self_filter" respawn="true" output="screen">
- <remap from="robot_description" to="robot_description" />
- <remap from="cloud_in" to="stereo_cloud_without_known_objects" />
- <remap from="cloud_out" to="full_stereo_cloud_annotated" />
- <param name="annotate" type="string" value="on_self" />
- </node>
-
- <node pkg="point_cloud_assembler" type="merge_clouds" output="screen">
-
- <!-- first input cloud -->
- <remap from="cloud_in1" to="full_stereo_cloud_annotated"/>
-
- <!-- second input cloud -->
- <remap from="cloud_in2" to="full_laser_cloud_annotated"/>
-
- <!-- output cloud -->
- <remap from="cloud_out" to="full_cloud_annotated"/>
-
- <!-- the frame in which the output cloud should be published; this parameter must ALWAYS be specified -->
- <param name="output_frame" type="string" value="base_link"/>
- </node>
-
-
- <!-- start collision map -->
- <include file="$(find collision_map)/collision_map_occ.launch" />
-
-</launch>
Deleted: pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/laser-perception.launch
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/laser-perception.launch 2009-07-29 01:53:44 UTC (rev 19959)
+++ pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/laser-perception.launch 2009-07-29 01:58:46 UTC (rev 19960)
@@ -1,60 +0,0 @@
-<launch>
-
- <!-- send additional description parameters -->
- <include file="$(find 3dnav_pr2)/launch/pr2_planning_environment.launch" />
-
- <!-- start controller -->
- <node pkg="mechanism_control" type="spawner.py" args="$(find pr2_default_controllers)/laser_tilt_controller.xml" />
- <node pkg="pr2_mechanism_controllers" type="send_periodic_cmd_srv.py" args="laser_tilt_controller linear 15 .75 .25" />
-
- <!-- convert laser scan to pointcloud -->
- <node pkg="laser_scan" type="scan_to_cloud" output="screen">
- <param name="scan_topic" type="string" value="tilt_scan" />
- <param name="scan_filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
- <param name="high_fidelity" type="bool" value="true" />
- <param name="cloud_topic" type="string" value="tilt_scan_cloud" />
- </node>
-
- <!-- remove points corresponding to known objects -->
- <node pkg="planning_environment" type="clear_known_objects" respawn="false" output="screen">
- <remap from="robot_description" to="robot_description" />
-
-<!-- define a frame that stays fixed for the known objects -->
-<!-- <param name="fixed_frame" type="string" value="/odom_combined" /> -->
-
- <remap from="cloud_in" to="tilt_scan_cloud" />
- <remap from="cloud_out" to="tilt_scan_cloud_without_known_objects" />
- <param name="object_scale" type="double" value="1.0" />
- <param name="object_padd" type="double" value="0.05" />
- </node>
-
- <!-- add a channel that marks points that are on the robot -->
- <node pkg="robot_self_filter" type="self_filter" respawn="true" output="screen">
- <remap from="robot_description" to="robot_description" />
- <remap from="cloud_in" to="tilt_scan_cloud_without_known_objects" />
- <remap from="cloud_out" to="tilt_scan_cloud_annotated" />
- <param name="annotate" type="string" value="on_self" />
- <param name="sensor_frame" type="string" value="laser_tilt_mount_link" />
- </node>
-
- <!-- assemble pointcloud into a full world view -->
- <node pkg="point_cloud_assembler" type="point_cloud_assembler_srv" output="screen" name="point_cloud_assembler">
- <remap from="scan_in" to="tilt_scan_cloud_annotated"/>
- <param name="tf_cache_time_secs" type="double" value="10.0" />
- <param name="tf_tolerance_secs" type="double" value="0.0" />
- <param name="max_scans" type="int" value="400" />
- <param name="ignore_laser_skew" type="bool" value="true" />
- <param name="fixed_frame" type="string" value="torso_lift_link" />
- <param name="downsample_factor" type="int" value="2" />
- </node>
-
- <node pkg="point_cloud_assembler" type="point_cloud_snapshotter" output="screen" name="snapshotter">
- <remap from="laser_scanner_signal" to="laser_tilt_controller/laser_scanner_signal"/>
- <remap from="build_cloud" to="point_cloud_assembler/build_cloud" />
- <remap from="full_cloud" to="full_cloud_annotated" />
- </node>
-
- <!-- start collision map -->
- <include file="$(find collision_map)/collision_map_occ.launch" />
-
-</launch>
Deleted: pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/stereo-perception.launch
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/stereo-perception.launch 2009-07-29 01:53:44 UTC (rev 19959)
+++ pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/stereo-perception.launch 2009-07-29 01:58:46 UTC (rev 19960)
@@ -1,29 +0,0 @@
-<launch>
-
- <include file="$(find 3dnav_pr2)/launch/pr2_planning_environment.launch" />
- <include file="$(find stereo_image_proc)/narrow_stereoproc.launch" />
-
- <!-- remove points corresponding to known objects -->
- <node pkg="planning_environment" type="clear_known_objects" respawn="false" output="screen">
- <remap from="robot_description" to="robot_description" />
-
-<!-- define a frame that stays fixed for the known objects -->
-<!-- <param name="fixed_frame" type="string" value="/odom_combined" /> -->
-
- <remap from="cloud_in" to="/narrow_stereo/cloud" />
- <remap from="cloud_out" to="full_cloud_without_known_objects" />
- <param name="object_scale" type="double" value="1.0" />
- <param name="object_padd" type="double" value="0.025" />
- </node>
-
- <!-- add a channel that marks points that are on the robot -->
- <node pkg="robot_self_filter" type="self_filter" respawn="true" output="screen">
- <remap from="robot_description" to="robot_description" />
- <remap from="cloud_in" to="full_cloud_without_known_objects" />
- <remap from="cloud_out" to="full_cloud_annotated" />
- <param name="annotate" type="string" value="on_self" />
- </node>
-
- <include file="$(find collision_map)/collision_map_occ.launch" />
-
-</launch>
Modified: pkg/trunk/highlevel/move_arm/src/arm_cmd_line.cpp
===================================================================
--- pkg/trunk/highlevel/move_arm/src/arm_cmd_line.cpp 2009-07-29 01:53:44 UTC (rev 19959)
+++ pkg/trunk/highlevel/move_arm/src/arm_cmd_line.cpp 2009-07-29 01:58:46 UTC (rev 19960)
@@ -163,19 +163,19 @@
goal.goal_constraints.pose_constraint[0].pose.pose.orientation.z = 0.0;
goal.goal_constraints.pose_constraint[0].pose.pose.orientation.w = 1.0;
- goal.goal_constraints.pose_constraint[0].position_tolerance_above.x = 0.002;
- goal.goal_constraints.pose_constraint[0].position_tolerance_above.y = 0.003;
- goal.goal_constraints.pose_constraint[0].position_tolerance_above.z = 0.008;
- goal.goal_constraints.pose_constraint[0].position_tolerance_below.x = 0.002;
- goal.goal_constraints.pose_constraint[0].position_tolerance_below.y = 0.003;
- goal.goal_constraints.pose_constraint[0].position_tolerance_below.z = 0.008;
+ goal.goal_constraints.pose_constraint[0].position_tolerance_above.x = 0.01;
+ goal.goal_constraints.pose_constraint[0].position_tolerance_above.y = 0.01;
+ goal.goal_constraints.pose_constraint[0].position_tolerance_above.z = 0.015;
+ goal.goal_constraints.pose_constraint[0].position_tolerance_below.x = 0.01;
+ goal.goal_constraints.pose_constraint[0].position_tolerance_below.y = 0.01;
+ goal.goal_constraints.pose_constraint[0].position_tolerance_below.z = 0.015;
- goal.goal_constraints.pose_constraint[0].orientation_tolerance_above.x = 0.005;
- goal.goal_constraints.pose_constraint[0].orientation_tolerance_above.y = 0.005;
- goal.goal_constraints.pose_constraint[0].orientation_tolerance_above.z = 0.005;
- goal.goal_constraints.pose_constraint[0].orientation_tolerance_below.x = 0.005;
- goal.goal_constraints.pose_constraint[0].orientation_tolerance_below.y = 0.005;
- goal.goal_constraints.pose_constraint[0].orientation_tolerance_below.z = 0.005;
+ goal.goal_constraints.pose_constraint[0].orientation_tolerance_above.x = 0.15;
+ goal.goal_constraints.pose_constraint[0].orientation_tolerance_above.y = 0.15;
+ goal.goal_constraints.pose_constraint[0].orientation_tolerance_above.z = 0.15;
+ goal.goal_constraints.pose_constraint[0].orientation_tolerance_below.x = 0.15;
+ goal.goal_constraints.pose_constraint[0].orientation_tolerance_below.y = 0.15;
+ goal.goal_constraints.pose_constraint[0].orientation_tolerance_below.z = 0.15;
goal.goal_constraints.pose_constraint[0].orientation_importance = 0.01;
}
Deleted: pkg/trunk/mapping/collision_map/collision_map_occ.launch
===================================================================
--- pkg/trunk/mapping/collision_map/collision_map_occ.launch 2009-07-29 01:53:44 UTC (rev 19959)
+++ pkg/trunk/mapping/collision_map/collision_map_occ.launch 2009-07-29 01:58:46 UTC (rev 19960)
@@ -1,42 +0,0 @@
-<launch>
- <node pkg="collision_map" type="collision_map_occ_node" name="collision_map_occ" respawn="true" output="screen">
- <remap from="cloud_in" to="full_cloud_annotated" />
- <remap from="cloud_incremental_in" to="tilt_scan_cloud_annotated" />
-
- <param name="publish_occlusion" type="bool" value="false" />
- <param name="mark_self_occlusion" type="bool" value="false" />
-
- <!-- tell the collision map there may be an annotation channel telling which points are on the robot -->
- <param name="cloud_annotation" type="string" value="on_self" />
-
- <!-- a frame that does not change as the robot moves -->
-<!-- <param name="fixed_frame" type="string" value="/odom_combined" /> -->
- <param name="fixed_frame" type="string" value="base_link" />
-
- <!-- define a box of size 2x3x4 around (1.1, 0, 0) in the robot frame -->
- <param name="robot_frame" type="string" value="base_link" />
-
- <param name="origin_x" type="double" value="1.1" />
- <param name="origin_y" type="double" value="0.0" />
- <param name="origin_z" type="double" value="0.0" />
-
- <param name="dimension_x" type="double" value="1.0" />
- <param name="dimension_y" type="double" value="1.5" />
- <param name="dimension_z" type="double" value="2.0" />
-
- <!-- set the resolution (1.0 cm) -->
- <param name="resolution" type="double" value="0.01" />
-
- <!-- the amount of time to remember an occluded point for -->
- <param name="keep_occluded" type="double" value="30.0" />
-
- <!-- when occluded obstacles are raytraced, keep boxes from occluded space within a given radius -->
- <param name="radius" type="int" value="5" />
-
- <!-- define sensor location in robot frame -->
- <param name="sensor_x" type="double" value="0.05" />
- <param name="sensor_y" type="double" value="0.0" />
- <param name="sensor_z" type="double" value="1.0" />
-
- </node>
-</launch>
Modified: pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp 2009-07-29 01:53:44 UTC (rev 19959)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp 2009-07-29 01:58:46 UTC (rev 19960)
@@ -39,7 +39,6 @@
#include <robot_msgs/PointStamped.h>
#include <robot_msgs/PoseStamped.h>
#include <boost/bind.hpp>
-#include <sstream>
#include <climits>
namespace planning_environment
Added: pkg/trunk/sandbox/3dnav_pr2/launch/collision_map_occ.launch
===================================================================
--- pkg/trunk/sandbox/3dnav_pr2/launch/collision_map_occ.launch (rev 0)
+++ pkg/trunk/sandbox/3dnav_pr2/launch/collision_map_occ.launch 2009-07-29 01:58:46 UTC (rev 19960)
@@ -0,0 +1,45 @@
+<launch>
+ <node pkg="collision_map" type="collision_map_occ_node" name="collision_map_occ" respawn="true" output="screen">
+ <remap from="cloud_in" to="full_cloud_annotated" />
+ <remap from="cloud_incremental_in" to="tilt_scan_cloud_annotated" />
+
+ <!-- we do not want a separate map with occlusions alone -->
+ <param name="publish_occlusion" type="bool" value="false" />
+
+ <!-- we do not want to assume initially occluded space (when we start the robot) is in collision -->
+ <param name="mark_self_occlusion" type="bool" value="false" />
+
+ <!-- tell the collision map there may be an annotation channel telling which points are on the robot -->
+ <param name="cloud_annotation" type="string" value="on_self" />
+
+ <!-- a frame that does not change as the robot moves -->
+<!-- <param name="fixed_frame" type="string" value="/odom_combined" /> -->
+ <param name="fixed_frame" type="string" value="base_link" />
+
+ <!-- define a box of size 2x3x4 around (1.1, 0, 0) in the robot frame -->
+ <param name="robot_frame" type="string" value="base_link" />
+
+ <param name="origin_x" type="double" value="1.1" />
+ <param name="origin_y" type="double" value="0.0" />
+ <param name="origin_z" type="double" value="0.0" />
+
+ <param name="dimension_x" type="double" value="1.0" />
+ <param name="dimension_y" type="double" value="1.5" />
+ <param name="dimension_z" type="double" value="2.0" />
+
+ <!-- set the resolution (1.0 cm) -->
+ <param name="resolution" type="double" value="0.01" />
+
+ <!-- the amount of time to remember an occluded point for -->
+ <param name="keep_occluded" type="double" value="30.0" />
+
+ <!-- when occluded obstacles are raytraced, keep boxes from occluded space within a given radius -->
+ <param name="radius" type="int" value="5" />
+
+ <!-- define sensor location in robot frame -->
+ <param name="sensor_x" type="double" value="0.05" />
+ <param name="sensor_y" type="double" value="0.0" />
+ <param name="sensor_z" type="double" value="1.0" />
+
+ </node>
+</launch>
Added: pkg/trunk/sandbox/3dnav_pr2/launch/laser+stereo-perception.launch
===================================================================
--- pkg/trunk/sandbox/3dnav_pr2/launch/laser+stereo-perception.launch (rev 0)
+++ pkg/trunk/sandbox/3dnav_pr2/launch/laser+stereo-perception.launch 2009-07-29 01:58:46 UTC (rev 19960)
@@ -0,0 +1,97 @@
+<launch>
+
+ <!-- send additional description parameters -->
+ <include file="$(find 3dnav_pr2)/launch/pr2_planning_environment.launch" />
+
+ <!-- start controller -->
+ <node pkg="mechanism_control" type="spawner.py" args="$(find pr2_default_controllers)/laser_tilt_controller.xml" />
+ <node pkg="pr2_mechanism_controllers" type="send_periodic_cmd_srv.py" args="laser_tilt_controller linear 8 .75 .25" />
+
+ <!-- convert laser scan to pointcloud -->
+ <node pkg="laser_scan" type="scan_to_cloud" output="screen">
+ <param name="scan_topic" type="string" value="tilt_scan" />
+ <param name="scan_filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
+ <param name="high_fidelity" type="bool" value="true" />
+ <param name="cloud_topic" type="string" value="tilt_scan_cloud" />
+ </node>
+
+ <!-- remove points corresponding to known objects -->
+ <node pkg="planning_environment" type="clear_known_objects" respawn="false" output="screen">
+ <remap from="robot_description" to="robot_description" />
+
+<!-- define a frame that stays fixed for the known objects -->
+<!-- <param name="fixed_frame" type="string" value="/odom_combined" /> -->
+
+ <remap from="cloud_in" to="tilt_scan_cloud" />
+ <remap from="cloud_out" to="tilt_scan_cloud_without_known_objects" />
+ <param name="object_scale" type="double" value="1.0" />
+ <param name="object_padd" type="double" value="0.05" />
+ </node>
+
+ <!-- add a channel that marks points that are on the robot -->
+ <node pkg="robot_self_filter" type="self_filter" respawn="true" output="screen">
+ <remap from="robot_description" to="robot_description" />
+ <remap from="cloud_in" to="tilt_scan_cloud_without_known_objects" />
+ <remap from="cloud_out" to="tilt_scan_cloud_annotated" />
+ <param name="annotate" type="string" value="on_self" />
+ <param name="sensor_frame" type="string" value="laser_tilt_mount_link" />
+ </node>
+
+ <!-- assemble pointcloud into a full world view -->
+ <node pkg="point_cloud_assembler" type="point_cloud_assembler_srv" output="screen" name="point_cloud_assembler">
+ <remap from="scan_in" to="tilt_scan_cloud_annotated"/>
+ <param name="tf_cache_time_secs" type="double" value="10.0" />
+ <param name="tf_tolerance_secs" type="double" value="0.0" />
+ <param name="max_scans" type="int" value="400" />
+ <param name="ignore_laser_skew" type="bool" value="true" />
+ <param name="fixed_frame" type="string" value="torso_lift_link" />
+ <param name="downsample_factor" type="int" value="2" />
+ </node>
+
+ <node pkg="point_cloud_assembler" type="point_cloud_snapshotter" output="screen" name="snapshotter">
+ <remap from="laser_scanner_signal" to="laser_tilt_controller/laser_scanner_signal"/>
+ <remap from="build_cloud" to="point_cloud_assembler/build_cloud" />
+ <remap from="full_cloud" to="full_laser_cloud_annotated" />
+ </node>
+
+ <include file="$(find 3dnav_pr2)/launch/narrow_stereoproc.launch" />
+
+ <!-- remove points corresponding to known objects -->
+ <node pkg="planning_environment" type="clear_known_objects" respawn="false" output="screen">
+ <remap from="robot_description" to="robot_description" />
+
+<!-- define a frame that stays fixed for the known objects -->
+<!-- <param name="fixed_frame" type="string" value="/odom_combined" /> -->
+
+ <remap from="cloud_in" to="/narrow_stereo/cloud" />
+ <remap from="cloud_out" to="stereo_cloud_without_known_objects" />
+ </node>
+
+ <!-- add a channel that marks points that are on the robot -->
+ <node pkg="robot_self_filter" type="self_filter" respawn="true" output="screen">
+ <remap from="robot_description" to="robot_description" />
+ <remap from="cloud_in" to="stereo_cloud_without_known_objects" />
+ <remap from="cloud_out" to="full_stereo_cloud_annotated" />
+ <param name="annotate" type="string" value="on_self" />
+ </node>
+
+ <node pkg="point_cloud_assembler" type="merge_clouds" output="screen">
+
+ <!-- first input cloud -->
+ <remap from="cloud_in1" to="full_stereo_cloud_annotated"/>
+
+ <!-- second input cloud -->
+ <remap from="cloud_in2" to="full_laser_cloud_annotated"/>
+
+ <!-- output cloud -->
+ <remap from="cloud_out" to="full_cloud_annotated"/>
+
+ <!-- the frame in which the output cloud should be published; this parameter must ALWAYS be specified -->
+ <param name="output_frame" type="string" value="base_link"/>
+ </node>
+
+
+ <!-- start collision map -->
+ <include file="$(find 3dnav_pr2)/launch/collision_map_occ.launch" />
+
+</launch>
Added: pkg/trunk/sandbox/3dnav_pr2/launch/laser-perception.launch
===================================================================
--- pkg/trunk/sandbox/3dnav_pr2/launch/laser-perception.launch (rev 0)
+++ pkg/trunk/sandbox/3dnav_pr2/launch/laser-perception.launch 2009-07-29 01:58:46 UTC (rev 19960)
@@ -0,0 +1,61 @@
+<launch>
+
+ <!-- send additional description parameters -->
+ <include file="$(find 3dnav_pr2)/launch/pr2_planning_environment.launch" />
+
+ <!-- start controller -->
+ <node pkg="mechanism_control" type="spawner.py" args="$(find pr2_default_controllers)/laser_tilt_controller.xml" />
+ <node pkg="pr2_mechanism_controllers" type="send_periodic_cmd_srv.py" args="laser_tilt_controller linear 10 .75 .25" />
+
+ <!-- convert laser scan to pointcloud -->
+ <node pkg="laser_scan" type="scan_to_cloud" output="screen">
+ <param name="scan_topic" type="string" value="tilt_scan" />
+ <param name="scan_filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
+ <param name="high_fidelity" type="bool" value="true" />
+ <param name="cloud_topic" type="string" value="tilt_scan_cloud" />
+ </node>
+
+ <!-- remove points corresponding to known objects -->
+ <node pkg="planning_environment" type="clear_known_objects" respawn="false" output="screen">
+ <remap from="robot_description" to="robot_description" />
+
+<!-- define a frame that stays fixed for the known objects -->
+<!-- <param name="fixed_frame" type="string" value="/odom_combined" /> -->
+
+ <remap from="cloud_in" to="tilt_scan_cloud" />
+ <remap from="cloud_out" to="tilt_scan_cloud_without_known_objects" />
+ <param name="object_scale" type="double" value="1.0" />
+ <param name="object_padd" type="double" value="0.05" />
+ </node>
+
+ <!-- add a channel that marks points that are on the robot -->
+ <node pkg="robot_self_filter" type="self_filter" respawn="true" output="screen">
+ <remap from="robot_description" to="robot_description" />
+ <remap from="cloud_in" to="tilt_scan_cloud_without_known_objects" />
+ <remap from="cloud_out" to="tilt_scan_cloud_annotated" />
+ <param name="annotate" type="string" value="on_self" />
+ <!-- we also want to remove shadow points -->
+ <param name="sensor_frame" type="string" value="laser_tilt_mount_link" />
+ </node>
+
+ <!-- assemble pointcloud into a full world view -->
+ <node pkg="point_cloud_assembler" type="point_cloud_assembler_srv" output="screen" name="point_cloud_assembler">
+ <remap from="scan_in" to="tilt_scan_cloud_annotated"/>
+ <param name="tf_cache_time_secs" type="double" value="10.0" />
+ <param name="tf_tolerance_secs" type="double" value="0.0" />
+ <param name="max_scans" type="int" value="400" />
+ <param name="ignore_laser_skew" type="bool" value="true" />
+ <param name="fixed_frame" type="string" value="torso_lift_link" />
+ <param name="downsample_factor" type="int" value="2" />
+ </node>
+
+ <node pkg="point_cloud_assembler" type="point_cloud_snapshotter" output="screen" name="snapshotter">
+ <remap from="laser_scanner_signal" to="laser_tilt_controller/laser_scanner_signal"/>
+ <remap from="build_cloud" to="point_cloud_assembler/build_cloud" />
+ <remap from="full_cloud" to="full_cloud_annotated" />
+ </node>
+
+ <!-- start collision map -->
+ <include file="$(find 3dnav_pr2)/launch/collision_map_occ.launch" />
+
+</launch>
Added: pkg/trunk/sandbox/3dnav_pr2/launch/narrow_stereoproc.launch
===================================================================
--- pkg/trunk/sandbox/3dnav_pr2/launch/narrow_stereoproc.launch (rev 0)
+++ pkg/trunk/sandbox/3dnav_pr2/launch/narrow_stereoproc.launch 2009-07-29 01:58:46 UTC (rev 19960)
@@ -0,0 +1,41 @@
+<launch>
+ <!-- videre_mode should be one of the following:
+ disparity: Disparity and rectification done on chip.
+ Provides: Disparity and left mono image
+ disparity_raw: Disparity done on chip (debayer and rectification in software).
+ Provides: disparity and left color image.
+ none: No stereo on chip (all processing done in software).
+ Provides: all 3 images available
+ rectified: Rectification on chip
+ Provides: all 3 images available but no color
+ -->
+ <!-- stereo processing parameters
+ texture_thresh: Threshold for removing bad disparities based on texture
+ Default value: 30
+ unique_thresh: Threshold for removing bad disparities based on ambiguity
+ Default value: 36
+ speckle_diff: Threshold for region-growing (1/16 pixel disparity)
+ Default value: 10
+ speckle_size: Threshold for disparity region size (pixels)
+ Default value: 100
+ horopter: X offset for close-in stereo (pixels)
+ Default value: 0
+ corr_size: Correlation window size (pixels)
+ Default value: 15
+ num_disp: Number of disparities (pixels)
+ Default value: 64
+ -->
+ <group ns="narrow_stereo">
+ <node pkg="stereo_image_proc" type="stereoproc" respawn="false" output="screen" name="stereoproc">
+ <param name="videre_mode" type="str" value="none"/>
+ <param name="do_colorize" type="bool" value="True"/>
+ <param name="do_rectify" type="bool" value="True"/>
+ <param name="do_stereo" type="bool" value="True"/>
+ <param name="do_calc_points" type="bool" value="True"/>
+ <param name="do_keep_coords" type="bool" value="True"/>
+ <param name="num_disp" type="int" value="128"/>
+ <param name="corr_size" type="int" value="7"/>
+ </node>
+ </group>
+</launch>
+
Added: pkg/trunk/sandbox/3dnav_pr2/launch/stereo-perception.launch
===================================================================
--- pkg/trunk/sandbox/3dnav_pr2/launch/stereo-perception.launch (rev 0)
+++ pkg/trunk/sandbox/3dnav_pr2/launch/stereo-perception.launch 2009-07-29 01:58:46 UTC (rev 19960)
@@ -0,0 +1,29 @@
+<launch>
+
+ <include file="$(find 3dnav_pr2)/launch/pr2_planning_environment.launch" />
+ <include file="$(find 3dnav_pr2)/launch/narrow_stereoproc.launch" />
+
+ <!-- remove points corresponding to known objects -->
+ <node pkg="planning_environment" type="clear_known_objects" respawn="false" output="screen">
+ <remap from="robot_description" to="robot_description" />
+
+<!-- define a frame that stays fixed for the known objects -->
+<!-- <param name="fixed_frame" type="string" value="/odom_combined" /> -->
+
+ <remap from="cloud_in" to="/narrow_stereo/cloud" />
+ <remap from="cloud_out" to="full_cloud_without_known_objects" />
+ <param name="object_scale" type="double" value="1.0" />
+ <param name="object_padd" type="double" value="0.025" />
+ </node>
+
+ <!-- add a channel that marks points that are on the robot -->
+ <node pkg="robot_self_filter" type="self_filter" respawn="true" output="screen">
+ <remap from="robot_description" to="robot_description" />
+ <remap from="cloud_in" to="full_cloud_without_known_objects" />
+ <remap from="cloud_out" to="full_cloud_annotated" />
+ <param name="annotate" type="string" value="on_self" />
+ </node>
+
+ <include file="$(find 3dnav_pr2)/launch/collision_map_occ.launch" />
+
+</launch>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|