|
From: <tf...@us...> - 2009-02-10 06:59:06
|
Revision: 10909
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=10909&view=rev
Author: tfoote
Date: 2009-02-10 06:59:02 +0000 (Tue, 10 Feb 2009)
Log Message:
-----------
deprecating RobotBase2DOdom and Pose2DFloat32
Modified Paths:
--------------
pkg/trunk/calibration/wheel_odometry_calibration/manifest.xml
pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller_pos.h
pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller_pos.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_dynamics_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_odom.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_run_base_controller.cpp
pkg/trunk/deprecated/robot_model/include/robot_model/knode.h
pkg/trunk/drivers/robot/erratic_player/erratic_player.cc
pkg/trunk/drivers/robot/pr2/pr2_phase_space/manifest.xml
pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_fake_localization.cpp
pkg/trunk/drivers/robot/segway_apox/manifest.xml
pkg/trunk/drivers/robot/segway_apox/segway.cpp
pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.h
pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/move_base.hh
pkg/trunk/highlevel/highlevel_controllers/manifest.xml
pkg/trunk/highlevel/highlevel_controllers/msg/RechargeGoal.msg
pkg/trunk/highlevel/highlevel_controllers/msg/RechargeState.msg
pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp
pkg/trunk/highlevel/highlevel_controllers/src/move_base_follow.cpp
pkg/trunk/highlevel/highlevel_controllers/src/move_base_navfn.cpp
pkg/trunk/highlevel/highlevel_controllers/src/move_base_sbpl.cpp
pkg/trunk/highlevel/highlevel_controllers/src/move_base_topological.cpp
pkg/trunk/motion_planning/mpglue/src/plan.cpp
pkg/trunk/motion_planning/mpglue/src/plan.h
pkg/trunk/motion_planning/mpglue/src/planner.h
pkg/trunk/motion_planning/mpglue/src/sbpl_environment.cpp
pkg/trunk/motion_planning/mpglue/src/sbpl_environment.h
pkg/trunk/nav/amcl_player/amcl_player.cc
pkg/trunk/nav/amcl_player/cli.cpp
pkg/trunk/nav/amcl_player/manifest.xml
pkg/trunk/nav/deadreckon/deadreckon.cpp
pkg/trunk/nav/deadreckon/manifest.xml
pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/governor_node.h
pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/trajectory_controller_ros.h
pkg/trunk/nav/trajectory_rollout/manifest.xml
pkg/trunk/nav/trajectory_rollout/msg/ScoreMap2D.msg
pkg/trunk/nav/trajectory_rollout/src/trajectory_controller_ros.cpp
pkg/trunk/prcore/robot_msgs/manifest.xml
pkg/trunk/prcore/robot_msgs/msg/MapMetaData.msg
pkg/trunk/prcore/robot_msgs/msg/OccMap2D.msg
pkg/trunk/prcore/robot_msgs/msg/Planner2DGoal.msg
pkg/trunk/prcore/robot_msgs/msg/Planner2DState.msg
pkg/trunk/prcore/robot_srvs/manifest.xml
pkg/trunk/simulators/rosstage/manifest.xml
pkg/trunk/simulators/rosstage/rosstage.cc
pkg/trunk/util/logsetta/carmen/carmen_logger/carmen_logger.cpp
pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp
pkg/trunk/util/logsetta/localize_extract/localize_extract.cpp
pkg/trunk/util/logsetta/odom/odom_extract.cpp
pkg/trunk/visualization/multitouch_nav/manifest.xml
pkg/trunk/visualization/multitouch_nav/skeleton.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/robot_base2d_pose_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/robot_base2d_pose_display.h
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/tools/pose_tool.cpp
pkg/trunk/world_models/topological_map/include/topological_map/ros_topological_planner.h
pkg/trunk/world_models/topological_map/manifest.xml
pkg/trunk/world_models/topological_map/srv/ConnectorCosts.srv
pkg/trunk/world_models/topological_map/srv/Nav2DPlan.srv
pkg/trunk/world_models/topological_map/srv/NavigationCost.srv
Added Paths:
-----------
pkg/trunk/deprecated/deprecated_msgs/msg/Pose2DFloat32.msg
pkg/trunk/deprecated/deprecated_msgs/msg/RobotBase2DOdom.msg
Modified: pkg/trunk/calibration/wheel_odometry_calibration/manifest.xml
===================================================================
--- pkg/trunk/calibration/wheel_odometry_calibration/manifest.xml 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/calibration/wheel_odometry_calibration/manifest.xml 2009-02-10 06:59:02 UTC (rev 10909)
@@ -5,6 +5,7 @@
<review status="unreviewed" notes=""/>
<depend package="tf" />
<depend package="std_msgs" />
+ <depend package="deprecated_msgs" />
<depend package="roscpp" />
<depend package="pr2_mechanism_controllers" />
</package>
Modified: pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.h
===================================================================
--- pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.h 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.h 2009-02-10 06:59:02 UTC (rev 10909)
@@ -42,7 +42,7 @@
// messages
-#include "std_msgs/RobotBase2DOdom.h"
+#include "deprecated_msgs/RobotBase2DOdom.h"
#include "std_msgs/PoseDot.h"
#include "std_msgs/PoseWithRatesStamped.h"
#include "robot_msgs/MechanismState.h"
@@ -79,7 +79,7 @@
void AngleOverflowCorrect(double& a, double ref);
// messages to receive
- std_msgs::RobotBase2DOdom _odom;
+ deprecated_msgs::RobotBase2DOdom _odom;
std_msgs::PoseWithRatesStamped _imu;
robot_msgs::MechanismState _mech;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller.h 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller.h 2009-02-10 06:59:02 UTC (rev 10909)
@@ -53,7 +53,7 @@
#include <newmat10/newmatio.h>
#include <newmat10/newmatap.h>
-#include <std_msgs/RobotBase2DOdom.h>
+#include <deprecated_msgs/RobotBase2DOdom.h>
#include <std_msgs/PoseDot.h>
#include <pr2_msgs/Odometer.h>
#include <pr2_msgs/Covariance2D.h>
@@ -185,9 +185,9 @@
void getOdometry(double &x, double &y, double &w, double &vx, double &vy, double &vw);
/*!
- * \brief Fill a structure of the form std_msgs::RobotBase2DOdom with odometry data
+ * \brief Fill a structure of the form deprecated_msgs::RobotBase2DOdom with odometry data
*/
- void setOdomMessage(std_msgs::RobotBase2DOdom &odom_msg_);
+ void setOdomMessage(deprecated_msgs::RobotBase2DOdom &odom_msg_);
/*!
* \brief compute the desired wheel speeds
@@ -502,9 +502,9 @@
boost::mutex ros_lock_;
/*!
- * \brief std_msgs representation of an odometry message
+ * \brief deprecated_msgs representation of an odometry message
*/
- std_msgs::RobotBase2DOdom odom_msg_;
+ deprecated_msgs::RobotBase2DOdom odom_msg_;
double last_time_message_sent_ ;/** last time odometry message was published */
@@ -512,7 +512,7 @@
double odom_publish_rate_; /** rate at which odometry message will be published ( = 1/odom_publish_delta_t_)*/
- realtime_tools::RealtimePublisher <std_msgs::RobotBase2DOdom>* publisher_ ; //!< Publishes the odometry msg from the update() realtime loop
+ realtime_tools::RealtimePublisher <deprecated_msgs::RobotBase2DOdom>* publisher_ ; //!< Publishes the odometry msg from the update() realtime loop
realtime_tools::RealtimePublisher <tf::tfMessage>* transform_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller_pos.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller_pos.h 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller_pos.h 2009-02-10 06:59:02 UTC (rev 10909)
@@ -55,7 +55,7 @@
#include <newmat10/newmatio.h>
#include <newmat10/newmatap.h>
-#include <std_msgs/RobotBase2DOdom.h>
+#include <deprecated_msgs/RobotBase2DOdom.h>
#include <std_msgs/PoseDot.h>
#include <pr2_msgs/Odometer.h>
#include <pr2_msgs/Covariance2D.h>
@@ -188,9 +188,9 @@
void getOdometry(double &x, double &y, double &w, double &vx, double &vy, double &vw);
/*!
- * \brief Fill a structure of the form std_msgs::RobotBase2DOdom with odometry data
+ * \brief Fill a structure of the form deprecated_msgs::RobotBase2DOdom with odometry data
*/
- void setOdomMessage(std_msgs::RobotBase2DOdom &odom_msg_);
+ void setOdomMessage(deprecated_msgs::RobotBase2DOdom &odom_msg_);
/*!
* \brief compute the desired wheel speeds
@@ -491,7 +491,7 @@
/*!
* \brief std_msgs representation of an odometry message
*/
- std_msgs::RobotBase2DOdom odom_msg_;
+ deprecated_msgs::RobotBase2DOdom odom_msg_;
double last_time_message_sent_ ;/** last time odometry message was published */
@@ -499,7 +499,7 @@
double odom_publish_rate_; /** rate at which odometry message will be published ( = 1/odom_publish_delta_t_)*/
- realtime_tools::RealtimePublisher <std_msgs::RobotBase2DOdom>* publisher_ ; //!< Publishes the odometry msg from the update() realtime loop
+ realtime_tools::RealtimePublisher <deprecated_msgs::RobotBase2DOdom>* publisher_ ; //!< Publishes the odometry msg from the update() realtime loop
realtime_tools::RealtimePublisher <tf::tfMessage>* transform_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml 2009-02-10 06:59:02 UTC (rev 10909)
@@ -14,6 +14,7 @@
<depend package="rospy" />
<depend package="libTF" />
<depend package="std_msgs" />
+ <depend package="deprecated_msgs" />
<depend package="pr2_msgs" />
<depend package="robot_msgs" />
<depend package="robot_kinematics" />
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp 2009-02-10 06:59:02 UTC (rev 10909)
@@ -571,7 +571,7 @@
base_casters_[i].controller_.update();
}
-void BaseController::setOdomMessage(std_msgs::RobotBase2DOdom &odom_msg_)
+void BaseController::setOdomMessage(deprecated_msgs::RobotBase2DOdom &odom_msg_)
{
odom_msg_.header.frame_id = "odom";
odom_msg_.header.stamp.sec = (unsigned long)floor(robot_state_->hw_->current_time_);
@@ -1081,7 +1081,7 @@
if (publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete publisher_ ;
- publisher_ = new realtime_tools::RealtimePublisher <std_msgs::RobotBase2DOdom> ("odom", 1) ;
+ publisher_ = new realtime_tools::RealtimePublisher <deprecated_msgs::RobotBase2DOdom> ("odom", 1) ;
if (odometer_publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete odometer_publisher_ ;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller_pos.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller_pos.cpp 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller_pos.cpp 2009-02-10 06:59:02 UTC (rev 10909)
@@ -680,7 +680,7 @@
base_casters_[i].position_controller_.update();
}
-void BaseControllerPos::setOdomMessage(std_msgs::RobotBase2DOdom &odom_msg_)
+void BaseControllerPos::setOdomMessage(deprecated_msgs::RobotBase2DOdom &odom_msg_)
{
odom_msg_.header.frame_id = "odom";
odom_msg_.header.stamp.sec = (unsigned long)floor(robot_state_->hw_->current_time_);
@@ -1148,7 +1148,7 @@
if (publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete publisher_ ;
- publisher_ = new realtime_tools::RealtimePublisher <std_msgs::RobotBase2DOdom> ("odom", 1) ;
+ publisher_ = new realtime_tools::RealtimePublisher <deprecated_msgs::RobotBase2DOdom> ("odom", 1) ;
if (odometer_publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete odometer_publisher_ ;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_dynamics_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_dynamics_controller.cpp 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_dynamics_controller.cpp 2009-02-10 06:59:02 UTC (rev 10909)
@@ -35,7 +35,7 @@
#include <libTF/libTF.h>
#include <ros/node.h>
#include <robot_srvs/SetJointCmd.h>
-#include <std_msgs/RobotBase2DOdom.h>
+#include <deprecated_msgs/RobotBase2DOdom.h>
static int done = 0;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/test/test_odom.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/test/test_odom.cpp 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/test/test_odom.cpp 2009-02-10 06:59:02 UTC (rev 10909)
@@ -35,7 +35,7 @@
#include <libTF/libTF.h>
#include <ros/node.h>
#include <std_msgs/PoseDot.h>
-#include <std_msgs/RobotBase2DOdom.h>
+#include <deprecated_msgs/RobotBase2DOdom.h>
#include <std_msgs/Quaternion.h>
#include <iostream>
#include <fstream>
@@ -87,7 +87,7 @@
~test_run_base() {}
- std_msgs::RobotBase2DOdom odom;
+ deprecated_msgs::RobotBase2DOdom odom;
void odomMsgReceived()
{
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/test/test_run_base_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/test/test_run_base_controller.cpp 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/test/test_run_base_controller.cpp 2009-02-10 06:59:02 UTC (rev 10909)
@@ -36,7 +36,7 @@
#include <ros/node.h>
#include <std_msgs/PoseWithRatesStamped.h>
#include <std_msgs/PoseDot.h>
-#include <std_msgs/RobotBase2DOdom.h>
+#include <deprecated_msgs/RobotBase2DOdom.h>
#include <std_msgs/Quaternion.h>
static int done = 0;
@@ -88,7 +88,7 @@
std_msgs::PoseWithRatesStamped ground_truth;
- std_msgs::RobotBase2DOdom odom;
+ deprecated_msgs::RobotBase2DOdom odom;
int subscriber_connected;
Added: pkg/trunk/deprecated/deprecated_msgs/msg/Pose2DFloat32.msg
===================================================================
--- pkg/trunk/deprecated/deprecated_msgs/msg/Pose2DFloat32.msg (rev 0)
+++ pkg/trunk/deprecated/deprecated_msgs/msg/Pose2DFloat32.msg 2009-02-10 06:59:02 UTC (rev 10909)
@@ -0,0 +1,3 @@
+float32 x
+float32 y
+float32 th
Added: pkg/trunk/deprecated/deprecated_msgs/msg/RobotBase2DOdom.msg
===================================================================
--- pkg/trunk/deprecated/deprecated_msgs/msg/RobotBase2DOdom.msg (rev 0)
+++ pkg/trunk/deprecated/deprecated_msgs/msg/RobotBase2DOdom.msg 2009-02-10 06:59:02 UTC (rev 10909)
@@ -0,0 +1,4 @@
+Header header
+Pose2DFloat32 pos
+Pose2DFloat32 vel
+byte stall
Modified: pkg/trunk/deprecated/robot_model/include/robot_model/knode.h
===================================================================
--- pkg/trunk/deprecated/robot_model/include/robot_model/knode.h 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/deprecated/robot_model/include/robot_model/knode.h 2009-02-10 06:59:02 UTC (rev 10909)
@@ -47,7 +47,7 @@
#include <ros/time.h>
#include <urdf/URDF.h>
#include <planning_models/kinematic.h>
-#include <std_msgs/RobotBase2DOdom.h>
+#include <deprecated_msgs/RobotBase2DOdom.h>
#include <tf/transform_listener.h>
#include <cmath>
@@ -301,7 +301,7 @@
tf::TransformListener m_tf;
ros::Node *m_node;
- std_msgs::RobotBase2DOdom m_localizedPose;
+ deprecated_msgs::RobotBase2DOdom m_localizedPose;
bool m_haveBasePos;
robot_msgs::MechanismState m_mechanismState;
Modified: pkg/trunk/drivers/robot/erratic_player/erratic_player.cc
===================================================================
--- pkg/trunk/drivers/robot/erratic_player/erratic_player.cc 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/drivers/robot/erratic_player/erratic_player.cc 2009-02-10 06:59:02 UTC (rev 10909)
@@ -86,7 +86,7 @@
//rosTF
#include "tf/transform_broadcaster.h"
// Messages that I need
-#include <std_msgs/RobotBase2DOdom.h>
+#include <deprecated_msgs/RobotBase2DOdom.h>
//#include <std_msgs/RobotBase2DCmdVel.h>
#include <std_msgs/PoseDot.h>
#include <robot_msgs/BatteryState.h>
@@ -102,7 +102,7 @@
public:
QueuePointer q;
- std_msgs::RobotBase2DOdom odom;
+ deprecated_msgs::RobotBase2DOdom odom;
std_msgs::PoseDot cmdvel;
tf::TransformBroadcaster tf;
@@ -118,7 +118,7 @@
// TODO: remove XDR dependency
playerxdr_ftable_init();
- advertise<std_msgs::RobotBase2DOdom>("odom", 1);
+ advertise<deprecated_msgs::RobotBase2DOdom>("odom", 1);
advertise<robot_msgs::BatteryState>("battery_state", 1);
// The Player address that will be assigned to this device. The format
Modified: pkg/trunk/drivers/robot/pr2/pr2_phase_space/manifest.xml
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_phase_space/manifest.xml 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/drivers/robot/pr2/pr2_phase_space/manifest.xml 2009-02-10 06:59:02 UTC (rev 10909)
@@ -5,6 +5,7 @@
<review status="unreviewed" notes=""/>
<depend package="roscpp" />
<depend package="std_msgs" />
+ <depend package="deprecated_msgs" />
<depend package="robot_msgs" />
<depend package="phase_space" />
<depend package="tf" />
Modified: pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_fake_localization.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_fake_localization.cpp 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_fake_localization.cpp 2009-02-10 06:59:02 UTC (rev 10909)
@@ -46,7 +46,7 @@
#include "robot_msgs/MocapBody.h"
#include "std_msgs/Transform.h"
-#include "std_msgs/RobotBase2DOdom.h"
+#include "deprecated_msgs/RobotBase2DOdom.h"
#include "std_msgs/PoseWithRatesStamped.h"
#include <tf/tf.h>
@@ -74,7 +74,7 @@
param("~publish_transform", publish_transform_, true) ;
param("~base_id", base_id_, 1) ;
- advertise<std_msgs::RobotBase2DOdom>("localizedpose", 1);
+ advertise<deprecated_msgs::RobotBase2DOdom>("localizedpose", 1);
advertise<std_msgs::PoseWithRatesStamped>("base_pose_ground_truth", 1) ;
m_tfServer = new tf::TransformBroadcaster(*this);
@@ -151,7 +151,7 @@
private:
robot_msgs::MocapSnapshot snapshot_;
- std_msgs::RobotBase2DOdom m_currentPos;
+ deprecated_msgs::RobotBase2DOdom m_currentPos;
tf::TransformBroadcaster *m_tfServer;
unsigned int publish_success_count_ ;
unsigned int publish_attempt_count_ ;
Modified: pkg/trunk/drivers/robot/segway_apox/manifest.xml
===================================================================
--- pkg/trunk/drivers/robot/segway_apox/manifest.xml 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/drivers/robot/segway_apox/manifest.xml 2009-02-10 06:59:02 UTC (rev 10909)
@@ -3,6 +3,7 @@
<license>BSD</license>
<review status="unreviewed" notes=""/>
<depend package="std_msgs"/>
+ <depend package="deprecated_msgs"/>
<depend package="roscpp"/>
<depend package="tf"/>
</package>
Modified: pkg/trunk/drivers/robot/segway_apox/segway.cpp
===================================================================
--- pkg/trunk/drivers/robot/segway_apox/segway.cpp 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/drivers/robot/segway_apox/segway.cpp 2009-02-10 06:59:02 UTC (rev 10909)
@@ -4,7 +4,7 @@
#include "ros/node.h"
#include "boost/thread/mutex.hpp"
#include "std_msgs/PoseDot.h"
-#include "std_msgs/RobotBase2DOdom.h"
+#include "deprecated_msgs/RobotBase2DOdom.h"
#include "std_msgs/String.h"
#include "rmp_frame.h"
extern "C" {
@@ -34,7 +34,7 @@
static const int max_x_stepsize = 5, max_yaw_stepsize = 2;
std_msgs::PoseDot cmd_vel;
- std_msgs::RobotBase2DOdom odom;
+ deprecated_msgs::RobotBase2DOdom odom;
std_msgs::String op_mode;
rmp_frame_t rmp;
dgc_usbcan_p can;
@@ -68,7 +68,7 @@
req_timeout(false)
{
odom.header.frame_id = "odom";
- advertise<std_msgs::RobotBase2DOdom>("odom", 1);
+ advertise<deprecated_msgs::RobotBase2DOdom>("odom", 1);
subscribe("cmd_vel", cmd_vel, &Segway::cmd_vel_cb, 1);
subscribe("operating_mode", op_mode, &Segway::op_mode_cb, 1);
}
Modified: pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.h
===================================================================
--- pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.h 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.h 2009-02-10 06:59:02 UTC (rev 10909)
@@ -43,7 +43,7 @@
#include "odom_estimation.h"
// messages
-#include "std_msgs/RobotBase2DOdom.h"
+#include "deprecated_msgs/RobotBase2DOdom.h"
#include "std_msgs/PoseDot.h"
#include "std_msgs/PoseWithRatesStamped.h"
#include "std_msgs/PoseStamped.h"
@@ -91,7 +91,7 @@
// messages to receive
std_msgs::PoseDot vel_;
- std_msgs::RobotBase2DOdom odom_;
+ deprecated_msgs::RobotBase2DOdom odom_;
std_msgs::PoseWithRatesStamped imu_;
robot_msgs::VOPose vo_;
Modified: pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/move_base.hh
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/move_base.hh 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/move_base.hh 2009-02-10 06:59:02 UTC (rev 10909)
@@ -56,7 +56,7 @@
#include <robot_msgs/Planner2DGoal.h>
#include <std_msgs/PoseDot.h>
#include <laser_scan/LaserScan.h>
-#include <std_msgs/RobotBase2DOdom.h>
+#include <deprecated_msgs/RobotBase2DOdom.h>
#include <std_msgs/PointCloud.h>
// For transform support
@@ -124,7 +124,7 @@
* @brief Overwrites the current plan with a new one. Will handle suitable publication
* @see publishPlan
*/
- void updatePlan(const std::list<std_msgs::Pose2DFloat32>& newPlan);
+ void updatePlan(const std::list<deprecated_msgs::Pose2DFloat32>& newPlan);
/**
* @brief Overwrites the current plan with a new one. Will handle suitable publication
@@ -199,7 +199,7 @@
*/
void stopRobot();
- void publishPath(bool isGlobal, const std::list<std_msgs::Pose2DFloat32>& path);
+ void publishPath(bool isGlobal, const std::list<deprecated_msgs::Pose2DFloat32>& path);
void publishFootprint(double x, double y, double th);
@@ -230,7 +230,7 @@
std_msgs::PointCloud tiltCloudMsg_; /**< Filled by subscriber with new tilte laser scans */
std_msgs::PointCloud groundPlaneCloudMsg_; /**< Filled by subscriber with point clouds */
std_msgs::PointCloud stereoCloudMsg_; /**< Filled by subscriber with point clouds */
- std_msgs::RobotBase2DOdom odomMsg_; /**< Odometry in the odom frame picked up by subscription */
+ deprecated_msgs::RobotBase2DOdom odomMsg_; /**< Odometry in the odom frame picked up by subscription */
laser_scan::LaserProjection projector_; /**< Used to project laser scans */
tf::TransformListener tf_; /**< Used to do transforms */
@@ -258,13 +258,13 @@
tf::Stamped<tf::Pose> global_pose_; /**< The global pose in the map frame */
- std_msgs::RobotBase2DOdom base_odom_; /**< Odometry in the base frame */
+ deprecated_msgs::RobotBase2DOdom base_odom_; /**< Odometry in the base frame */
/** Parameters that will be passed on initialization soon */
double baseLaserMaxRange_; /**< Used in laser scan projection */
double tiltLaserMaxRange_; /**< Used in laser scan projection */
- std::list<std_msgs::Pose2DFloat32> plan_; /**< The 2D plan in grid co-ordinates of the cost map */
+ std::list<deprecated_msgs::Pose2DFloat32> plan_; /**< The 2D plan in grid co-ordinates of the cost map */
// Filter parameters
double minZ_;
Modified: pkg/trunk/highlevel/highlevel_controllers/manifest.xml
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/manifest.xml 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/highlevel/highlevel_controllers/manifest.xml 2009-02-10 06:59:02 UTC (rev 10909)
@@ -15,6 +15,7 @@
<depend package="roscpp"/>
<depend package="rosconsole"/>
<depend package="std_msgs"/>
+ <depend package="deprecated_msgs"/>
<depend package="robot_msgs"/>
<depend package="robot_srvs"/>
<!--depend package="std_srvs"/ Trying to remove Tully-->
Modified: pkg/trunk/highlevel/highlevel_controllers/msg/RechargeGoal.msg
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/msg/RechargeGoal.msg 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/highlevel/highlevel_controllers/msg/RechargeGoal.msg 2009-02-10 06:59:02 UTC (rev 10909)
@@ -6,7 +6,7 @@
float32 recharge_level
# Sets the pose for accessing the plug
-std_msgs/Pose2DFloat32 pose
+deprecated_msgs/Pose2DFloat32 pose
# True to submit a goal, false to recall it
byte enable
Modified: pkg/trunk/highlevel/highlevel_controllers/msg/RechargeState.msg
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/msg/RechargeState.msg 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/highlevel/highlevel_controllers/msg/RechargeState.msg 2009-02-10 06:59:02 UTC (rev 10909)
@@ -22,4 +22,4 @@
float32 goal_recharge_level
# The goal pose for accessing the plug
-std_msgs/Pose2DFloat32 goal_pose
+deprecated_msgs/Pose2DFloat32 goal_pose
Modified: pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp 2009-02-10 06:59:02 UTC (rev 10909)
@@ -36,7 +36,7 @@
#include <highlevel_controllers/move_base.hh>
#include <std_msgs/PoseDot.h>
#include <std_msgs/PointCloud.h>
-#include <std_msgs/Pose2DFloat32.h>
+#include <deprecated_msgs/Pose2DFloat32.h>
#include <std_msgs/Polyline2D.h>
#include <robot_srvs/StaticMap.h>
#include <std_msgs/PointStamped.h>
@@ -514,7 +514,7 @@
stopRobot();
}
- void MoveBase::updatePlan(const std::list<std_msgs::Pose2DFloat32>& newPlan){
+ void MoveBase::updatePlan(const std::list<deprecated_msgs::Pose2DFloat32>& newPlan){
lock();
// If we have a valid plan then only swap in the new plan if it is shorter.
@@ -527,7 +527,7 @@
unlock();
}
- /** \todo Some code duplication wrt MoveBase::updatePlan(const std::list<std_msgs::Pose2DFloat32>&). */
+ /** \todo Some code duplication wrt MoveBase::updatePlan(const std::list<deprecated_msgs::Pose2DFloat32>&). */
void MoveBase::updatePlan(mpglue::waypoint_plan_t const & newPlan) {
sentry<MoveBase> guard(this);
if (!isValid() || plan_.size() > newPlan.size()){
@@ -542,8 +542,8 @@
* applied to protect access to the plan.
*/
bool MoveBase::inCollision() const {
- for(std::list<std_msgs::Pose2DFloat32>::const_iterator it = plan_.begin(); it != plan_.end(); ++it){
- const std_msgs::Pose2DFloat32& w = *it;
+ for(std::list<deprecated_msgs::Pose2DFloat32>::const_iterator it = plan_.begin(); it != plan_.end(); ++it){
+ const deprecated_msgs::Pose2DFloat32& w = *it;
unsigned int ind = costMap_->WC_IND(w.x, w.y);
if((*costMap_)[ind] >= CostMap2D::INSCRIBED_INFLATED_OBSTACLE){
ROS_DEBUG("path in collision at <%f, %f>\n", w.x, w.y);
@@ -569,13 +569,13 @@
publish("robot_footprint", footprint_msg);
}
- void MoveBase::publishPath(bool isGlobal, const std::list<std_msgs::Pose2DFloat32>& path) {
+ void MoveBase::publishPath(bool isGlobal, const std::list<deprecated_msgs::Pose2DFloat32>& path) {
std_msgs::Polyline2D guiPathMsg;
guiPathMsg.set_points_size(path.size());
unsigned int i = 0;
- for(std::list<std_msgs::Pose2DFloat32>::const_iterator it = path.begin(); it != path.end(); ++it){
- const std_msgs::Pose2DFloat32& w = *it;
+ for(std::list<deprecated_msgs::Pose2DFloat32>::const_iterator it = path.begin(); it != path.end(); ++it){
+ const deprecated_msgs::Pose2DFloat32& w = *it;
guiPathMsg.points[i].x = w.x;
guiPathMsg.points[i].y = w.y;
i++;
@@ -678,9 +678,9 @@
// the global plan has failed since we are nowhere near the plan. We also prune parts of the plan that are behind us as we go. We determine this
// by assuming that we start within a certain distance from the beginning of the plan and we can stay within a maximum error of the planned
// path
- std::list<std_msgs::Pose2DFloat32>::iterator it = plan_.begin();
+ std::list<deprecated_msgs::Pose2DFloat32>::iterator it = plan_.begin();
while(it != plan_.end()){
- const std_msgs::Pose2DFloat32& w = *it;
+ const deprecated_msgs::Pose2DFloat32& w = *it;
// Fixed error bound of 2 meters for now. Can reduce to a portion of the map size or based on the resolution
if(fabs(global_pose_.getOrigin().x() - w.x) < 2 && fabs(global_pose_.getOrigin().y() - w.y) < 2){
ROS_DEBUG("Nearest waypoint to <%f, %f> is <%f, %f>\n", global_pose_.getOrigin().x(), global_pose_.getOrigin().y(), w.x, w.y);
@@ -704,7 +704,7 @@
ros::Time start = ros::Time::now();
// Create a window onto the global cost map for the velocity controller
- std::list<std_msgs::Pose2DFloat32> localPlan; // Capture local plan for display
+ std::list<deprecated_msgs::Pose2DFloat32> localPlan; // Capture local plan for display
lock();
// Aggregate buffered observations across all sources. Must be thread safe
Modified: pkg/trunk/highlevel/highlevel_controllers/src/move_base_follow.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/move_base_follow.cpp 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/highlevel/highlevel_controllers/src/move_base_follow.cpp 2009-02-10 06:59:02 UTC (rev 10909)
@@ -72,10 +72,10 @@
stateMsg.unlock();
// Simply pass on the goal as the plan for the controller
- std::list<std_msgs::Pose2DFloat32> newPlan;
+ std::list<deprecated_msgs::Pose2DFloat32> newPlan;
//This is a hack for now to add the goal.
- std_msgs::Pose2DFloat32 goalstep;
+ deprecated_msgs::Pose2DFloat32 goalstep;
goalstep.x = goalX;
goalstep.y = goalY;
newPlan.push_back(goalstep);
@@ -126,7 +126,7 @@
ros::Time start = ros::Time::now();
// Create a window onto the global cost map for the velocity controller
- std::list<std_msgs::Pose2DFloat32> localPlan; // Capture local plan for display
+ std::list<deprecated_msgs::Pose2DFloat32> localPlan; // Capture local plan for display
lock();
// Aggregate buffered observations across all sources. Must be thread safe
Modified: pkg/trunk/highlevel/highlevel_controllers/src/move_base_navfn.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/move_base_navfn.cpp 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/highlevel/highlevel_controllers/src/move_base_navfn.cpp 2009-02-10 06:59:02 UTC (rev 10909)
@@ -130,20 +130,20 @@
float *x = planner_.getPathX();
float *y = planner_.getPathY();
int len = planner_.getPathLen();
- std::list<std_msgs::Pose2DFloat32> newPlan;
+ std::list<deprecated_msgs::Pose2DFloat32> newPlan;
for(int i=0; i < len; i++){
double wx, wy;
unsigned int mx = (unsigned int) x[i];
unsigned int my = (unsigned int) y[i];
getCostMap().MC_WC(mx, my, wx, wy);
- std_msgs::Pose2DFloat32 step;
+ deprecated_msgs::Pose2DFloat32 step;
step.x = wx;
step.y = wy;
newPlan.push_back(step);
}
//This is a hack for now to add the goal.
- std_msgs::Pose2DFloat32 goalstep;
+ deprecated_msgs::Pose2DFloat32 goalstep;
goalstep.x = goalX;
goalstep.y = goalY;
newPlan.push_back(goalstep);
Modified: pkg/trunk/highlevel/highlevel_controllers/src/move_base_sbpl.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/move_base_sbpl.cpp 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/highlevel/highlevel_controllers/src/move_base_sbpl.cpp 2009-02-10 06:59:02 UTC (rev 10909)
@@ -264,8 +264,8 @@
// backs. Note that cost map queries here are const methods that merely do co-ordinate transformations, so we do not need
// to lock protect those.
stateMsg.lock();
- std_msgs::Pose2DFloat32 const start(stateMsg.pos);
- std_msgs::Pose2DFloat32 const goal(stateMsg.goal);
+ deprecated_msgs::Pose2DFloat32 const start(stateMsg.pos);
+ deprecated_msgs::Pose2DFloat32 const goal(stateMsg.goal);
stateMsg.unlock();
// Assume the robot is constantly moving, so always set start.
Modified: pkg/trunk/highlevel/highlevel_controllers/src/move_base_topological.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/move_base_topological.cpp 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/highlevel/highlevel_controllers/src/move_base_topological.cpp 2009-02-10 06:59:02 UTC (rev 10909)
@@ -135,12 +135,12 @@
// Invoke the planner
vector<GridCell> solution=graph_.findOptimalPath(start, goal);
- std::list<std_msgs::Pose2DFloat32> newPlan;
+ std::list<deprecated_msgs::Pose2DFloat32> newPlan;
ROS_DEBUG ("Topological planner found plan with waypoints: ");
for (unsigned int i=0; i<solution.size(); i++) {
double wx=solution[i].second*resolution;
double wy=(solution[i].first)*resolution;
- std_msgs::Pose2DFloat32 step;
+ deprecated_msgs::Pose2DFloat32 step;
step.x = wx;
step.y = wy;
newPlan.push_back(step);
Modified: pkg/trunk/motion_planning/mpglue/src/plan.cpp
===================================================================
--- pkg/trunk/motion_planning/mpglue/src/plan.cpp 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/motion_planning/mpglue/src/plan.cpp 2009-02-10 06:59:02 UTC (rev 10909)
@@ -55,7 +55,7 @@
void PlanConverter::
- addWaypoint(std_msgs::Pose2DFloat32 const & waypoint)
+ addWaypoint(deprecated_msgs::Pose2DFloat32 const & waypoint)
{
if (0 < count_) {
double const dx(waypoint.x - prevx_);
@@ -78,7 +78,7 @@
void PlanConverter::
addWaypoint(double px, double py, double pth)
{
- std_msgs::Pose2DFloat32 pp;
+ deprecated_msgs::Pose2DFloat32 pp;
pp.x = px;
pp.y = py;
pp.th = pth;
Modified: pkg/trunk/motion_planning/mpglue/src/plan.h
===================================================================
--- pkg/trunk/motion_planning/mpglue/src/plan.h 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/motion_planning/mpglue/src/plan.h 2009-02-10 06:59:02 UTC (rev 10909)
@@ -35,13 +35,13 @@
#ifndef MPGLUE_PLAN_HPP
#define MPGLUE_PLAN_HPP
-#include <std_msgs/Pose2DFloat32.h>
+#include <deprecated_msgs/Pose2DFloat32.h>
#include <vector>
namespace mpglue {
typedef std::vector<int> raw_sbpl_plan_t;
- typedef std::vector<std_msgs::Pose2DFloat32> waypoint_plan_t;
+ typedef std::vector<deprecated_msgs::Pose2DFloat32> waypoint_plan_t;
class SBPLEnvironment;
class IndexTransform;
@@ -55,7 +55,7 @@
{
public:
explicit PlanConverter(waypoint_plan_t * plan);
- void addWaypoint(std_msgs::Pose2DFloat32 const & waypoint);
+ void addWaypoint(deprecated_msgs::Pose2DFloat32 const & waypoint);
void addWaypoint(double px, double py, double pth);
double plan_length, tangent_change, direction_change;
@@ -72,7 +72,7 @@
SBPLPlanner subclasses) to waypoints that are
understandable. Optionally provides some statistics on the plan.
*/
- void convertPlan(/** in: how to translate state IDs to std_msgs::Pose2DFloat32 */
+ void convertPlan(/** in: how to translate state IDs to deprecated_msgs::Pose2DFloat32 */
SBPLEnvironment const & environment,
/** in: the raw plan */
raw_sbpl_plan_t const & raw,
@@ -88,7 +88,7 @@
double * optTangentChangeRad,
/** optional out: the cumulated change in the
direction of the waypoints (the delta of
- std_msgs::Pose2DFloat32::th values).
+ deprecated_msgs::Pose2DFloat32::th values).
\note This only makes sense for plans that are
aware of the robot's heading though. */
double * optDirectionChangeRad);
@@ -100,7 +100,7 @@
convertPlanInterpolate() though, it takes advantage of the
sub-pixel resolution available in NavFn.
*/
- void convertPlan(/** in: how to translate state IDs to std_msgs::Pose2DFloat32 */
+ void convertPlan(/** in: how to translate state IDs to deprecated_msgs::Pose2DFloat32 */
IndexTransform const & itransform,
/** in: array of X-coordinates (continuous grid index). */
float const * path_x,
@@ -120,7 +120,7 @@
double * optTangentChangeRad,
/** optional out: the cumulated change in the
direction of the waypoints (the delta of
- std_msgs::Pose2DFloat32::th values).
+ deprecated_msgs::Pose2DFloat32::th values).
\note This only makes sense for plans that are
aware of the robot's heading though. */
double * optDirectionChangeRad);
@@ -128,7 +128,7 @@
/**
Uses interpolateIndexToGlobal() for sub-pixel resolution.
*/
- void convertPlanInterpolate(/** in: how to translate state IDs to std_msgs::Pose2DFloat32 */
+ void convertPlanInterpolate(/** in: how to translate state IDs to deprecated_msgs::Pose2DFloat32 */
IndexTransform const & itransform,
/** in: array of X-coordinates (continuous grid index). */
float const * path_x,
@@ -148,7 +148,7 @@
double * optTangentChangeRad,
/** optional out: the cumulated change in the
direction of the waypoints (the delta of
- std_msgs::Pose2DFloat32::th values).
+ deprecated_msgs::Pose2DFloat32::th values).
\note This only makes sense for plans that are
aware of the robot's heading though. */
double * optDirectionChangeRad);
Modified: pkg/trunk/motion_planning/mpglue/src/planner.h
===================================================================
--- pkg/trunk/motion_planning/mpglue/src/planner.h 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/motion_planning/mpglue/src/planner.h 2009-02-10 06:59:02 UTC (rev 10909)
@@ -38,7 +38,7 @@
#define MPGLUE_PLANNER_HPP
#include <mpglue/plan.h>
-#include <std_msgs/Pose2DFloat32.h>
+#include <deprecated_msgs/Pose2DFloat32.h>
#include <boost/shared_ptr.hpp>
#include <stdexcept>
@@ -106,7 +106,7 @@
virtual void setStart(double px, double py, double pth) throw(std::out_of_range);
/** Delegated to setStart(double, double, double). */
- void setStart(std_msgs::Pose2DFloat32 const & start) throw(std::out_of_range)
+ void setStart(deprecated_msgs::Pose2DFloat32 const & start) throw(std::out_of_range)
{ setStart(start.x, start.y, start.th); }
/** Default implementation just stores the goal and its
@@ -114,7 +114,7 @@
virtual void setGoal(double px, double py, double pth) throw(std::out_of_range);
/** Delegated to setGoal(double, double, double). */
- void setGoal(std_msgs::Pose2DFloat32 const & goal) throw(std::out_of_range)
+ void setGoal(deprecated_msgs::Pose2DFloat32 const & goal) throw(std::out_of_range)
{ setGoal(goal.x, goal.y, goal.th); }
/** Default implementation just stores the goal tolerance in the
Modified: pkg/trunk/motion_planning/mpglue/src/sbpl_environment.cpp
===================================================================
--- pkg/trunk/motion_planning/mpglue/src/sbpl_environment.cpp 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/motion_planning/mpglue/src/sbpl_environment.cpp 2009-02-10 06:59:02 UTC (rev 10909)
@@ -99,8 +99,8 @@
virtual int SetStart(double px, double py, double pth);
virtual int SetGoal(double px, double py, double pth);
virtual void SetGoalTolerance(double tol_xy, double tol_th);
- virtual std_msgs::Pose2DFloat32 GetPoseFromState(int stateID) const throw(invalid_state);
- virtual int GetStateFromPose(std_msgs::Pose2DFloat32 const & pose) const;
+ virtual deprecated_msgs::Pose2DFloat32 GetPoseFromState(int stateID) const throw(invalid_state);
+ virtual int GetStateFromPose(deprecated_msgs::Pose2DFloat32 const & pose) const;
virtual std::string getName() const;
protected:
@@ -137,8 +137,8 @@
virtual int SetStart(double px, double py, double pth);
virtual int SetGoal(double px, double py, double pth);
virtual void SetGoalTolerance(double tol_xy, double tol_th);
- virtual std_msgs::Pose2DFloat32 GetPoseFromState(int stateID) const throw(invalid_state);
- virtual int GetStateFromPose(std_msgs::Pose2DFloat32 const & pose) const;
+ virtual deprecated_msgs::Pose2DFloat32 GetPoseFromState(int stateID) const throw(invalid_state);
+ virtual int GetStateFromPose(deprecated_msgs::Pose2DFloat32 const & pose) const;
virtual std::string getName() const;
protected:
@@ -365,7 +365,7 @@
/** \note Always sets pose.th == -42 so people can detect that it is
undefined. */
- std_msgs::Pose2DFloat32 SBPLEnvironment2D::
+ deprecated_msgs::Pose2DFloat32 SBPLEnvironment2D::
GetPoseFromState(int stateID) const
throw(invalid_state)
{
@@ -377,7 +377,7 @@
// wouldn't have a stateID)
double px, py;
it_->indexToGlobal(ix, iy, &px, &py);
- std_msgs::Pose2DFloat32 pose;
+ deprecated_msgs::Pose2DFloat32 pose;
pose.x = px;
pose.y = py;
pose.th = -42;
@@ -386,7 +386,7 @@
int SBPLEnvironment2D::
- GetStateFromPose(std_msgs::Pose2DFloat32 const & pose) const
+ GetStateFromPose(deprecated_msgs::Pose2DFloat32 const & pose) const
{
ssize_t ix, iy;
it_->globalToIndex(pose.x, pose.y, &ix, &iy);
@@ -562,7 +562,7 @@
}
- std_msgs::Pose2DFloat32 SBPLEnvironment3DKIN::
+ deprecated_msgs::Pose2DFloat32 SBPLEnvironment3DKIN::
GetPoseFromState(int stateID) const
throw(invalid_state)
{
@@ -574,7 +574,7 @@
// PoseDiscToCont() retval
double px, py, pth;
env_->PoseDiscToCont(ix, iy, ith, px, py, pth);
- std_msgs::Pose2DFloat32 pose;
+ deprecated_msgs::Pose2DFloat32 pose;
pose.x = px;
pose.y = py;
pose.th = pth;
@@ -583,7 +583,7 @@
int SBPLEnvironment3DKIN::
- GetStateFromPose(std_msgs::Pose2DFloat32 const & pose) const
+ GetStateFromPose(deprecated_msgs::Pose2DFloat32 const & pose) const
{
int ix, iy, ith;
if ( ! env_->PoseContToDisc(pose.x, pose.y, pose.th, ix, iy, ith))
Modified: pkg/trunk/motion_planning/mpglue/src/sbpl_environment.h
===================================================================
--- pkg/trunk/motion_planning/mpglue/src/sbpl_environment.h 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/motion_planning/mpglue/src/sbpl_environment.h 2009-02-10 06:59:02 UTC (rev 10909)
@@ -37,7 +37,7 @@
#include <mpglue/costmap.h>
#include <mpglue/footprint.h>
-#include <std_msgs/Pose2DFloat32.h>
+#include <deprecated_msgs/Pose2DFloat32.h>
#include <boost/shared_ptr.hpp>
#include <stdexcept>
#include <string>
@@ -129,7 +129,7 @@
virtual int SetStart(double px, double py, double pth) = 0;
/** \note see SetStart(double, double, double) */
- int SetStart(std_msgs::Pose2DFloat32 const & start)
+ int SetStart(deprecated_msgs::Pose2DFloat32 const & start)
{ return SetStart(start.x, start.y, start.th); }
/** \return The stateID of the goal, or -1 if it lies outside the map. */
@@ -138,14 +138,14 @@
virtual void SetGoalTolerance(double tol_xy, double tol_th) = 0;
/** \note see SetGoal(double, double, double) */
- int SetGoal(std_msgs::Pose2DFloat32 const & goal)
+ int SetGoal(deprecated_msgs::Pose2DFloat32 const & goal)
{ return SetGoal(goal.x, goal.y, goal.th) ; }
- virtual std_msgs::Pose2DFloat32 GetPoseFromState(int stateID) const throw(invalid_state) = 0;
+ virtual deprecated_msgs::Pose2DFloat32 GetPoseFromState(int stateID) const throw(invalid_state) = 0;
/** \return the stateID of a pose, or -1 if the pose lies outside
of the map. */
- virtual int GetStateFromPose(std_msgs::Pose2DFloat32 const & pose) const = 0;
+ virtual int GetStateFromPose(deprecated_msgs::Pose2DFloat32 const & pose) const = 0;
virtual std::string getName() const = 0;
Modified: pkg/trunk/nav/amcl_player/amcl_player.cc
===================================================================
--- pkg/trunk/nav/amcl_player/amcl_player.cc 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/nav/amcl_player/amcl_player.cc 2009-02-10 06:59:02 UTC (rev 10909)
@@ -98,9 +98,9 @@
// Messages that I need
#include "laser_scan/LaserScan.h"
-#include "std_msgs/RobotBase2DOdom.h"
+#include "deprecated_msgs/RobotBase2DOdom.h"
#include "robot_msgs/ParticleCloud.h"
-#include "std_msgs/Pose2DFloat32.h"
+#include "deprecated_msgs/Pose2DFloat32.h"
#include "robot_srvs/StaticMap.h"
// For transform support
@@ -144,11 +144,11 @@
ConfigFile* cf;
// incoming messages
- std_msgs::RobotBase2DOdom localizedOdomMsg;
+ deprecated_msgs::RobotBase2DOdom localizedOdomMsg;
robot_msgs::ParticleCloud particleCloudMsg;
- std_msgs::RobotBase2DOdom odomMsg;
+ deprecated_msgs::RobotBase2DOdom odomMsg;
laser_scan::LaserScan laserMsg;
- std_msgs::Pose2DFloat32 initialPoseMsg;
+ deprecated_msgs::Pose2DFloat32 initialPoseMsg;
// Message callbacks
void odomReceived();
@@ -437,7 +437,7 @@
this->tf = new tf::TransformBroadcaster(*this);
this->tfL = new tf::TransformListener(*this);
- advertise<std_msgs::RobotBase2DOdom>("localizedpose",2);
+ advertise<deprecated_msgs::RobotBase2DOdom>("localizedpose",2);
advertise<robot_msgs::ParticleCloud>("particlecloud",2);
//subscribe("odom", odomMsg, &AmclNode::odomReceived,2);
subscribe("scan", laserMsg, &AmclNode::laserReceived,2);
Modified: pkg/trunk/nav/amcl_player/cli.cpp
===================================================================
--- pkg/trunk/nav/amcl_player/cli.cpp 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/nav/amcl_player/cli.cpp 2009-02-10 06:59:02 UTC (rev 10909)
@@ -1,11 +1,11 @@
#include <cstdio>
#include "ros/node.h"
-#include "std_msgs/RobotBase2DOdom.h"
+#include "deprecated_msgs/RobotBase2DOdom.h"
class AmclCLI: public ros::Node
{
public:
- std_msgs::RobotBase2DOdom pose_msg;
+ deprecated_msgs::RobotBase2DOdom pose_msg;
bool done;
AmclCLI(): ros::Node("amcl_cli"), done(false)
Modified: pkg/trunk/nav/amcl_player/manifest.xml
===================================================================
--- pkg/trunk/nav/amcl_player/manifest.xml 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/nav/amcl_player/manifest.xml 2009-02-10 06:59:02 UTC (rev 10909)
@@ -8,6 +8,7 @@
<depend package="tf" />
<depend package="robot_srvs" />
<depend package="std_msgs" />
+ <depend package="deprecated_msgs" />
<depend package="robot_msgs" />
<depend package="laser_scan" />
</package>
Modified: pkg/trunk/nav/deadreckon/deadreckon.cpp
===================================================================
--- pkg/trunk/nav/deadreckon/deadreckon.cpp 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/nav/deadreckon/deadreckon.cpp 2009-02-10 06:59:02 UTC (rev 10909)
@@ -30,7 +30,7 @@
#include <cmath>
#include "ros/node.h"
#include "std_msgs/PoseDot.h"
-#include "std_msgs/RobotBase2DOdom.h"
+#include "deprecated_msgs/RobotBase2DOdom.h"
#include "deadreckon/DriveDeadReckon.h"
using namespace std;
using namespace ros;
@@ -39,7 +39,7 @@
{
public:
std_msgs::PoseDot velMsg;
- std_msgs::RobotBase2DOdom odomMsg;
+ deprecated_msgs::RobotBase2DOdom odomMsg;
double maxTV, maxRV, distEps, headEps, finalEps, tgtX, tgtY, tgtTh;
enum
{
Modified: pkg/trunk/nav/deadreckon/manifest.xml
===================================================================
--- pkg/trunk/nav/deadreckon/manifest.xml 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/nav/deadreckon/manifest.xml 2009-02-10 06:59:02 UTC (rev 10909)
@@ -7,6 +7,7 @@
<review status="unreviewed" notes=""/>
<depend package="roscpp"/>
<depend package="std_msgs"/>
+ <depend package="deprecated_msgs"/>
<export>
<cpp cflags="-I${prefix}/srv/cpp" />
</export>
Modified: pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/governor_node.h
===================================================================
--- pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/governor_node.h 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/governor_node.h 2009-02-10 06:59:02 UTC (rev 10909)
@@ -43,7 +43,7 @@
#include <std_msgs/PoseDot.h>
#include <trajectory_rollout/ScoreMap2D.h>
#include <trajectory_rollout/WavefrontPlan.h>
-#include <std_msgs/RobotBase2DOdom.h>
+#include <deprecated_msgs/RobotBase2DOdom.h>
//for GUI debugging
#include <std_msgs/Polyline2D.h>
@@ -158,7 +158,7 @@
//incoming messages
trajectory_rollout::WavefrontPlan plan_msg_;
- std_msgs::RobotBase2DOdom odom_msg_;
+ deprecated_msgs::RobotBase2DOdom odom_msg_;
//outgoing messages
std_msgs::Polyline2D poly_line_msg_;
Modified: pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/trajectory_controller_ros.h
===================================================================
--- pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/trajectory_controller_ros.h 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/trajectory_controller_ros.h 2009-02-10 06:59:02 UTC (rev 10909)
@@ -93,11 +93,11 @@
* @param observations A vector of updates from the robot's sensors in world space, is sometimes unused depending on the model
* @return True if a valid trajectory was found, false otherwise
*/
- bool computeVelocityCommands(const std::list<std_msgs::Pose2DFloat32>& global_plan,
+ bool computeVelocityCommands(const std::list<deprecated_msgs::Pose2DFloat32>& global_plan,
const tf::Stamped<tf::Pose>& global_pose,
const std_msgs::PoseDot& global_vel,
std_msgs::PoseDot& cmd_vel,
- std::list<std_msgs::Pose2DFloat32>& localPlan,
+ std::list<deprecated_msgs::Pose2DFloat32>& localPlan,
const std::vector<costmap_2d::Observation>& observations = std::vector<costmap_2d::Observation>(0));
/**
Modified: pkg/trunk/nav/trajectory_rollout/manifest.xml
===================================================================
--- pkg/trunk/nav/trajectory_rollout/manifest.xml 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/nav/trajectory_rollout/manifest.xml 2009-02-10 06:59:02 UTC (rev 10909)
@@ -8,6 +8,7 @@
<license>BSD</license>
<review status="proposal cleared" notes=""/>
<depend package="std_msgs" />
+ <depend package="deprecated_msgs" />
<depend package="rosconsole" />
<depend package="roscpp" />
<depend package="tf" />
Modified: pkg/trunk/nav/trajectory_rollout/msg/ScoreMap2D.msg
===================================================================
--- pkg/trunk/nav/trajectory_rollout/msg/ScoreMap2D.msg 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/nav/trajectory_rollout/msg/ScoreMap2D.msg 2009-02-10 06:59:02 UTC (rev 10909)
@@ -7,6 +7,6 @@
uint32 size_y
#bottom left corner of the map in world space
-std_msgs/Pose2DFloat32 origin
+deprecated_msgs/Pose2DFloat32 origin
ScoreMapCell2D[] data
Modified: pkg/trunk/nav/trajectory_rollout/src/trajectory_controller_ros.cpp
===================================================================
--- pkg/trunk/nav/trajectory_rollout/src/trajectory_controller_ros.cpp 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/nav/trajectory_rollout/src/trajectory_controller_ros.cpp 2009-02-10 06:59:02 UTC (rev 10909)
@@ -104,11 +104,11 @@
return tc_->drawFootprint(x_i, y_i, theta_i);
}
- bool TrajectoryControllerROS::computeVelocityCommands(const std::list<std_msgs::Pose2DFloat32>& global_plan,
+ bool TrajectoryControllerROS::computeVelocityCommands(const std::list<deprecated_msgs::Pose2DFloat32>& global_plan,
const tf::Stamped<tf::Pose>& global_pose,
const std_msgs::PoseDot& global_vel,
std_msgs::PoseDot& cmd_vel,
- std::list<std_msgs::Pose2DFloat32>& localPlan,
+ std::list<deprecated_msgs::Pose2DFloat32>& localPlan,
const std::vector<costmap_2d::Observation>& observations){
@@ -130,7 +130,7 @@
// Temporary Transformation till api below changes
std::vector<std_msgs::Point2DFloat32> copiedGlobalPlan;
- for(std::list<std_msgs::Pose2DFloat32>::const_iterator it = global_plan.begin(); it != global_plan.end(); ++it){
+ for(std::list<deprecated_msgs::Pose2DFloat32>::const_iterator it = global_plan.begin(); it != global_plan.end(); ++it){
std_msgs::Point2DFloat32 p;
p.x = it->x;
p.y = it->y;
@@ -172,7 +172,7 @@
double p_x, p_y, p_th;
path.getPoint(i, p_x, p_y, p_th);
- std_msgs::Pose2DFloat32 p;
+ deprecated_msgs::Pose2DFloat32 p;
p.x = p_x;
p.y = p_y;
p.th = p_th;
Modified: pkg/trunk/prcore/robot_msgs/manifest.xml
===================================================================
--- pkg/trunk/prcore/robot_msgs/manifest.xml 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/prcore/robot_msgs/manifest.xml 2009-02-10 06:59:02 UTC (rev 10909)
@@ -10,6 +10,7 @@
<url>http://pr.willowgarage.com/wiki/std_msgs</url>
<logo>http://www.willowgarage.com/files/willowgarage/robot10.jpg</logo>
<depend package="std_msgs"/>
+ <depend package="deprecated_msgs"/>
<export>
<cpp cflags="-I${prefix}/msg/cpp"/>
</export>
Modified: pkg/trunk/prcore/robot_msgs/msg/MapMetaData.msg
===================================================================
--- pkg/trunk/prcore/robot_msgs/msg/MapMetaData.msg 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/prcore/robot_msgs/msg/MapMetaData.msg 2009-02-10 06:59:02 UTC (rev 10909)
@@ -8,4 +8,4 @@
uint32 height
# The origin of the map [m, m, rad]. This is the real-world pose of the
# cell (0,0) in the map.
-std_msgs/Pose2DFloat32 origin
\ No newline at end of file
+deprecated_msgs/Pose2DFloat32 origin
\ No newline at end of file
Modified: pkg/trunk/prcore/robot_msgs/msg/OccMap2D.msg
===================================================================
--- pkg/trunk/prcore/robot_msgs/msg/OccMap2D.msg 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/prcore/robot_msgs/msg/OccMap2D.msg 2009-02-10 06:59:02 UTC (rev 10909)
@@ -10,7 +10,7 @@
uint32 height
# The origin of the map [m, m, rad]. This is the real-world pose of the
# cell (0,0) in the map.
-std_msgs/Pose2DFloat32 origin
+deprecated_msgs/Pose2DFloat32 origin
# The map data, in row-major order, starting with (0,0). Occupancy
# probabilities are in the range [0,100]. Unknown is -1.
byte[] data
Modified: pkg/trunk/prcore/robot_msgs/msg/Planner2DGoal.msg
===================================================================
--- pkg/trunk/prcore/robot_msgs/msg/Planner2DGoal.msg 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/prcore/robot_msgs/msg/Planner2DGoal.msg 2009-02-10 06:59:02 UTC (rev 10909)
@@ -1,5 +1,5 @@
Header header
-std_msgs/Pose2DFloat32 goal
+deprecated_msgs/Pose2DFloat32 goal
byte enable
# Total timelimit for the controller, if a plan is not
Modified: pkg/trunk/prcore/robot_msgs/msg/Planner2DState.msg
===================================================================
--- pkg/trunk/prcore/robot_msgs/msg/Planner2DState.msg 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/prcore/robot_msgs/msg/Planner2DState.msg 2009-02-10 06:59:02 UTC (rev 10909)
@@ -10,13 +10,13 @@
#Was the planner told to stop?
byte preempted
# Current location (m,m,rad)
-std_msgs/Pose2DFloat32 pos
+deprecated_msgs/Pose2DFloat32 pos
# Goal location (m,m,rad)
-std_msgs/Pose2DFloat32 goal
+deprecated_msgs/Pose2DFloat32 goal
# Current waypoint location (m,m,rad)
-std_msgs/Pose2DFloat32 waypoint
+deprecated_msgs/Pose2DFloat32 waypoint
# Current list of waypoints in the plan
-std_msgs/Pose2DFloat32[] waypoints
+deprecated_msgs/Pose2DFloat32[] waypoints
# Current waypoint index. May be negative if there's no plan, or if
# the plan is done
int32 waypoint_idx
Modified: pkg/trunk/prcore/robot_srvs/manifest.xml
===================================================================
--- pkg/trunk/prcore/robot_srvs/manifest.xml 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/prcore/robot_srvs/manifest.xml 2009-02-10 06:59:02 UTC (rev 10909)
@@ -10,6 +10,7 @@
<url>http://pr.willowgarage.com/wiki/robot_srvs</url>
<logo>http://www.willowgarage.com/files/willowgarage/robot10.jpg</logo>
<depend package="std_msgs"/>
+ <depend package="deprecated_msgs"/>
<depend package="robot_msgs"/>
<export>
<cpp cflags="-I${prefix}/srv/cpp"/>
Modified: pkg/trunk/simulators/rosstage/manifest.xml
===================================================================
--- pkg/trunk/simulators/rosstage/manifest.xml 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/simulators/rosstage/manifest.xml 2009-02-10 06:59:02 UTC (rev 10909)
@@ -6,6 +6,7 @@
<depend package="roscpp" />
<depend package="stage" />
<depend package="std_msgs" />
+ <depend package="deprecated_msgs" />
<depend package="laser_scan" />
<depend package="tf" />
</package>
Modified: pkg/trunk/simulators/rosstage/rosstage.cc
===================================================================
--- pkg/trunk/simulators/rosstage/rosstage.cc 2009-02-10 06:57:18 UTC (rev 10908)
+++ pkg/trunk/simulators/rosstage/rosstage.cc 2009-02-10 06:59:02 UTC (rev 10909)
@@ -85,7 +85,7 @@
#include <ros/node.h>
#include "boost/thread/mutex.hpp"
#include <laser_scan/LaserScan.h>
-#include <std_msgs/RobotBase2DOdom.h>
+#include <deprecated_msgs/RobotBase2DOdom.h>
#include <std_msgs/PoseWithRatesStamped.h>
#include <std_msgs/PoseDot.h>
#include <roslib/Time.h>
@@ -101,7 +101,7 @@
// Messages that we'll send or receive
std_msgs::PoseDot velMsg;
laser_scan::Las...
[truncated message content] |