|
From: <is...@us...> - 2009-06-19 22:27:31
|
Revision: 17380
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17380&view=rev
Author: isucan
Date: 2009-06-19 22:27:26 +0000 (Fri, 19 Jun 2009)
Log Message:
-----------
changed pointcloud processing to remove self filter on a line-by-line basis
Modified Paths:
--------------
pkg/trunk/demos/tabletop_manipulation/launch/laser-perception.launch
pkg/trunk/util/new_robot_self_filter/src/self_filter.cpp
Modified: pkg/trunk/demos/tabletop_manipulation/launch/laser-perception.launch
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/launch/laser-perception.launch 2009-06-19 22:24:01 UTC (rev 17379)
+++ pkg/trunk/demos/tabletop_manipulation/launch/laser-perception.launch 2009-06-19 22:27:26 UTC (rev 17380)
@@ -3,29 +3,6 @@
<include file="$(find pr2_defs)/pr2_planning_environment.launch" />
<include file="$(find pr2_laser_tilt)/laser_tilt_controller.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>
-
- <node pkg="new_robot_self_filter" type="self_filter" respawn="true" output="screen">
- <remap from="robot_description" to="robotdesc/pr2" />
- <remap from="cloud_in" to="snapshot_cloud" />
- <remap from="cloud_out" to="snapshot_cloud_filtered" />
- </node>
-
-
<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" />
@@ -39,6 +16,22 @@
<remap from="cloud_out" to="tilt_scan_cloud_filtered" />
</node>
+ <node pkg="point_cloud_assembler" type="point_cloud_assembler_srv" output="screen" name="point_cloud_assembler">
+ <remap from="scan_in" to="tilt_scan_cloud_filtered"/>
+ <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="snapshot_cloud" />
+ </node>
+
<include file="$(find collision_map)/collision_map.launch" />
</launch>
Modified: pkg/trunk/util/new_robot_self_filter/src/self_filter.cpp
===================================================================
--- pkg/trunk/util/new_robot_self_filter/src/self_filter.cpp 2009-06-19 22:24:01 UTC (rev 17379)
+++ pkg/trunk/util/new_robot_self_filter/src/self_filter.cpp 2009-06-19 22:27:26 UTC (rev 17380)
@@ -56,7 +56,7 @@
ros::WallTime tm = ros::WallTime::now();
sf_.update(*cloud, out);
double sec = (ros::WallTime::now() - tm).toSec();
- ROS_INFO("Self filter: reduced %d points to %d points in %f seconds", (int)cloud->pts.size(), (int)out.pts.size(), sec);
+ ROS_DEBUG("Self filter: reduced %d points to %d points in %f seconds", (int)cloud->pts.size(), (int)out.pts.size(), sec);
pointCloudPublisher_.publish(out);
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|