|
From: <tpr...@us...> - 2009-08-24 20:52:27
|
Revision: 22748
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=22748&view=rev
Author: tpratkanis
Date: 2009-08-24 20:52:00 +0000 (Mon, 24 Aug 2009)
Log Message:
-----------
Fix scan to cloud extrapolation issues.
Modified Paths:
--------------
pkg/trunk/demos/door_demos_gazebo/launch/pr2_door_test.launch
pkg/trunk/stacks/common/laser_scan/src/scan_to_cloud.cpp
Modified: pkg/trunk/demos/door_demos_gazebo/launch/pr2_door_test.launch
===================================================================
--- pkg/trunk/demos/door_demos_gazebo/launch/pr2_door_test.launch 2009-08-24 20:47:22 UTC (rev 22747)
+++ pkg/trunk/demos/door_demos_gazebo/launch/pr2_door_test.launch 2009-08-24 20:52:00 UTC (rev 22748)
@@ -5,5 +5,7 @@
<!--<node pkg="rosrecord" type="rosrecord" args=" -f door_demos_test.bag " />-->
<test test-name="door_demos_test_open_door" pkg="door_demos_gazebo" type="door_demo_test_exec_test.py" time-limit="1000" />
<node pkg="rostopic" type="rostopic" args="list" output="screen" />
+ <param name="/base_shadow_filter/notifier_tolerance" value="0.09" type="double" />
+ <param name="/tilt_shadow_filter/notifier_tolerance" value="0.09" type="double" />
</launch>
Modified: pkg/trunk/stacks/common/laser_scan/src/scan_to_cloud.cpp
===================================================================
--- pkg/trunk/stacks/common/laser_scan/src/scan_to_cloud.cpp 2009-08-24 20:47:22 UTC (rev 22747)
+++ pkg/trunk/stacks/common/laser_scan/src/scan_to_cloud.cpp 2009-08-24 20:52:00 UTC (rev 22748)
@@ -75,6 +75,7 @@
// TF
tf::TransformListener* tf_;
tf::MessageNotifier<sensor_msgs::LaserScan>* notifier_;
+ double tf_tolerance_;
filters::FilterChain<sensor_msgs::PointCloud> cloud_filter_chain_;
filters::FilterChain<sensor_msgs::LaserScan> scan_filter_chain_;
@@ -93,10 +94,11 @@
ros::Node::instance()->param ("~scan_topic", scan_topic_, std::string("tilt_scan"));
ros::Node::instance()->param ("~cloud_topic", cloud_topic_, std::string("tilt_laser_cloud_filtered"));
ros::Node::instance()->param ("~laser_max_range", laser_max_range_, DBL_MAX);
+ ros::Node::instance()->param ("~notifier_tolerance", tf_tolerance_, 0.03);
notifier_ = new tf::MessageNotifier<sensor_msgs::LaserScan>(tf_, ros::Node::instance(),
boost::bind(&ScanShadowsFilter::scanCallback, this, _1), scan_topic_, "base_link", 50);
- notifier_->setTolerance(ros::Duration(0.03));
+ notifier_->setTolerance(ros::Duration(tf_tolerance_));
ros::Node::instance()->advertise<sensor_msgs::PointCloud> (cloud_topic_, 10);
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|