|
From: <ehb...@us...> - 2009-08-10 11:16:54
|
Revision: 21391
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21391&view=rev
Author: ehberger
Date: 2009-08-10 11:16:47 +0000 (Mon, 10 Aug 2009)
Log Message:
-----------
Eliminating robot_msgs references
Modified Paths:
--------------
pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h
pkg/trunk/stacks/geometry/tf/include/tf/transform_listener.h
pkg/trunk/stacks/navigation/costmap_2d/src/costmap_test.cpp
pkg/trunk/stacks/semantic_mapping/door_handle_detector/test/test_door_detection_joystick.cpp
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/cloud_io/tools/cloudmsg_to_screen.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/polygonal_map_display.h
pkg/trunk/util/robot_self_filter/include/robot_self_filter/self_see_filter.h
Modified: pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h
===================================================================
--- pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h 2009-08-10 11:15:57 UTC (rev 21390)
+++ pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h 2009-08-10 11:16:47 UTC (rev 21391)
@@ -58,7 +58,7 @@
static const double QUATERNION_TOLERANCE = 0.1f;
-/** \brief The data type which will be cross compatable with robot_msgs
+/** \brief The data type which will be cross compatable with geometry_msgs
* this will require the associated rosTF package to convert */
template <typename T>
class Stamped : public T{
Modified: pkg/trunk/stacks/geometry/tf/include/tf/transform_listener.h
===================================================================
--- pkg/trunk/stacks/geometry/tf/include/tf/transform_listener.h 2009-08-10 11:15:57 UTC (rev 21390)
+++ pkg/trunk/stacks/geometry/tf/include/tf/transform_listener.h 2009-08-10 11:16:47 UTC (rev 21391)
@@ -115,7 +115,7 @@
- ///\todo move to high precision laser projector class void projectAndTransformLaserScan(const robot_msgs::LaserScan& scan_in, sensor_msgs::PointCloud& pcout);
+ ///\todo move to high precision laser projector class void projectAndTransformLaserScan(const sensor_msgs::LaserScan& scan_in, sensor_msgs::PointCloud& pcout);
bool getFrames(tf::FrameGraph::Request& req, tf::FrameGraph::Response& res)
{
Modified: pkg/trunk/stacks/navigation/costmap_2d/src/costmap_test.cpp
===================================================================
--- pkg/trunk/stacks/navigation/costmap_2d/src/costmap_test.cpp 2009-08-10 11:15:57 UTC (rev 21390)
+++ pkg/trunk/stacks/navigation/costmap_2d/src/costmap_test.cpp 2009-08-10 11:16:47 UTC (rev 21391)
@@ -50,7 +50,7 @@
#include <sensor_msgs/LaserScan.h>
#include <laser_scan/laser_scan.h>
-#include <robot_msgs/PointCloud.h>
+#include <sensor_msgs/PointCloud.h>
// Thread suppport
#include <boost/thread.hpp>
Modified: pkg/trunk/stacks/semantic_mapping/door_handle_detector/test/test_door_detection_joystick.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/door_handle_detector/test/test_door_detection_joystick.cpp 2009-08-10 11:15:57 UTC (rev 21390)
+++ pkg/trunk/stacks/semantic_mapping/door_handle_detector/test/test_door_detection_joystick.cpp 2009-08-10 11:16:47 UTC (rev 21391)
@@ -160,7 +160,7 @@
if(joy_msg_.data == std::string("open_door"))
{
geometry_msgs::PoseStamped pose_msg;
- robot_msgs::JointTraj traj;
+ manipulation_msgs::JointTraj traj;
pose_msg.pose = RPYToTransform(0.0,0.0,0.0,door_msg_from_detector_.handle.x, door_msg_from_detector_.handle.y, door_msg_from_detector_.handle.z);
pose_msg.header.frame_id = door_msg_from_detector_.header.frame_id;
Modified: pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/cloud_io/tools/cloudmsg_to_screen.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/cloud_io/tools/cloudmsg_to_screen.cpp 2009-08-10 11:15:57 UTC (rev 21390)
+++ pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/cloud_io/tools/cloudmsg_to_screen.cpp 2009-08-10 11:16:47 UTC (rev 21391)
@@ -30,7 +30,7 @@
/** \author Radu Bogdan Rusu
*
- * Extremely silly PCD to C++ ROS robot_msgs PointCloud converter.
+ * Extremely silly PCD to C++ ROS sensor_msgs PointCloud converter.
* Useful for tools which don't want to link against \a cloud_io (I guess).
*
*/
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/displays/polygonal_map_display.h
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/displays/polygonal_map_display.h 2009-08-10 11:15:57 UTC (rev 21390)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/polygonal_map_display.h 2009-08-10 11:16:47 UTC (rev 21391)
@@ -76,7 +76,7 @@
/**
* \class PolygonalMapDisplay
- * \brief Displays a robot_msgs::PolygonalMap message
+ * \brief Displays a mapping_msgs::PolygonalMap message
*/
class PolygonalMapDisplay : public Display
{
Modified: pkg/trunk/util/robot_self_filter/include/robot_self_filter/self_see_filter.h
===================================================================
--- pkg/trunk/util/robot_self_filter/include/robot_self_filter/self_see_filter.h 2009-08-10 11:15:57 UTC (rev 21390)
+++ pkg/trunk/util/robot_self_filter/include/robot_self_filter/self_see_filter.h 2009-08-10 11:16:47 UTC (rev 21391)
@@ -130,8 +130,8 @@
};
- typedef sensor_msgs::PointCloud robot_msgs_PointCloud;
- FILTERS_REGISTER_FILTER(SelfFilter, robot_msgs_PointCloud);
+ typedef sensor_msgs::PointCloud sensor_msgs_PointCloud;
+ FILTERS_REGISTER_FILTER(SelfFilter, sensor_msgs_PointCloud);
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|