|
From: <tf...@us...> - 2009-08-07 20:42:09
|
Revision: 21043
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21043&view=rev
Author: tfoote
Date: 2009-08-07 20:41:56 +0000 (Fri, 07 Aug 2009)
Log Message:
-----------
moving PoseArray into geometry_msgs #1907
Modified Paths:
--------------
pkg/trunk/stacks/navigation/amcl/src/amcl_node.cpp
pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp
pkg/trunk/stacks/navigation/fake_localization/manifest.xml
pkg/trunk/stacks/navigation/nav_view/manifest.xml
pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.cpp
pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.h
pkg/trunk/stacks/visualization/rviz/manifest.xml
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.h
Added Paths:
-----------
pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseArray.msg
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/nav_msgs/msg/PoseArray.msg
Copied: pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseArray.msg (from rev 20633, pkg/trunk/stacks/common_msgs/nav_msgs/msg/PoseArray.msg)
===================================================================
--- pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseArray.msg (rev 0)
+++ pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseArray.msg 2009-08-07 20:41:56 UTC (rev 21043)
@@ -0,0 +1,3 @@
+Header header
+
+geometry_msgs/Pose[] poses
Deleted: pkg/trunk/stacks/common_msgs/nav_msgs/msg/PoseArray.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/nav_msgs/msg/PoseArray.msg 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/common_msgs/nav_msgs/msg/PoseArray.msg 2009-08-07 20:41:56 UTC (rev 21043)
@@ -1,3 +0,0 @@
-Header header
-
-geometry_msgs/Pose[] poses
Modified: pkg/trunk/stacks/navigation/amcl/src/amcl_node.cpp
===================================================================
--- pkg/trunk/stacks/navigation/amcl/src/amcl_node.cpp 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/navigation/amcl/src/amcl_node.cpp 2009-08-07 20:41:56 UTC (rev 21043)
@@ -38,7 +38,7 @@
// Messages that I need
#include "sensor_msgs/LaserScan.h"
#include "geometry_msgs/PoseWithCovariance.h"
-#include "nav_msgs/PoseArray.h"
+#include "geometry_msgs/PoseArray.h"
#include "geometry_msgs/Pose.h"
#include "nav_msgs/GetMap.h"
#include "std_srvs/Empty.h"
@@ -320,7 +320,7 @@
laser_likelihood_max_dist);
ros::Node::instance()->advertise<geometry_msgs::PoseWithCovariance>("amcl_pose",2);
- ros::Node::instance()->advertise<nav_msgs::PoseArray>("particlecloud",2);
+ ros::Node::instance()->advertise<geometry_msgs::PoseArray>("particlecloud",2);
ros::Node::instance()->advertise<visualization_msgs::Polyline>("gui_laser",2);
ros::Node::instance()->advertiseService("global_localization",
&AmclNode::globalLocalizationCallback,
@@ -606,7 +606,7 @@
// Publish the resulting cloud
// TODO: set maximum rate for publishing
- nav_msgs::PoseArray cloud_msg;
+ geometry_msgs::PoseArray cloud_msg;
cloud_msg.header.stamp = ros::Time::now();
cloud_msg.header.frame_id = "map";
cloud_msg.set_poses_size(set->sample_count);
Modified: pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp
===================================================================
--- pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp 2009-08-07 20:41:56 UTC (rev 21043)
@@ -60,7 +60,7 @@
Publishes to (name / type):
- @b "amcl_pose" geometry_msgs/PoseWithCovariance : robot's estimated pose in the map, with covariance
-- @b "particlecloud" nav_msgs/PoseArray : fake set of poses being maintained by the filter (one paricle only).
+- @b "particlecloud" geometry_msgs/PoseArray : fake set of poses being maintained by the filter (one paricle only).
<hr>
@@ -74,7 +74,7 @@
#include <ros/time.h>
#include <geometry_msgs/PoseWithRatesStamped.h>
-#include <nav_msgs/PoseArray.h>
+#include <geometry_msgs/PoseArray.h>
#include <geometry_msgs/PoseWithCovariance.h>
#include <angles/angles.h>
@@ -92,7 +92,7 @@
FakeOdomNode(void) : ros::Node("fake_localization")
{
advertise<geometry_msgs::PoseWithCovariance>("amcl_pose",1);
- advertise<nav_msgs::PoseArray>("particlecloud",1);
+ advertise<geometry_msgs::PoseArray>("particlecloud",1);
m_tfServer = new tf::TransformBroadcaster();
m_tfListener = new tf::TransformListener(*this);
m_lastUpdate = ros::Time::now();
@@ -140,7 +140,7 @@
bool m_base_pos_received;
geometry_msgs::PoseWithRatesStamped m_basePosMsg;
- nav_msgs::PoseArray m_particleCloud;
+ geometry_msgs::PoseArray m_particleCloud;
geometry_msgs::PoseWithCovariance m_currentPos;
//parameter for what odom to use
Modified: pkg/trunk/stacks/navigation/fake_localization/manifest.xml
===================================================================
--- pkg/trunk/stacks/navigation/fake_localization/manifest.xml 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/navigation/fake_localization/manifest.xml 2009-08-07 20:41:56 UTC (rev 21043)
@@ -7,6 +7,7 @@
<depend package="roscpp" />
<depend package="rosconsole" />
<depend package="nav_msgs" />
+ <depend package="geometry_msgs" />
<depend package="robot_msgs" />
<depend package="tf" />
<depend package="angles" />
Modified: pkg/trunk/stacks/navigation/nav_view/manifest.xml
===================================================================
--- pkg/trunk/stacks/navigation/nav_view/manifest.xml 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/navigation/nav_view/manifest.xml 2009-08-07 20:41:56 UTC (rev 21043)
@@ -7,6 +7,7 @@
<depend package="roscpp"/>
<depend package="robot_srvs"/>
<depend package="nav_msgs"/>
+ <depend package="geometry_msgs"/>
<depend package="tf"/>
<depend package="ogre"/>
<depend package="ogre_tools"/>
Modified: pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.cpp
===================================================================
--- pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.cpp 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.cpp 2009-08-07 20:41:56 UTC (rev 21043)
@@ -32,7 +32,7 @@
#include "ogre_tools/wx_ogre_render_window.h"
#include "nav_msgs/GetMap.h"
-#include "nav_msgs/PoseArray.h"
+#include "geometry_msgs/PoseArray.h"
#include <tf/transform_listener.h>
@@ -474,7 +474,7 @@
queueRender();
}
-void NavViewPanel::incomingPoseArray(const nav_msgs::PoseArray::ConstPtr& msg)
+void NavViewPanel::incomingPoseArray(const geometry_msgs::PoseArray::ConstPtr& msg)
{
if ( !cloud_object_ )
{
Modified: pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.h
===================================================================
--- pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.h 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.h 2009-08-07 20:41:56 UTC (rev 21043)
@@ -32,7 +32,7 @@
#include "nav_view_panel_generated.h"
-#include "nav_msgs/PoseArray.h"
+#include "geometry_msgs/PoseArray.h"
#include "geometry_msgs/PoseStamped.h"
#include "visualization_msgs/Polyline.h"
#include "geometry_msgs/PoseWithCovariance.h"
@@ -89,7 +89,7 @@
@section topic ROS topics
Subscribes to (name/type):
-- @b "particlecloud"nav_msgs/PoseArray : a set particles from a probabilistic localization system. Rendered is a set of small arrows.
+- @b "particlecloud"geometry_msgs/PoseArray : a set particles from a probabilistic localization system. Rendered is a set of small arrows.
- @b "gui_path"/Polyline : a path from a planner. Rendered as a dashed line.
- @b "gui_laser"/Polyline : re-projected laser scan from a planner. Rendered as a set of points.
- @b "local_path"/Polyline : local path from a planner. Rendered as a dashed line.
@@ -164,7 +164,7 @@
void loadMap();
void clearMap();
- void incomingPoseArray(const nav_msgs::PoseArray::ConstPtr& msg);
+ void incomingPoseArray(const geometry_msgs::PoseArray::ConstPtr& msg);
void incomingGuiPath(const visualization_msgs::Polyline::ConstPtr& msg);
void incomingLocalPath(const visualization_msgs::Polyline::ConstPtr& msg);
void incomingRobotFootprint(const visualization_msgs::Polyline::ConstPtr& msg);
Modified: pkg/trunk/stacks/visualization/rviz/manifest.xml
===================================================================
--- pkg/trunk/stacks/visualization/rviz/manifest.xml 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/visualization/rviz/manifest.xml 2009-08-07 20:41:56 UTC (rev 21043)
@@ -16,6 +16,7 @@
<depend package="std_msgs"/>
<depend package="robot_msgs"/>
<depend package="sensor_msgs"/>
+ <depend package="geometry_msgs"/>
<depend package="nav_msgs"/>
<depend package="mechanism_msgs" />
<depend package="deprecated_msgs"/>
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.cpp
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.cpp 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.cpp 2009-08-07 20:41:56 UTC (rev 21043)
@@ -168,7 +168,7 @@
topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Topic", property_prefix_, boost::bind( &ParticleCloud2DDisplay::getTopic, this ),
boost::bind( &ParticleCloud2DDisplay::setTopic, this, _1 ), category_, this );
ROSTopicStringPropertyPtr topic_prop = topic_property_.lock();
- topic_prop->setMessageType(nav_msgs::PoseArray::__s_getDataType());
+ topic_prop->setMessageType(geometry_msgs::PoseArray::__s_getDataType());
}
void ParticleCloud2DDisplay::fixedFrameChanged()
@@ -180,7 +180,7 @@
{
}
-void ParticleCloud2DDisplay::processMessage(const nav_msgs::PoseArray::ConstPtr& msg)
+void ParticleCloud2DDisplay::processMessage(const geometry_msgs::PoseArray::ConstPtr& msg)
{
clear();
@@ -275,7 +275,7 @@
causeRender();
}
-void ParticleCloud2DDisplay::incomingMessage(const nav_msgs::PoseArray::ConstPtr& msg)
+void ParticleCloud2DDisplay::incomingMessage(const geometry_msgs::PoseArray::ConstPtr& msg)
{
processMessage(msg);
}
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.h
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.h 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.h 2009-08-07 20:41:56 UTC (rev 21043)
@@ -35,7 +35,7 @@
#include "helpers/color.h"
#include "properties/forwards.h"
-#include <nav_msgs/PoseArray.h>
+#include <geometry_msgs/PoseArray.h>
#include <ros/ros.h>
@@ -84,8 +84,8 @@
void subscribe();
void unsubscribe();
void clear();
- void incomingMessage(const nav_msgs::PoseArray::ConstPtr& msg);
- void processMessage(const nav_msgs::PoseArray::ConstPtr& msg);
+ void incomingMessage(const geometry_msgs::PoseArray::ConstPtr& msg);
+ void processMessage(const geometry_msgs::PoseArray::ConstPtr& msg);
// overrides from Display
virtual void onEnable();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|