|
From: <is...@us...> - 2009-06-18 00:57:11
|
Revision: 17268
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17268&view=rev
Author: isucan
Date: 2009-06-18 00:55:11 +0000 (Thu, 18 Jun 2009)
Log Message:
-----------
added stereo perception launch file
Added Paths:
-----------
pkg/trunk/demos/tabletop_manipulation/launch/laser-perception.launch
pkg/trunk/demos/tabletop_manipulation/launch/stereo-perception.launch
Removed Paths:
-------------
pkg/trunk/demos/tabletop_manipulation/launch/perception.launch
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/point_cloud_assembler.launch
Added: pkg/trunk/demos/tabletop_manipulation/launch/laser-perception.launch
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/launch/laser-perception.launch (rev 0)
+++ pkg/trunk/demos/tabletop_manipulation/launch/laser-perception.launch 2009-06-18 00:55:11 UTC (rev 17268)
@@ -0,0 +1,27 @@
+<launch>
+
+ <include file="$(find pr2_defs)/pr2_planning_environment.launch" />
+
+ <node pkg="point_cloud_assembler" type="laser_scan_assembler_srv" output="screen" name="laser_scan_assembler">
+ <remap from="scan_in" to="tilt_scan"/>
+ <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="laser_scan_assembler/build_cloud" />
+ <remap from="full_cloud" to="snapshot_cloud" />
+ </node>
+
+ <include file="$(find pr2_laser_tilt)/laser_tilt_controller.launch" />
+
+ <node pkg="new_robot_self_filter" type="self_filter" args="robot_description:=robotdesc/pr2 full_cloud:=snapshot_cloud" respawn="true" output="screen" />
+
+ <include file="$(find collision_map)/collision_map.launch" />
+
+</launch>
Deleted: pkg/trunk/demos/tabletop_manipulation/launch/perception.launch
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/launch/perception.launch 2009-06-18 00:55:06 UTC (rev 17267)
+++ pkg/trunk/demos/tabletop_manipulation/launch/perception.launch 2009-06-18 00:55:11 UTC (rev 17268)
@@ -1,7 +0,0 @@
-<launch>
- <include file="$(find pr2_defs)/pr2_planning_environment.launch" />
- <include file="$(find pr2_laser_tilt)/laser_tilt_controller.launch" />
- <include file="$(find point_cloud_assembler)/point_cloud_assembler.launch" />
- <include file="$(find new_robot_self_filter)/self_filter.launch" />
- <include file="$(find collision_map)/collision_map.launch" />
-</launch>
Added: pkg/trunk/demos/tabletop_manipulation/launch/stereo-perception.launch
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/launch/stereo-perception.launch (rev 0)
+++ pkg/trunk/demos/tabletop_manipulation/launch/stereo-perception.launch 2009-06-18 00:55:11 UTC (rev 17268)
@@ -0,0 +1,10 @@
+<launch>
+
+ <include file="$(find pr2_defs)/pr2_planning_environment.launch" />
+ <include file="$(find stereo_image_proc)/stereo.launch" />
+
+ <node pkg="new_robot_self_filter" type="self_filter" args="robot_description:=robotdesc/pr2 full_cloud:=stereo/cloud" respawn="true" output="screen" />
+
+ <include file="$(find collision_map)/collision_map.launch" />
+
+</launch>
Deleted: pkg/trunk/drivers/robot/pr2/point_cloud_assembler/point_cloud_assembler.launch
===================================================================
--- pkg/trunk/drivers/robot/pr2/point_cloud_assembler/point_cloud_assembler.launch 2009-06-18 00:55:06 UTC (rev 17267)
+++ pkg/trunk/drivers/robot/pr2/point_cloud_assembler/point_cloud_assembler.launch 2009-06-18 00:55:11 UTC (rev 17268)
@@ -1,19 +0,0 @@
-<launch>
-
- <node pkg="point_cloud_assembler" type="laser_scan_assembler_srv" output="screen" name="laser_scan_assembler">
- <remap from="scan_in" to="tilt_scan"/>
- <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="laser_scan_assembler/build_cloud" />
- <remap from="full_cloud" to="snapshot_cloud" />
- </node>
-
-</launch>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|