|
From: <is...@us...> - 2009-08-26 21:34:25
|
Revision: 23034
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23034&view=rev
Author: isucan
Date: 2009-08-26 21:34:16 +0000 (Wed, 26 Aug 2009)
Log Message:
-----------
fixing some issues caused by the roscpp bug that adds '...' at the end of parameter values
Modified Paths:
--------------
pkg/trunk/mapping/collision_map/src/collision_map_self_occ.cpp
pkg/trunk/motion_planning/planning_environment/src/tools/clear_known_objects.cpp
pkg/trunk/sandbox/3dnav_pr2/launch/perception/bits/collision_map_self_occ.launch
pkg/trunk/sandbox/3dnav_pr2/launch/perception/bits/tilt_laser_self_filter.launch
pkg/trunk/util/robot_self_filter/src/self_filter.cpp
Modified: pkg/trunk/mapping/collision_map/src/collision_map_self_occ.cpp
===================================================================
--- pkg/trunk/mapping/collision_map/src/collision_map_self_occ.cpp 2009-08-26 21:32:48 UTC (rev 23033)
+++ pkg/trunk/mapping/collision_map/src/collision_map_self_occ.cpp 2009-08-26 21:34:16 UTC (rev 23034)
@@ -244,7 +244,7 @@
updateMap(obstacles);
double sec = (ros::WallTime::now() - tm).toSec();
- ROS_INFO("Updated collision map with %d points at %f Hz", currentMap_.size(), 1.0/sec);
+ ROS_INFO("Updated collision map with %d points at %f Hz", (int)currentMap_.size(), 1.0/sec);
publishCollisionMap(currentMap_, header_, cmapPublisher_);
mapProcessing_.unlock();
@@ -426,7 +426,7 @@
int main (int argc, char** argv)
{
- ros::init(argc, argv, "collision_map_self_occ", ros::init_options::AnonymousName);
+ ros::init(argc, argv, "collision_map_self_occ");
CollisionMapperOcc cm;
cm.run();
Modified: pkg/trunk/motion_planning/planning_environment/src/tools/clear_known_objects.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/tools/clear_known_objects.cpp 2009-08-26 21:32:48 UTC (rev 23033)
+++ pkg/trunk/motion_planning/planning_environment/src/tools/clear_known_objects.cpp 2009-08-26 21:34:16 UTC (rev 23034)
@@ -273,7 +273,7 @@
data_out.channels[j].values.push_back(cloud->channels[j].values[i]);
}
- ROS_DEBUG("Published filtered cloud (%d points out of %d)", data_out.points.size(), cloud->points.size());
+ ROS_DEBUG("Published filtered cloud (%d points out of %d)", (int)data_out.points.size(), (int)cloud->points.size());
cloudPublisher_.publish(data_out);
}
else
@@ -378,7 +378,6 @@
int main(int argc, char **argv)
{
- // Took out anonymous - bmm
ros::init(argc, argv, "clear_known_objects");
ClearKnownObjects cko;
Modified: pkg/trunk/sandbox/3dnav_pr2/launch/perception/bits/collision_map_self_occ.launch
===================================================================
--- pkg/trunk/sandbox/3dnav_pr2/launch/perception/bits/collision_map_self_occ.launch 2009-08-26 21:32:48 UTC (rev 23033)
+++ pkg/trunk/sandbox/3dnav_pr2/launch/perception/bits/collision_map_self_occ.launch 2009-08-26 21:34:16 UTC (rev 23034)
@@ -2,7 +2,7 @@
<include file="$(find 3dnav_pr2)/launch/prX.machine" />
- <node machine="four" pkg="collision_map" type="collision_map_self_occ_node" respawn="true" output="screen">
+ <node machine="four" pkg="collision_map" type="collision_map_self_occ_node" name="collision_map_self_occ_node" respawn="true" output="screen">
<remap from="cloud_in" to="full_cloud_filtered" />
<remap from="cloud_incremental_in" to="tilt_scan_cloud_filtered" />
Modified: pkg/trunk/sandbox/3dnav_pr2/launch/perception/bits/tilt_laser_self_filter.launch
===================================================================
--- pkg/trunk/sandbox/3dnav_pr2/launch/perception/bits/tilt_laser_self_filter.launch 2009-08-26 21:32:48 UTC (rev 23033)
+++ pkg/trunk/sandbox/3dnav_pr2/launch/perception/bits/tilt_laser_self_filter.launch 2009-08-26 21:34:16 UTC (rev 23034)
@@ -1,5 +1,5 @@
<launch>
- <node pkg="robot_self_filter" type="self_filter" respawn="true" output="screen">
+ <node pkg="robot_self_filter" type="self_filter" respawn="true" name="robot_self_filter" output="screen">
<!-- The topic for the input cloud -->
<remap from="cloud_in" to="tilt_scan_cloud_without_known_objects" />
Modified: pkg/trunk/util/robot_self_filter/src/self_filter.cpp
===================================================================
--- pkg/trunk/util/robot_self_filter/src/self_filter.cpp 2009-08-26 21:32:48 UTC (rev 23033)
+++ pkg/trunk/util/robot_self_filter/src/self_filter.cpp 2009-08-26 21:34:16 UTC (rev 23034)
@@ -191,7 +191,7 @@
int main(int argc, char **argv)
{
- ros::init(argc, argv, "self_filter", ros::init_options::AnonymousName);
+ ros::init(argc, argv, "self_filter");
SelfFilter s;
ros::spin();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|