|
From: <tpr...@us...> - 2009-01-12 22:27:57
|
Revision: 9272
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=9272&view=rev
Author: tpratkanis
Date: 2009-01-12 22:10:26 +0000 (Mon, 12 Jan 2009)
Log Message:
-----------
Moving std_msgs/Planner2DState and std_msgs/Planner2DGoal to robot_msgs.
Modified Paths:
--------------
pkg/trunk/highlevel/executive_python/src/navigation_adapter.py
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/BaseControllerAdapter.cc
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/BaseControllerAdapter.hh
pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh
pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp
pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.h
pkg/trunk/nav/nav_view/src/nav_view/tools.cpp
pkg/trunk/nav/wavefront_player/cli.cpp
pkg/trunk/nav/wavefront_player/manifest.xml
pkg/trunk/nav/wavefront_player/wavefront_player.cc
Added Paths:
-----------
pkg/trunk/robot_msgs/msg/Planner2DGoal.msg
pkg/trunk/robot_msgs/msg/Planner2DState.msg
Modified: pkg/trunk/highlevel/executive_python/src/navigation_adapter.py
===================================================================
--- pkg/trunk/highlevel/executive_python/src/navigation_adapter.py 2009-01-12 21:58:09 UTC (rev 9271)
+++ pkg/trunk/highlevel/executive_python/src/navigation_adapter.py 2009-01-12 22:10:26 UTC (rev 9272)
@@ -38,7 +38,7 @@
rostools.update_path('executive_python')
import rospy
import random
-from std_msgs.msg import Planner2DGoal, Planner2DState
+from robot_msgs.msg import Planner2DGoal, Planner2DState
class NavigationAdapter:
def __init__(self, no_plan_limit, time_limit, state_topic, goal_topic):
@@ -83,6 +83,7 @@
goal.goal.x = goal_pts[0]
goal.goal.y = goal_pts[1]
goal.goal.th = goal_pts[2]
+ goal.timeout = 0
goal.enable = 1
self.pub.publish(goal)
Modified: pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/BaseControllerAdapter.cc
===================================================================
--- pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/BaseControllerAdapter.cc 2009-01-12 21:58:09 UTC (rev 9271)
+++ pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/BaseControllerAdapter.cc 2009-01-12 22:10:26 UTC (rev 9272)
@@ -1,16 +1,16 @@
#include "ROSControllerAdapter.hh"
#include "IntervalDomain.hh"
#include "Token.hh"
-#include <std_msgs/Planner2DState.h>
-#include <std_msgs/Planner2DGoal.h>
+#include <robot_msgs/Planner2DState.h>
+#include <robot_msgs/Planner2DGoal.h>
namespace TREX {
- class BaseControllerAdapter: public ROSControllerAdapter<std_msgs::Planner2DState, std_msgs::Planner2DGoal> {
+ class BaseControllerAdapter: public ROSControllerAdapter<robot_msgs::Planner2DState, robot_msgs::Planner2DGoal> {
public:
BaseControllerAdapter(const LabelStr& agentName, const TiXmlElement& configData)
- : ROSControllerAdapter<std_msgs::Planner2DState, std_msgs::Planner2DGoal>(agentName, configData){
+ : ROSControllerAdapter<robot_msgs::Planner2DState, robot_msgs::Planner2DGoal>(agentName, configData){
}
virtual ~BaseControllerAdapter(){}
@@ -29,7 +29,7 @@
obs->push_back("th", new IntervalDomain(stateMsg.pos.th));
}
- void fillRequestParameters(std_msgs::Planner2DGoal& goalMsg, const TokenId& goalToken){
+ void fillRequestParameters(robot_msgs::Planner2DGoal& goalMsg, const TokenId& goalToken){
const IntervalDomain& x = goalToken->getVariable("x")->lastDomain();
const IntervalDomain& y = goalToken->getVariable("y")->lastDomain();
const IntervalDomain& th = goalToken->getVariable("th")->lastDomain();
Modified: pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/BaseControllerAdapter.hh
===================================================================
--- pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/BaseControllerAdapter.hh 2009-01-12 21:58:09 UTC (rev 9271)
+++ pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/BaseControllerAdapter.hh 2009-01-12 22:10:26 UTC (rev 9272)
@@ -4,7 +4,7 @@
#include "ROSAdapter.hh"
// State Update messages
-#include <std_msgs/Planner2DState.h>
+#include <robot_msgs/Planner2DState.h>
namespace TREX {
Modified: pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh 2009-01-12 21:58:09 UTC (rev 9271)
+++ pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh 2009-01-12 22:10:26 UTC (rev 9272)
@@ -52,8 +52,8 @@
#include <plan_wrap.h>
// Message structures used
-#include <std_msgs/Planner2DState.h>
-#include <std_msgs/Planner2DGoal.h>
+#include <robot_msgs/Planner2DState.h>
+#include <robot_msgs/Planner2DGoal.h>
#include <std_msgs/LaserScan.h>
#include <std_msgs/BaseVel.h>
#include <std_msgs/RobotBase2DOdom.h>
@@ -73,7 +73,7 @@
namespace ros {
namespace highlevel_controllers {
- class MoveBase : public HighlevelController<std_msgs::Planner2DState, std_msgs::Planner2DGoal> {
+ class MoveBase : public HighlevelController<robot_msgs::Planner2DState, robot_msgs::Planner2DGoal> {
public:
Modified: pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp
===================================================================
--- pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp 2009-01-12 21:58:09 UTC (rev 9271)
+++ pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp 2009-01-12 22:10:26 UTC (rev 9272)
@@ -114,7 +114,7 @@
render_panel_->getViewport()->setCamera( camera_ );
- ros_node_->advertise<std_msgs::Planner2DGoal>("goal", 1);
+ ros_node_->advertise<robot_msgs::Planner2DGoal>("goal", 1);
ros_node_->advertise<std_msgs::Pose2DFloat32>("initialpose", 1);
ros_node_->subscribe("particlecloud", cloud_, &NavViewPanel::incomingParticleCloud, this, 1);
ros_node_->subscribe("gui_path", path_line_, &NavViewPanel::incomingGuiPath, this, 1);
Modified: pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.h
===================================================================
--- pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.h 2009-01-12 21:58:09 UTC (rev 9271)
+++ pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.h 2009-01-12 22:10:26 UTC (rev 9272)
@@ -33,7 +33,7 @@
#include "nav_view_panel_generated.h"
#include "std_msgs/ParticleCloud2D.h"
-#include "std_msgs/Planner2DGoal.h"
+#include "robot_msgs/Planner2DGoal.h"
#include "std_msgs/Polyline2D.h"
#include "std_msgs/Pose2DFloat32.h"
#include "std_srvs/StaticMap.h"
@@ -206,7 +206,7 @@
Ogre::TexturePtr map_texture_;
std_msgs::ParticleCloud2D cloud_;
- std_msgs::Planner2DGoal goal_;
+ robot_msgs::Planner2DGoal goal_;
std_msgs::Polyline2D path_line_;
std_msgs::Polyline2D local_path_;
std_msgs::Polyline2D robot_footprint_;
Modified: pkg/trunk/nav/nav_view/src/nav_view/tools.cpp
===================================================================
--- pkg/trunk/nav/nav_view/src/nav_view/tools.cpp 2009-01-12 21:58:09 UTC (rev 9271)
+++ pkg/trunk/nav/nav_view/src/nav_view/tools.cpp 2009-01-12 22:10:26 UTC (rev 9272)
@@ -158,7 +158,7 @@
if ( is_goal_ )
{
- std_msgs::Planner2DGoal goal;
+ robot_msgs::Planner2DGoal goal;
goal.goal.x = pos_.x;
goal.goal.y = pos_.y;
goal.goal.th = angle;
Modified: pkg/trunk/nav/wavefront_player/cli.cpp
===================================================================
--- pkg/trunk/nav/wavefront_player/cli.cpp 2009-01-12 21:58:09 UTC (rev 9271)
+++ pkg/trunk/nav/wavefront_player/cli.cpp 2009-01-12 22:10:26 UTC (rev 9272)
@@ -1,14 +1,14 @@
#include <cstdio>
#include <stdlib.h>
#include "ros/node.h"
-#include "std_msgs/Planner2DState.h"
-#include "std_msgs/Planner2DGoal.h"
+#include "robot_msgs/Planner2DState.h"
+#include "robot_msgs/Planner2DGoal.h"
class WavefrontCLI : public ros::node
{
public:
- std_msgs::Planner2DState wf_state;
- std_msgs::Planner2DGoal wf_goal;
+ robot_msgs::Planner2DState wf_state;
+ robot_msgs::Planner2DGoal wf_goal;
enum { WF_IDLE, WF_SEEKING_GOAL, WF_DONE } state;
WavefrontCLI(double x, double y, double th)
@@ -19,7 +19,7 @@
wf_goal.goal.th = th;
wf_goal.enable = 1;
subscribe("state", wf_state, &WavefrontCLI::state_cb, 1);
- advertise<std_msgs::Planner2DGoal>("goal", 1);
+ advertise<robot_msgs::Planner2DGoal>("goal", 1);
}
void state_cb()
{
Modified: pkg/trunk/nav/wavefront_player/manifest.xml
===================================================================
--- pkg/trunk/nav/wavefront_player/manifest.xml 2009-01-12 21:58:09 UTC (rev 9271)
+++ pkg/trunk/nav/wavefront_player/manifest.xml 2009-01-12 22:10:26 UTC (rev 9272)
@@ -8,6 +8,7 @@
<depend package="player" />
<depend package="laser_scan" />
<depend package="std_srvs" />
+ <depend package="robot_msgs" />
<depend package="tf"/>
<export>
<cpp cflags="-I${prefix}/srv/cpp"/>
Modified: pkg/trunk/nav/wavefront_player/wavefront_player.cc
===================================================================
--- pkg/trunk/nav/wavefront_player/wavefront_player.cc 2009-01-12 21:58:09 UTC (rev 9271)
+++ pkg/trunk/nav/wavefront_player/wavefront_player.cc 2009-01-12 22:10:26 UTC (rev 9272)
@@ -114,8 +114,8 @@
#include "boost/thread/mutex.hpp"
// The messages that we'll use
-#include <std_msgs/Planner2DState.h>
-#include <std_msgs/Planner2DGoal.h>
+#include <robot_msgs/Planner2DState.h>
+#include <robot_msgs/Planner2DGoal.h>
#include <std_msgs/BaseVel.h>
#include <std_msgs/PointCloud.h>
#include <std_msgs/LaserScan.h>
@@ -202,11 +202,11 @@
double tvmin, tvmax, avmin, avmax, amin, amax;
// incoming/outgoing messages
- std_msgs::Planner2DGoal goalMsg;
+ robot_msgs::Planner2DGoal goalMsg;
//MsgRobotBase2DOdom odomMsg;
std_msgs::Polyline2D polylineMsg;
std_msgs::Polyline2D pointcloudMsg;
- std_msgs::Planner2DState pstate;
+ robot_msgs::Planner2DState pstate;
//MsgRobotBase2DOdom prevOdom;
bool firstodom;
@@ -365,7 +365,7 @@
this->firstodom = true;
- advertise<std_msgs::Planner2DState>("state",1);
+ advertise<robot_msgs::Planner2DState>("state",1);
advertise<std_msgs::Polyline2D>("gui_path",1);
advertise<std_msgs::Polyline2D>("gui_laser",1);
advertise<std_msgs::BaseVel>("cmd_vel",1);
Added: pkg/trunk/robot_msgs/msg/Planner2DGoal.msg
===================================================================
--- pkg/trunk/robot_msgs/msg/Planner2DGoal.msg (rev 0)
+++ pkg/trunk/robot_msgs/msg/Planner2DGoal.msg 2009-01-12 22:10:26 UTC (rev 9272)
@@ -0,0 +1,6 @@
+Header header
+std_msgs/Pose2DFloat32 goal
+byte enable
+
+# Timelimit for planning. Set it to zero for unlimited.
+float64 timeout
Added: pkg/trunk/robot_msgs/msg/Planner2DState.msg
===================================================================
--- pkg/trunk/robot_msgs/msg/Planner2DState.msg (rev 0)
+++ pkg/trunk/robot_msgs/msg/Planner2DState.msg 2009-01-12 22:10:26 UTC (rev 9272)
@@ -0,0 +1,22 @@
+Header header
+# Is the planner actively going to a goal?
+byte active
+# Did the planner find a valid path?
+byte valid
+# Have we arrived at the goal?
+byte done
+#Did the planner give up?
+byte aborted
+#Was the planner told to stop?
+byte preempted
+# Current location (m,m,rad)
+std_msgs/Pose2DFloat32 pos
+# Goal location (m,m,rad)
+std_msgs/Pose2DFloat32 goal
+# Current waypoint location (m,m,rad)
+std_msgs/Pose2DFloat32 waypoint
+# Current list of waypoints in the plan
+std_msgs/Pose2DFloat32[] waypoints
+# Current waypoint index. May be negative if there's no plan, or if
+# the plan is done
+int32 waypoint_idx
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|