|
From: <tf...@us...> - 2009-02-11 03:22:16
|
Revision: 10969
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=10969&view=rev
Author: tfoote
Date: 2009-02-11 02:35:23 +0000 (Wed, 11 Feb 2009)
Log Message:
-----------
moving Point2DFloat32 and Position2DInt into personalrobots
Modified Paths:
--------------
pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/move_base.hh
pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp
pkg/trunk/mapping/point_cloud_mapping/include/cloud_geometry/areas.h
pkg/trunk/mapping/point_cloud_mapping/src/cloud_geometry/areas.cpp
pkg/trunk/motion_planning/mpglue/src/footprint.cpp
pkg/trunk/motion_planning/mpglue/src/footprint.h
pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/costmap_model.h
pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/governor_node.h
pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/point_grid.h
pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/trajectory_controller.h
pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/trajectory_controller_ros.h
pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/world_model.h
pkg/trunk/nav/trajectory_rollout/msg/GlobalPlan.msg
pkg/trunk/nav/trajectory_rollout/src/costmap_model.cpp
pkg/trunk/nav/trajectory_rollout/src/governor_node.cpp
pkg/trunk/nav/trajectory_rollout/src/point_grid.cpp
pkg/trunk/nav/trajectory_rollout/src/trajectory_controller.cpp
pkg/trunk/nav/trajectory_rollout/src/trajectory_controller_ros.cpp
pkg/trunk/nav/trajectory_rollout/test/utest.cpp
pkg/trunk/pr2_msgs/manifest.xml
pkg/trunk/pr2_msgs/msg/OccDiff.msg
pkg/trunk/pr2_srvs/manifest.xml
pkg/trunk/prcore/robot_msgs/msg/Polyline2D.msg
Added Paths:
-----------
pkg/trunk/deprecated/deprecated_msgs/msg/Point2DFloat32.msg
pkg/trunk/nav/trajectory_rollout/msg/Position2DInt.msg
Added: pkg/trunk/deprecated/deprecated_msgs/msg/Point2DFloat32.msg
===================================================================
--- pkg/trunk/deprecated/deprecated_msgs/msg/Point2DFloat32.msg (rev 0)
+++ pkg/trunk/deprecated/deprecated_msgs/msg/Point2DFloat32.msg 2009-02-11 02:35:23 UTC (rev 10969)
@@ -0,0 +1,2 @@
+float32 x
+float32 y
\ No newline at end of file
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-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/move_base.hh 2009-02-11 02:35:23 UTC (rev 10969)
@@ -87,7 +87,7 @@
public:
- typedef std::vector<std_msgs::Point2DFloat32> footprint_t;
+ typedef std::vector<deprecated_msgs::Point2DFloat32> footprint_t;
/**
* @brief Constructor
Modified: pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp 2009-02-11 02:35:23 UTC (rev 10969)
@@ -240,7 +240,7 @@
global_map_accessor_ = new CostMapAccessor(*costMap_);
local_map_accessor_ = new CostMapAccessor(*costMap_, mapSize, 0.0, 0.0);
- std_msgs::Point2DFloat32 pt;
+ deprecated_msgs::Point2DFloat32 pt;
//create a square footprint
pt.x = robotRadius;
pt.y = -1 * robotRadius;
@@ -555,7 +555,7 @@
}
void MoveBase::publishFootprint(double x, double y, double th){
- std::vector<std_msgs::Point2DFloat32> footprint = controller_->drawFootprint(x, y, th);
+ std::vector<deprecated_msgs::Point2DFloat32> footprint = controller_->drawFootprint(x, y, th);
robot_msgs::Polyline2D footprint_msg;
footprint_msg.set_points_size(footprint.size());
footprint_msg.color.r = 1.0;
Modified: pkg/trunk/mapping/point_cloud_mapping/include/cloud_geometry/areas.h
===================================================================
--- pkg/trunk/mapping/point_cloud_mapping/include/cloud_geometry/areas.h 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/mapping/point_cloud_mapping/include/cloud_geometry/areas.h 2009-02-11 02:35:23 UTC (rev 10969)
@@ -36,7 +36,7 @@
// ROS includes
#include <robot_msgs/Point32.h>
#include <robot_msgs/PointCloud.h>
-#include <std_msgs/Point2DFloat32.h>
+#include <deprecated_msgs/Point2DFloat32.h>
#include <robot_msgs/Polygon3D.h>
#include <robot_msgs/Polyline2D.h>
@@ -54,7 +54,7 @@
* \param p2 the second Point2DFloat32 point
*/
inline bool
- comparePoint2DFloat32 (const std_msgs::Point2DFloat32& p1, const std_msgs::Point2DFloat32& p2)
+ comparePoint2DFloat32 (const deprecated_msgs::Point2DFloat32& p1, const deprecated_msgs::Point2DFloat32& p2)
{
if (p1.x < p2.x) return (true);
else if (p1.x > p2.x) return (false);
@@ -81,7 +81,7 @@
double compute2DPolygonalArea (robot_msgs::PointCloud points, std::vector<double> normal);
double compute2DPolygonalArea (robot_msgs::Polygon3D polygon, std::vector<double> normal);
void convexHull2D (robot_msgs::PointCloud *points, std::vector<int> *indices, std::vector<double> *coeff, robot_msgs::Polygon3D &hull);
- void convexHull2D (std::vector<std_msgs::Point2DFloat32> points, robot_msgs::Polyline2D &hull);
+ void convexHull2D (std::vector<deprecated_msgs::Point2DFloat32> points, robot_msgs::Polyline2D &hull);
bool isPointIn2DPolygon (robot_msgs::Point32 point, robot_msgs::Polygon3D *polygon);
}
Modified: pkg/trunk/mapping/point_cloud_mapping/src/cloud_geometry/areas.cpp
===================================================================
--- pkg/trunk/mapping/point_cloud_mapping/src/cloud_geometry/areas.cpp 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/mapping/point_cloud_mapping/src/cloud_geometry/areas.cpp 2009-02-11 02:35:23 UTC (rev 10969)
@@ -155,7 +155,7 @@
centroid (1) /= epoints.size ();
// Push projected centered 2d points
- std::vector<std_msgs::Point2DFloat32> epoints_demean (epoints.size ());
+ std::vector<deprecated_msgs::Point2DFloat32> epoints_demean (epoints.size ());
for (unsigned int cp = 0; cp < indices->size (); cp++)
{
epoints_demean[cp].x = epoints[cp](k1) - centroid (0);
@@ -213,7 +213,7 @@
* \param hull the resultant 2D convex hull model as a \a Polyline2D
*/
void
- convexHull2D (std::vector<std_msgs::Point2DFloat32> points, robot_msgs::Polyline2D &hull)
+ convexHull2D (std::vector<deprecated_msgs::Point2DFloat32> points, robot_msgs::Polyline2D &hull)
{
int nr_points = points.size ();
hull.points.resize (nr_points + 1);
Modified: pkg/trunk/motion_planning/mpglue/src/footprint.cpp
===================================================================
--- pkg/trunk/motion_planning/mpglue/src/footprint.cpp 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/motion_planning/mpglue/src/footprint.cpp 2009-02-11 02:35:23 UTC (rev 10969)
@@ -49,7 +49,7 @@
void initSimpleFootprint(footprint_t & footprint,
double inscribedRadius, double circumscribedRadius)
{
- std_msgs::Point2DFloat32 pt;
+ deprecated_msgs::Point2DFloat32 pt;
//create a square footprint
pt.x = inscribedRadius;
Modified: pkg/trunk/motion_planning/mpglue/src/footprint.h
===================================================================
--- pkg/trunk/motion_planning/mpglue/src/footprint.h 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/motion_planning/mpglue/src/footprint.h 2009-02-11 02:35:23 UTC (rev 10969)
@@ -35,12 +35,12 @@
#ifndef MPGLUE_FOOTPRINT_HPP
#define MPGLUE_FOOTPRINT_HPP
-#include <std_msgs/Point2DFloat32.h>
+#include <deprecated_msgs/Point2DFloat32.h>
#include <vector>
namespace mpglue {
- typedef std::vector<std_msgs::Point2DFloat32> footprint_t;
+ typedef std::vector<deprecated_msgs::Point2DFloat32> footprint_t;
footprint_t createSimpleFootprint(double inscribedRadius, double circumscribedRadius);
Modified: pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/costmap_model.h
===================================================================
--- pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/costmap_model.h 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/costmap_model.h 2009-02-11 02:35:23 UTC (rev 10969)
@@ -69,7 +69,7 @@
* @param circumscribed_radius The radius of the circumscribed circle of the robot
* @return True if all points lie outside the footprint, false otherwise
*/
- virtual bool legalFootprint(const std_msgs::Point2DFloat32& position, const std::vector<std_msgs::Point2DFloat32>& footprint,
+ virtual bool legalFootprint(const deprecated_msgs::Point2DFloat32& position, const std::vector<deprecated_msgs::Point2DFloat32>& footprint,
double inscribed_radius, double circumscribed_radius);
/**
@@ -77,7 +77,7 @@
* @param observations The observations from various sensors
* @param laser_outline The polygon of the active sensor region
*/
- virtual void updateWorld(const std::vector<costmap_2d::Observation>& observations, const std::vector<std_msgs::Point2DFloat32>& laser_outline){}
+ virtual void updateWorld(const std::vector<costmap_2d::Observation>& observations, const std::vector<deprecated_msgs::Point2DFloat32>& laser_outline){}
private:
/**
* @brief Rasterizes a line in the costmap grid and checks for collisions
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-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/governor_node.h 2009-02-11 02:35:23 UTC (rev 10969)
@@ -47,7 +47,7 @@
//for GUI debugging
#include <robot_msgs/Polyline2D.h>
-#include <std_msgs/Point2DFloat32.h>
+#include <deprecated_msgs/Point2DFloat32.h>
//for transform support
@@ -127,7 +127,7 @@
class GovernorNode: public ros::Node
{
public:
- GovernorNode(std::vector<std_msgs::Point2DFloat32> footprint_spec);
+ GovernorNode(std::vector<deprecated_msgs::Point2DFloat32> footprint_spec);
//callback for when the planned passes a new map
void planReceived();
Modified: pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/point_grid.h
===================================================================
--- pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/point_grid.h 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/point_grid.h 2009-02-11 02:35:23 UTC (rev 10969)
@@ -39,7 +39,7 @@
#include <vector>
#include <list>
#include <cfloat>
-#include <std_msgs/Point2DFloat32.h>
+#include <deprecated_msgs/Point2DFloat32.h>
#include <robot_msgs/Point32.h>
#include <costmap_2d/observation.h>
#include <trajectory_rollout/world_model.h>
@@ -65,7 +65,7 @@
* @param obstacle_range The maximum distance for obstacles to be added to the grid
* @param min_separation The minimum distance between points in the grid
*/
- PointGrid(double width, double height, double resolution, std_msgs::Point2DFloat32 origin,
+ PointGrid(double width, double height, double resolution, deprecated_msgs::Point2DFloat32 origin,
double max_z, double obstacle_range, double min_separation);
/**
@@ -79,7 +79,7 @@
* @param upper_right The upper right corner of the range search
* @param points A vector of pointers to lists of the relevant points
*/
- void getPointsInRange(std_msgs::Point2DFloat32 lower_left, std_msgs::Point2DFloat32 upper_right, std::vector< std::list<robot_msgs::Point32>* > points);
+ void getPointsInRange(deprecated_msgs::Point2DFloat32 lower_left, deprecated_msgs::Point2DFloat32 upper_right, std::vector< std::list<robot_msgs::Point32>* > points);
/**
* @brief Checks if any points in the grid lie inside a convex footprint
@@ -89,7 +89,7 @@
* @param circumscribed_radius The radius of the circumscribed circle of the robot
* @return True if all points lie outside the footprint, false otherwise
*/
- virtual bool legalFootprint(const std_msgs::Point2DFloat32& position, const std::vector<std_msgs::Point2DFloat32>& footprint,
+ virtual bool legalFootprint(const deprecated_msgs::Point2DFloat32& position, const std::vector<deprecated_msgs::Point2DFloat32>& footprint,
double inscribed_radius, double circumscribed_radius);
/**
@@ -97,7 +97,7 @@
* @param observations The observations from various sensors
* @param laser_outline The polygon of the active sensor region
*/
- virtual void updateWorld(const std::vector<costmap_2d::Observation>& observations, const std::vector<std_msgs::Point2DFloat32>& laser_outline);
+ virtual void updateWorld(const std::vector<costmap_2d::Observation>& observations, const std::vector<deprecated_msgs::Point2DFloat32>& laser_outline);
/**
* @brief Convert from world coordinates to grid coordinates
@@ -106,7 +106,7 @@
* @param gy The y coordinate of the corresponding grid cell to be set by the function
* @return True if the conversion was successful, false otherwise
*/
- inline bool gridCoords(std_msgs::Point2DFloat32 pt, unsigned int& gx, unsigned int& gy) const {
+ inline bool gridCoords(deprecated_msgs::Point2DFloat32 pt, unsigned int& gx, unsigned int& gy) const {
if(pt.x < origin_.x || pt.y < origin_.y){
gx = 0;
gy = 0;
@@ -131,7 +131,7 @@
* @param lower_left The lower left bounds of the cell in world coordinates to be filled in
* @param upper_right The upper right bounds of the cell in world coordinates to be filled in
*/
- inline void getCellBounds(unsigned int gx, unsigned int gy, std_msgs::Point2DFloat32& lower_left, std_msgs::Point2DFloat32& upper_right) const {
+ inline void getCellBounds(unsigned int gx, unsigned int gy, deprecated_msgs::Point2DFloat32& lower_left, deprecated_msgs::Point2DFloat32& upper_right) const {
lower_left.x = gx * resolution_ + origin_.x;
lower_left.y = gy * resolution_ + origin_.y;
@@ -201,7 +201,7 @@
* @param c The point to compute orientation for
* @return orient(a, b, c) < 0 ----> Left, orient(a, b, c) > 0 ----> Right
*/
- inline double orient(const std_msgs::Point2DFloat32& a, const std_msgs::Point2DFloat32& b, const robot_msgs::Point32& c){
+ inline double orient(const deprecated_msgs::Point2DFloat32& a, const deprecated_msgs::Point2DFloat32& b, const robot_msgs::Point32& c){
double acx = a.x - c.x;
double bcx = b.x - c.x;
double acy = a.y - c.y;
@@ -215,7 +215,7 @@
* @param poly The polygon to check against
* @return True if the point is in the polygon, false otherwise
*/
- bool ptInPolygon(const robot_msgs::Point32& pt, const std::vector<std_msgs::Point2DFloat32>& poly);
+ bool ptInPolygon(const robot_msgs::Point32& pt, const std::vector<deprecated_msgs::Point2DFloat32>& poly);
/**
* @brief Insert a point into the point grid
@@ -243,11 +243,11 @@
* @brief Removes points from the grid that lie within the polygon
* @param poly A specification of the polygon to clear from the grid
*/
- void removePointsInPolygon(const std::vector<std_msgs::Point2DFloat32> poly);
+ void removePointsInPolygon(const std::vector<deprecated_msgs::Point2DFloat32> poly);
private:
double resolution_; ///< @brief The resolution of the grid in meters/cell
- std_msgs::Point2DFloat32 origin_; ///< @brief The origin point of the grid
+ deprecated_msgs::Point2DFloat32 origin_; ///< @brief The origin point of the grid
unsigned int width_; ///< @brief The width of the grid in cells
unsigned int height_; ///< @brief The height of the grid in cells
std::vector< std::list<robot_msgs::Point32> > cells_; ///< @brief Storage for the cells in the grid
Modified: pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/trajectory_controller.h
===================================================================
--- pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/trajectory_controller.h 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/trajectory_controller.h 2009-02-11 02:35:23 UTC (rev 10969)
@@ -52,8 +52,8 @@
#include <trajectory_rollout/trajectory.h>
//we'll take in a path as a vector of points
-#include <std_msgs/Point2DFloat32.h>
-#include <std_msgs/Position2DInt.h>
+#include <deprecated_msgs/Point2DFloat32.h>
+#include <trajectory_rollout/Position2DInt.h>
//for computing path distance
#include <queue>
@@ -97,7 +97,7 @@
*/
TrajectoryController(WorldModel& world_model,
const costmap_2d::ObstacleMapAccessor& ma,
- std::vector<std_msgs::Point2DFloat32> footprint_spec,
+ std::vector<deprecated_msgs::Point2DFloat32> footprint_spec,
double inscribed_radius, double circumscribed_radius,
double acc_lim_x = 1.0, double acc_lim_y = 1.0, double acc_lim_theta = 1.0,
double sim_time = 1.0, double sim_granularity = 0.025, int samples_per_dim = 20,
@@ -129,7 +129,7 @@
* @brief Update the plan that the controller is following
* @param new_plan A new plan for the controller to follow
*/
- void updatePlan(const std::vector<std_msgs::Point2DFloat32>& new_plan);
+ void updatePlan(const std::vector<deprecated_msgs::Point2DFloat32>& new_plan);
/**
* @brief Used for display purposes, allows the footprint of the robot to be drawn in visualization tools
@@ -138,7 +138,7 @@
* @param theta_i The orientation of the robot
* @return A vector of points in world coordinates that correspond to the verticies of the robot's footprint
*/
- std::vector<std_msgs::Point2DFloat32> drawFootprint(double x_i, double y_i, double theta_i);
+ std::vector<deprecated_msgs::Point2DFloat32> drawFootprint(double x_i, double y_i, double theta_i);
/**
* @brief Accessor for the goal the robot is currently pursuing in world corrdinates
@@ -214,7 +214,7 @@
* @param fill If true: returns all cells in the footprint of the robot. If false: returns only the cells that make up the outline of the footprint.
* @return The cells that make up either the outline or entire footprint of the robot depending on fill
*/
- std::vector<std_msgs::Position2DInt> getFootprintCells(double x_i, double y_i, double theta_i, bool fill);
+ std::vector<trajectory_rollout::Position2DInt> getFootprintCells(double x_i, double y_i, double theta_i, bool fill);
/**
* @brief Use Bresenham's algorithm to trace a line between two points in a grid
@@ -224,13 +224,13 @@
* @param y1 The y coordinate of the second point
* @param pts Will be filled with the cells that lie on the line in the grid
*/
- void getLineCells(int x0, int x1, int y0, int y1, std::vector<std_msgs::Position2DInt>& pts);
+ void getLineCells(int x0, int x1, int y0, int y1, std::vector<trajectory_rollout::Position2DInt>& pts);
/**
* @brief Fill the outline of a polygon, in this case the robot footprint, in a grid
* @param footprint The list of cells making up the footprint in the grid, will be modified to include all cells inside the footprint
*/
- void getFillCells(std::vector<std_msgs::Position2DInt>& footprint);
+ void getFillCells(std::vector<trajectory_rollout::Position2DInt>& footprint);
/**
* @brief Update what cells are considered path based on the global plan
@@ -241,11 +241,11 @@
const costmap_2d::ObstacleMapAccessor& ma_; ///< @brief Provides access to cost map information
WorldModel& world_model_; ///< @brief The world model that the controller uses for collision detection
- std::vector<std_msgs::Point2DFloat32> footprint_spec_; ///< @brief The footprint specification of the robot
+ std::vector<deprecated_msgs::Point2DFloat32> footprint_spec_; ///< @brief The footprint specification of the robot
double inscribed_radius_, circumscribed_radius_; ///< @brief The inscribed and circumscribed radii of the robot
- std::vector<std_msgs::Point2DFloat32> global_plan_; ///< @brief The global path for the robot to follow
+ std::vector<deprecated_msgs::Point2DFloat32> global_plan_; ///< @brief The global path for the robot to follow
bool stuck_left, stuck_right; ///< @brief Booleans to keep the robot from oscillating during rotation
bool rotating_left, rotating_right; ///< @brief Booleans to keep track of the direction of rotation for the robot
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-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/trajectory_controller_ros.h 2009-02-11 02:35:23 UTC (rev 10969)
@@ -47,8 +47,7 @@
#include <tf/transform_datatypes.h>
-#include <std_msgs/Point2DFloat32.h>
-#include <std_msgs/Position2DInt.h>
+#include <deprecated_msgs/Point2DFloat32.h>
#include <robot_msgs/PoseDot.h>
namespace trajectory_rollout {
@@ -67,7 +66,7 @@
* @param circumscribed_radius The circumscribed radius of the robot
*/
TrajectoryControllerROS(ros::Node& ros_node,
- const costmap_2d::CostMapAccessor& ma, std::vector<std_msgs::Point2DFloat32> footprint_spec,
+ const costmap_2d::CostMapAccessor& ma, std::vector<deprecated_msgs::Point2DFloat32> footprint_spec,
double inscribed_radius, double cirumscribed_radius);
/**
@@ -82,7 +81,7 @@
* @param theta_i The orientation of the robot
* @return A vector of points in world coordinates that correspond to the verticies of the robot's footprint
*/
- std::vector<std_msgs::Point2DFloat32> drawFootprint(double x_i, double y_i, double theta_i);
+ std::vector<deprecated_msgs::Point2DFloat32> drawFootprint(double x_i, double y_i, double theta_i);
/**
* @brief Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base
Modified: pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/world_model.h
===================================================================
--- pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/world_model.h 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/nav/trajectory_rollout/include/trajectory_rollout/world_model.h 2009-02-11 02:35:23 UTC (rev 10969)
@@ -39,7 +39,7 @@
#include <vector>
#include <costmap_2d/observation.h>
-#include <std_msgs/Point2DFloat32.h>
+#include <deprecated_msgs/Point2DFloat32.h>
namespace trajectory_rollout {
/**
@@ -54,7 +54,7 @@
* @param observations The observations from various sensors
* @param laser_outline The polygon of the active sensor region
*/
- virtual void updateWorld(const std::vector<costmap_2d::Observation>& observations, const std::vector<std_msgs::Point2DFloat32>& laser_outline) = 0;
+ virtual void updateWorld(const std::vector<costmap_2d::Observation>& observations, const std::vector<deprecated_msgs::Point2DFloat32>& laser_outline) = 0;
/**
* @brief Subclass will implement this method to check a footprint at a given position and orientation for legality in the world
@@ -64,7 +64,7 @@
* @param circumscribed_radius The radius of the circumscribed circle of the robot
* @return True if the footprint is legal based on the world model, false otherwise
*/
- virtual bool legalFootprint(const std_msgs::Point2DFloat32& position, const std::vector<std_msgs::Point2DFloat32>& footprint,
+ virtual bool legalFootprint(const deprecated_msgs::Point2DFloat32& position, const std::vector<deprecated_msgs::Point2DFloat32>& footprint,
double inscribed_radius, double circumscribed_radius) = 0;
/**
Modified: pkg/trunk/nav/trajectory_rollout/msg/GlobalPlan.msg
===================================================================
--- pkg/trunk/nav/trajectory_rollout/msg/GlobalPlan.msg 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/nav/trajectory_rollout/msg/GlobalPlan.msg 2009-02-11 02:35:23 UTC (rev 10969)
@@ -1 +1 @@
-std_msgs/Point2DFloat32[] path
+deprecated_msgs/Point2DFloat32[] path
Added: pkg/trunk/nav/trajectory_rollout/msg/Position2DInt.msg
===================================================================
--- pkg/trunk/nav/trajectory_rollout/msg/Position2DInt.msg (rev 0)
+++ pkg/trunk/nav/trajectory_rollout/msg/Position2DInt.msg 2009-02-11 02:35:23 UTC (rev 10969)
@@ -0,0 +1,2 @@
+int64 x
+int64 y
\ No newline at end of file
Modified: pkg/trunk/nav/trajectory_rollout/src/costmap_model.cpp
===================================================================
--- pkg/trunk/nav/trajectory_rollout/src/costmap_model.cpp 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/nav/trajectory_rollout/src/costmap_model.cpp 2009-02-11 02:35:23 UTC (rev 10969)
@@ -37,7 +37,7 @@
#include <trajectory_rollout/costmap_model.h>
using namespace std;
-using namespace std_msgs;
+using namespace deprecated_msgs;
using namespace costmap_2d;
namespace trajectory_rollout {
Modified: pkg/trunk/nav/trajectory_rollout/src/governor_node.cpp
===================================================================
--- pkg/trunk/nav/trajectory_rollout/src/governor_node.cpp 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/nav/trajectory_rollout/src/governor_node.cpp 2009-02-11 02:35:23 UTC (rev 10969)
@@ -38,7 +38,7 @@
using namespace trajectory_rollout;
namespace trajectory_rollout{
- GovernorNode::GovernorNode(std::vector<std_msgs::Point2DFloat32> footprint_spec) :
+ GovernorNode::GovernorNode(std::vector<deprecated_msgs::Point2DFloat32> footprint_spec) :
ros::Node("governor_node"), map_(MAP_SIZE_X, MAP_SIZE_Y),
tf_(*this, true, (uint64_t)10000000000ULL),
ma_(map_, OUTER_RADIUS),
@@ -86,7 +86,7 @@
ma_.synchronize();
//update the global plan from the message
- vector<std_msgs::Point2DFloat32> plan;
+ vector<deprecated_msgs::Point2DFloat32> plan;
for(unsigned int i = 0; i < plan_msg_.plan.get_path_size(); ++i){
plan.push_back(plan_msg_.plan.path[i]);
@@ -176,7 +176,7 @@
publish("local_path", path_msg);
printf("path msg\n");
- vector<std_msgs::Point2DFloat32> footprint = tc_.drawFootprint(x, y, th);
+ vector<deprecated_msgs::Point2DFloat32> footprint = tc_.drawFootprint(x, y, th);
//let's also draw the footprint of the robot for the last point on the selected trajectory
footprint_msg.set_points_size(footprint.size());
footprint_msg.color.r = 1.0;
@@ -223,8 +223,8 @@
int main(int argc, char** argv){
ros::init(argc, argv);
- std::vector<std_msgs::Point2DFloat32> footprint_spec;
- std_msgs::Point2DFloat32 pt;
+ std::vector<deprecated_msgs::Point2DFloat32> footprint_spec;
+ deprecated_msgs::Point2DFloat32 pt;
//create a square footprint
pt.x = ROBOT_FRONT_RADIUS;
pt.y = ROBOT_SIDE_RADIUS;
Modified: pkg/trunk/nav/trajectory_rollout/src/point_grid.cpp
===================================================================
--- pkg/trunk/nav/trajectory_rollout/src/point_grid.cpp 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/nav/trajectory_rollout/src/point_grid.cpp 2009-02-11 02:35:23 UTC (rev 10969)
@@ -42,12 +42,12 @@
using namespace std;
using namespace robot_msgs;
-using namespace std_msgs;
+using namespace deprecated_msgs;
using namespace costmap_2d;
namespace trajectory_rollout {
-PointGrid::PointGrid(double size_x, double size_y, double resolution, std_msgs::Point2DFloat32 origin, double max_z, double obstacle_range, double min_seperation) :
+PointGrid::PointGrid(double size_x, double size_y, double resolution, deprecated_msgs::Point2DFloat32 origin, double max_z, double obstacle_range, double min_seperation) :
resolution_(resolution), origin_(origin), max_z_(max_z), sq_obstacle_range_(obstacle_range * obstacle_range), sq_min_separation_(min_seperation * min_seperation)
{
width_ = (int) (size_x / resolution_);
Modified: pkg/trunk/nav/trajectory_rollout/src/trajectory_controller.cpp
===================================================================
--- pkg/trunk/nav/trajectory_rollout/src/trajectory_controller.cpp 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/nav/trajectory_rollout/src/trajectory_controller.cpp 2009-02-11 02:35:23 UTC (rev 10969)
@@ -38,13 +38,13 @@
#include <trajectory_rollout/trajectory_controller.h>
using namespace std;
-using namespace std_msgs;
+using namespace deprecated_msgs;
using namespace costmap_2d;
namespace trajectory_rollout{
TrajectoryController::TrajectoryController(WorldModel& world_model,
const costmap_2d::ObstacleMapAccessor& ma,
- std::vector<std_msgs::Point2DFloat32> footprint_spec,
+ std::vector<deprecated_msgs::Point2DFloat32> footprint_spec,
double inscribed_radius, double circumscribed_radius,
double acc_lim_x, double acc_lim_y, double acc_lim_theta,
double sim_time, double sim_granularity, int samples_per_dim,
@@ -625,8 +625,8 @@
Trajectory TrajectoryController::findBestPath(tf::Stamped<tf::Pose> global_pose, tf::Stamped<tf::Pose> global_vel,
tf::Stamped<tf::Pose>& drive_velocities, vector<costmap_2d::Observation> observations){
- std::vector<std_msgs::Point2DFloat32> clear_box;
- std_msgs::Point2DFloat32 pt;
+ std::vector<deprecated_msgs::Point2DFloat32> clear_box;
+ deprecated_msgs::Point2DFloat32 pt;
double x_pos = global_pose.getOrigin().getX();
double y_pos = global_pose.getOrigin().getY();
@@ -660,7 +660,7 @@
//temporarily remove obstacles that are within the footprint of the robot
- vector<std_msgs::Position2DInt> footprint_list = getFootprintCells(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), yaw, true);
+ vector<trajectory_rollout::Position2DInt> footprint_list = getFootprintCells(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), yaw, true);
//mark cells within the initial footprint of the robot
for(unsigned int i = 0; i < footprint_list.size(); ++i){
@@ -724,7 +724,7 @@
//build the oriented footprint
double cos_th = cos(theta_i);
double sin_th = sin(theta_i);
- vector<std_msgs::Point2DFloat32> oriented_footprint;
+ vector<deprecated_msgs::Point2DFloat32> oriented_footprint;
for(unsigned int i = 0; i < footprint_spec_.size(); ++i){
Point2DFloat32 new_pt;
new_pt.x = x_i + (footprint_spec_[i].x * cos_th - footprint_spec_[i].y * sin_th);
@@ -732,7 +732,7 @@
oriented_footprint.push_back(new_pt);
}
- std_msgs::Point2DFloat32 robot_position;
+ deprecated_msgs::Point2DFloat32 robot_position;
robot_position.x = x_i;
robot_position.y = y_i;
@@ -745,7 +745,7 @@
return -1.0;
}
- void TrajectoryController::getLineCells(int x0, int x1, int y0, int y1, vector<std_msgs::Position2DInt>& pts){
+ void TrajectoryController::getLineCells(int x0, int x1, int y0, int y1, vector<trajectory_rollout::Position2DInt>& pts){
//Bresenham Ray-Tracing
int deltax = abs(x1 - x0); // The difference between the x's
int deltay = abs(y1 - y0); // The difference between the y's
@@ -755,7 +755,7 @@
int xinc1, xinc2, yinc1, yinc2;
int den, num, numadd, numpixels;
- std_msgs::Position2DInt pt;
+ trajectory_rollout::Position2DInt pt;
if (x1 >= x0) // The x-values are increasing
{
@@ -817,9 +817,9 @@
}
//its nice to be able to draw a footprint for a particular point for debugging info
- vector<std_msgs::Point2DFloat32> TrajectoryController::drawFootprint(double x_i, double y_i, double theta_i){
- vector<std_msgs::Position2DInt> footprint_cells = getFootprintCells(x_i, y_i, theta_i, false);
- vector<std_msgs::Point2DFloat32> footprint_pts;
+ vector<deprecated_msgs::Point2DFloat32> TrajectoryController::drawFootprint(double x_i, double y_i, double theta_i){
+ vector<trajectory_rollout::Position2DInt> footprint_cells = getFootprintCells(x_i, y_i, theta_i, false);
+ vector<deprecated_msgs::Point2DFloat32> footprint_pts;
Point2DFloat32 pt;
for(unsigned int i = 0; i < footprint_cells.size(); ++i){
double pt_x, pt_y;
@@ -832,8 +832,8 @@
}
//get the cellsof a footprint at a given position
- vector<std_msgs::Position2DInt> TrajectoryController::getFootprintCells(double x_i, double y_i, double theta_i, bool fill){
- vector<std_msgs::Position2DInt> footprint_cells;
+ vector<trajectory_rollout::Position2DInt> TrajectoryController::getFootprintCells(double x_i, double y_i, double theta_i, bool fill){
+ vector<trajectory_rollout::Position2DInt> footprint_cells;
//if we have no footprint... do nothing
if(footprint_spec_.size() <= 1)
@@ -877,9 +877,9 @@
return footprint_cells;
}
- void TrajectoryController::getFillCells(vector<std_msgs::Position2DInt>& footprint){
+ void TrajectoryController::getFillCells(vector<trajectory_rollout::Position2DInt>& footprint){
//quick bubble sort to sort pts by x
- std_msgs::Position2DInt swap, pt;
+ trajectory_rollout::Position2DInt swap, pt;
unsigned int i = 0;
while(i < footprint.size() - 1){
if(footprint[i].x > footprint[i + 1].x){
@@ -894,8 +894,8 @@
}
i = 0;
- std_msgs::Position2DInt min_pt;
- std_msgs::Position2DInt max_pt;
+ trajectory_rollout::Position2DInt min_pt;
+ trajectory_rollout::Position2DInt max_pt;
unsigned int min_x = footprint[0].x;
unsigned int max_x = footprint[footprint.size() -1].x;
//walk through each column and mark cells inside the footprint
Modified: pkg/trunk/nav/trajectory_rollout/src/trajectory_controller_ros.cpp
===================================================================
--- pkg/trunk/nav/trajectory_rollout/src/trajectory_controller_ros.cpp 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/nav/trajectory_rollout/src/trajectory_controller_ros.cpp 2009-02-11 02:35:23 UTC (rev 10969)
@@ -40,13 +40,13 @@
#include <sys/time.h>
using namespace std;
-using namespace std_msgs;
+using namespace deprecated_msgs;
using namespace costmap_2d;
namespace trajectory_rollout {
TrajectoryControllerROS::TrajectoryControllerROS(ros::Node& ros_node,
const costmap_2d::CostMapAccessor& ma,
- std::vector<std_msgs::Point2DFloat32> footprint_spec, double inscribed_radius, double circumscribed_radius)
+ std::vector<deprecated_msgs::Point2DFloat32> footprint_spec, double inscribed_radius, double circumscribed_radius)
: world_model_(NULL), tc_(NULL){
double acc_lim_x, acc_lim_y, acc_lim_theta, sim_time, sim_granularity;
int samples_per_dim;
@@ -133,9 +133,9 @@
//map_.sizeCheck(ma_.getWidth(), ma_.getHeight(), origin_x, origin_y);
// Temporary Transformation till api below changes
- std::vector<std_msgs::Point2DFloat32> copiedGlobalPlan;
+ std::vector<deprecated_msgs::Point2DFloat32> copiedGlobalPlan;
for(std::list<deprecated_msgs::Pose2DFloat32>::const_iterator it = global_plan.begin(); it != global_plan.end(); ++it){
- std_msgs::Point2DFloat32 p;
+ deprecated_msgs::Point2DFloat32 p;
p.x = it->x;
p.y = it->y;
copiedGlobalPlan.push_back(p);
Modified: pkg/trunk/nav/trajectory_rollout/test/utest.cpp
===================================================================
--- pkg/trunk/nav/trajectory_rollout/test/utest.cpp 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/nav/trajectory_rollout/test/utest.cpp 2009-02-11 02:35:23 UTC (rev 10969)
@@ -44,7 +44,7 @@
#include <math.h>
#include <std_msgs/Point2DFloat32.h>
-#include <std_msgs/Position2DInt.h>
+#include <trajectory_rollout/Position2DInt.h>
using namespace std;
@@ -73,7 +73,7 @@
void TrajectoryControllerTest::correctFootprint(){
//just create a basic footprint
- vector<std_msgs::Position2DInt> footprint = tc.getFootprintCells(4.5, 4.5, 0, false);
+ vector<trajectory_rollout::Position2DInt> footprint = tc.getFootprintCells(4.5, 4.5, 0, false);
//we expect the front line to be first
EXPECT_EQ(footprint[0].x, 6); EXPECT_EQ(footprint[0].y, 6);
Modified: pkg/trunk/pr2_msgs/manifest.xml
===================================================================
--- pkg/trunk/pr2_msgs/manifest.xml 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/pr2_msgs/manifest.xml 2009-02-11 02:35:23 UTC (rev 10969)
@@ -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="robot_msgs"/>
+ <depend package="deprecated_msgs"/>
<depend package="std_msgs"/>
<export>
<cpp cflags="-I${prefix}/msg/cpp"/>
Modified: pkg/trunk/pr2_msgs/msg/OccDiff.msg
===================================================================
--- pkg/trunk/pr2_msgs/msg/OccDiff.msg 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/pr2_msgs/msg/OccDiff.msg 2009-02-11 02:35:23 UTC (rev 10969)
@@ -1,3 +1,3 @@
Header header
-std_msgs/Point2DFloat32[] occ_points
-std_msgs/Point2DFloat32[] unocc_points
+deprecated_msgs/Point2DFloat32[] occ_points
+deprecated_msgs/Point2DFloat32[] unocc_points
Modified: pkg/trunk/pr2_srvs/manifest.xml
===================================================================
--- pkg/trunk/pr2_srvs/manifest.xml 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/pr2_srvs/manifest.xml 2009-02-11 02:35:23 UTC (rev 10969)
@@ -12,6 +12,7 @@
<depend package="robot_msgs"/>
<depend package="pr2_msgs"/>
<depend package="std_msgs"/>
+ <depend package="deprecated_msgs"/>
<export>
<cpp cflags="-I${prefix}/srv/cpp"/>
</export>
Modified: pkg/trunk/prcore/robot_msgs/msg/Polyline2D.msg
===================================================================
--- pkg/trunk/prcore/robot_msgs/msg/Polyline2D.msg 2009-02-11 02:31:59 UTC (rev 10968)
+++ pkg/trunk/prcore/robot_msgs/msg/Polyline2D.msg 2009-02-11 02:35:23 UTC (rev 10969)
@@ -1,2 +1,2 @@
-std_msgs/Point2DFloat32[] points
+deprecated_msgs/Point2DFloat32[] points
std_msgs/ColorRGBA color
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|