|
From: <vij...@us...> - 2009-08-25 05:41:44
|
Revision: 22820
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=22820&view=rev
Author: vijaypradeep
Date: 2009-08-25 05:41:33 +0000 (Tue, 25 Aug 2009)
Log Message:
-----------
Moving actionlib messages into common_msgs/actionlib_msgs. Trac #2504
Modified Paths:
--------------
pkg/trunk/highlevel/move_arm/manifest.xml
pkg/trunk/highlevel/move_arm/msg/ActuateGripperActionFeedback.msg
pkg/trunk/highlevel/move_arm/msg/ActuateGripperActionGoal.msg
pkg/trunk/highlevel/move_arm/msg/ActuateGripperActionResult.msg
pkg/trunk/highlevel/move_arm/msg/ActuateGripperFeedback.msg
pkg/trunk/highlevel/move_arm/msg/ActuateGripperResult.msg
pkg/trunk/highlevel/move_arm/msg/MoveArmActionFeedback.msg
pkg/trunk/highlevel/move_arm/msg/MoveArmActionGoal.msg
pkg/trunk/highlevel/move_arm/msg/MoveArmActionResult.msg
pkg/trunk/sandbox/move_base_client/src/move_base_translator.cpp
pkg/trunk/stacks/common/actionlib/genaction.py
pkg/trunk/stacks/common/actionlib/include/actionlib/client/action_client.h
pkg/trunk/stacks/common/actionlib/include/actionlib/client/client_goal_handle_imp.h
pkg/trunk/stacks/common/actionlib/include/actionlib/client/client_helpers.h
pkg/trunk/stacks/common/actionlib/include/actionlib/client/comm_state_machine_imp.h
pkg/trunk/stacks/common/actionlib/include/actionlib/client/goal_manager_imp.h
pkg/trunk/stacks/common/actionlib/include/actionlib/goal_id_generator.h
pkg/trunk/stacks/common/actionlib/include/actionlib/server/action_server.h
pkg/trunk/stacks/common/actionlib/include/actionlib/server/action_server_imp.h
pkg/trunk/stacks/common/actionlib/include/actionlib/server/server_goal_handle.h
pkg/trunk/stacks/common/actionlib/include/actionlib/server/server_goal_handle_imp.h
pkg/trunk/stacks/common/actionlib/include/actionlib/server/simple_action_server_imp.h
pkg/trunk/stacks/common/actionlib/include/actionlib/server/status_tracker.h
pkg/trunk/stacks/common/actionlib/include/actionlib/server/status_tracker_imp.h
pkg/trunk/stacks/common/actionlib/manifest.xml
pkg/trunk/stacks/common/actionlib_tutorials/manifest.xml
pkg/trunk/stacks/common/actionlib_tutorials/msg/AveragingActionFeedback.msg
pkg/trunk/stacks/common/actionlib_tutorials/msg/AveragingActionGoal.msg
pkg/trunk/stacks/common/actionlib_tutorials/msg/AveragingActionResult.msg
pkg/trunk/stacks/common/actionlib_tutorials/msg/FibonacciActionFeedback.msg
pkg/trunk/stacks/common/actionlib_tutorials/msg/FibonacciActionGoal.msg
pkg/trunk/stacks/common/actionlib_tutorials/msg/FibonacciActionResult.msg
pkg/trunk/stacks/mechanism/mechanism_msgs/manifest.xml
pkg/trunk/stacks/mechanism/mechanism_msgs/msg/SwitchControllerActionFeedback.msg
pkg/trunk/stacks/mechanism/mechanism_msgs/msg/SwitchControllerActionGoal.msg
pkg/trunk/stacks/mechanism/mechanism_msgs/msg/SwitchControllerActionResult.msg
pkg/trunk/stacks/navigation/move_base_msgs/manifest.xml
pkg/trunk/stacks/navigation/move_base_msgs/msg/MoveBaseActionFeedback.msg
pkg/trunk/stacks/navigation/move_base_msgs/msg/MoveBaseActionGoal.msg
pkg/trunk/stacks/navigation/move_base_msgs/msg/MoveBaseActionResult.msg
pkg/trunk/stacks/navigation/move_base_msgs/msg/MoveBaseFeedback.msg
pkg/trunk/stacks/navigation/move_base_msgs/msg/MoveBaseResult.msg
Added Paths:
-----------
pkg/trunk/stacks/common_msgs/actionlib_msgs/
pkg/trunk/stacks/common_msgs/actionlib_msgs/msg/
pkg/trunk/stacks/common_msgs/actionlib_msgs/msg/GoalID.msg
pkg/trunk/stacks/common_msgs/actionlib_msgs/msg/GoalStatus.msg
pkg/trunk/stacks/common_msgs/actionlib_msgs/msg/GoalStatusArray.msg
Removed Paths:
-------------
pkg/trunk/stacks/common/actionlib/msg/GoalID.msg
pkg/trunk/stacks/common/actionlib/msg/GoalStatus.msg
pkg/trunk/stacks/common/actionlib/msg/GoalStatusArray.msg
pkg/trunk/stacks/common/actionlib/msg/RequestType.msg
Modified: pkg/trunk/highlevel/move_arm/manifest.xml
===================================================================
--- pkg/trunk/highlevel/move_arm/manifest.xml 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/highlevel/move_arm/manifest.xml 2009-08-25 05:41:33 UTC (rev 22820)
@@ -22,6 +22,7 @@
<depend package="planning_models" />
<depend package="planning_environment" />
<depend package="actionlib"/>
+ <depend package="actionlib_msgs"/>
<depend package="experimental_controllers"/>
<depend package="tf_conversions"/>
Modified: pkg/trunk/highlevel/move_arm/msg/ActuateGripperActionFeedback.msg
===================================================================
--- pkg/trunk/highlevel/move_arm/msg/ActuateGripperActionFeedback.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/highlevel/move_arm/msg/ActuateGripperActionFeedback.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1,4 +1,4 @@
Header header
-actionlib/GoalStatus status
+actionlib_msgs/GoalStatus status
ActuateGripperFeedback feedback
Modified: pkg/trunk/highlevel/move_arm/msg/ActuateGripperActionGoal.msg
===================================================================
--- pkg/trunk/highlevel/move_arm/msg/ActuateGripperActionGoal.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/highlevel/move_arm/msg/ActuateGripperActionGoal.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1,4 +1,4 @@
Header header
-actionlib/GoalID goal_id
+actionlib_msgs/GoalID goal_id
ActuateGripperGoal goal
Modified: pkg/trunk/highlevel/move_arm/msg/ActuateGripperActionResult.msg
===================================================================
--- pkg/trunk/highlevel/move_arm/msg/ActuateGripperActionResult.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/highlevel/move_arm/msg/ActuateGripperActionResult.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1,4 +1,4 @@
Header header
-actionlib/GoalStatus status
+actionlib_msgs/GoalStatus status
ActuateGripperResult result
Modified: pkg/trunk/highlevel/move_arm/msg/ActuateGripperFeedback.msg
===================================================================
--- pkg/trunk/highlevel/move_arm/msg/ActuateGripperFeedback.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/highlevel/move_arm/msg/ActuateGripperFeedback.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1,2 +1 @@
-float64 crap
Modified: pkg/trunk/highlevel/move_arm/msg/ActuateGripperResult.msg
===================================================================
--- pkg/trunk/highlevel/move_arm/msg/ActuateGripperResult.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/highlevel/move_arm/msg/ActuateGripperResult.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1 +0,0 @@
-float64 crap
Modified: pkg/trunk/highlevel/move_arm/msg/MoveArmActionFeedback.msg
===================================================================
--- pkg/trunk/highlevel/move_arm/msg/MoveArmActionFeedback.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/highlevel/move_arm/msg/MoveArmActionFeedback.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1,4 +1,4 @@
Header header
-actionlib/GoalStatus status
+actionlib_msgs/GoalStatus status
MoveArmFeedback feedback
Modified: pkg/trunk/highlevel/move_arm/msg/MoveArmActionGoal.msg
===================================================================
--- pkg/trunk/highlevel/move_arm/msg/MoveArmActionGoal.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/highlevel/move_arm/msg/MoveArmActionGoal.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1,4 +1,4 @@
Header header
-actionlib/GoalID goal_id
+actionlib_msgs/GoalID goal_id
MoveArmGoal goal
Modified: pkg/trunk/highlevel/move_arm/msg/MoveArmActionResult.msg
===================================================================
--- pkg/trunk/highlevel/move_arm/msg/MoveArmActionResult.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/highlevel/move_arm/msg/MoveArmActionResult.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1,4 +1,4 @@
Header header
-actionlib/GoalStatus status
+actionlib_msgs/GoalStatus status
MoveArmResult result
Modified: pkg/trunk/sandbox/move_base_client/src/move_base_translator.cpp
===================================================================
--- pkg/trunk/sandbox/move_base_client/src/move_base_translator.cpp 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/sandbox/move_base_client/src/move_base_translator.cpp 2009-08-25 05:41:33 UTC (rev 22820)
@@ -57,10 +57,10 @@
return action_feedback.cur_pose;
}*/
-PoseStamped fromActionResult(const move_base_msgs::MoveBaseResult& action_result)
+/*PoseStamped fromActionResult(const move_base_msgs::MoveBaseResult& action_result)
{
return action_result.final_pose;
-}
+}*/
int main(int argc, char** argv)
{
@@ -69,7 +69,7 @@
ros::NodeHandle n;
action_translator::ActionTranslator<move_base_msgs::MoveBaseAction, PoseStamped, PoseStamped>
- translator("move_base", &fromOldGoal, NULL, &fromActionResult);
+ translator("move_base", &fromOldGoal, NULL, NULL);
robot_actions::ActionRunner runner(10.0);
runner.connect<geometry_msgs::PoseStamped, nav_robot_actions::MoveBaseState, geometry_msgs::PoseStamped>(translator);
Modified: pkg/trunk/stacks/common/actionlib/genaction.py
===================================================================
--- pkg/trunk/stacks/common/actionlib/genaction.py 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/genaction.py 2009-08-25 05:41:33 UTC (rev 22820)
@@ -94,21 +94,21 @@
goal_msg = goal
action_goal_msg = """
Header header
-actionlib/GoalID goal_id
+actionlib_msgs/GoalID goal_id
%sGoal goal
""" % name
result_msg = result
action_result_msg = """
Header header
-actionlib/GoalStatus status
+actionlib_msgs/GoalStatus status
%sResult result
""" % name
feedback_msg = feedback
action_feedback_msg = """
Header header
-actionlib/GoalStatus status
+actionlib_msgs/GoalStatus status
%sFeedback feedback
""" % name
Modified: pkg/trunk/stacks/common/actionlib/include/actionlib/client/action_client.h
===================================================================
--- pkg/trunk/stacks/common/actionlib/include/actionlib/client/action_client.h 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/include/actionlib/client/action_client.h 2009-08-25 05:41:33 UTC (rev 22820)
@@ -117,7 +117,7 @@
*/
void cancelAllGoals()
{
- GoalID cancel_msg;
+ actionlib_msgs::GoalID cancel_msg;
// CancelAll policy encoded by stamp=0, id=0
cancel_msg.stamp = ros::Time(0,0);
cancel_msg.id = ros::Time(0,0);
@@ -196,7 +196,7 @@
goal_pub_.publish(action_goal);
}
- void sendCancelFunc(const GoalID& cancel_msg)
+ void sendCancelFunc(const actionlib_msgs::GoalID& cancel_msg)
{
cancel_pub_.publish(cancel_msg);
}
@@ -206,7 +206,7 @@
// Start publishers and subscribers
server_connected_ = false;
goal_pub_ = queue_advertise<ActionGoal>("goal", 1, boost::bind(&ActionClient::serverConnectionCb, this, _1), queue);
- cancel_pub_ = n_.advertise<GoalID>("cancel", 1, true);
+ cancel_pub_ = n_.advertise<actionlib_msgs::GoalID>("cancel", 1, true);
manager_.registerSendGoalFunc(boost::bind(&ActionClientT::sendGoalFunc, this, _1));
manager_.registerCancelFunc(boost::bind(&ActionClientT::sendCancelFunc, this, _1));
@@ -238,7 +238,7 @@
return n_.subscribe(ops);
}
- void statusCb(const GoalStatusArrayConstPtr& status_array)
+ void statusCb(const actionlib_msgs::GoalStatusArrayConstPtr& status_array)
{
manager_.updateStatuses(status_array);
}
Modified: pkg/trunk/stacks/common/actionlib/include/actionlib/client/client_goal_handle_imp.h
===================================================================
--- pkg/trunk/stacks/common/actionlib/include/actionlib/client/client_goal_handle_imp.h 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/include/actionlib/client/client_goal_handle_imp.h 2009-08-25 05:41:33 UTC (rev 22820)
@@ -94,21 +94,21 @@
if (comm_state_ != CommState::DONE)
ROS_WARN("Asking for the terminal state when we're in [%s]", comm_state_.toString().c_str());
- GoalStatus goal_status = list_handle_.getElem()->getGoalStatus();
+ actionlib_msgs::GoalStatus goal_status = list_handle_.getElem()->getGoalStatus();
switch (goal_status.status)
{
- case GoalStatus::PENDING:
- case GoalStatus::ACTIVE:
- case GoalStatus::PREEMPTING:
- case GoalStatus::RECALLING:
+ case actionlib_msgs::GoalStatus::PENDING:
+ case actionlib_msgs::GoalStatus::ACTIVE:
+ case actionlib_msgs::GoalStatus::PREEMPTING:
+ case actionlib_msgs::GoalStatus::RECALLING:
ROS_ERROR("Asking for terminal state, but latest goal status is %u", goal_status.status); return TerminalState::LOST;
- case GoalStatus::PREEMPTED: return TerminalState::PREEMPTED;
- case GoalStatus::SUCCEEDED: return TerminalState::SUCCEEDED;
- case GoalStatus::ABORTED: return TerminalState::ABORTED;
- case GoalStatus::REJECTED: return TerminalState::REJECTED;
- case GoalStatus::RECALLED: return TerminalState::RECALLED;
- case GoalStatus::LOST: return TerminalState::LOST;
+ case actionlib_msgs::GoalStatus::PREEMPTED: return TerminalState::PREEMPTED;
+ case actionlib_msgs::GoalStatus::SUCCEEDED: return TerminalState::SUCCEEDED;
+ case actionlib_msgs::GoalStatus::ABORTED: return TerminalState::ABORTED;
+ case actionlib_msgs::GoalStatus::REJECTED: return TerminalState::REJECTED;
+ case actionlib_msgs::GoalStatus::RECALLED: return TerminalState::RECALLED;
+ case actionlib_msgs::GoalStatus::LOST: return TerminalState::LOST;
default:
ROS_ERROR("Unknown goal status: %u", goal_status.status); break;
}
@@ -154,7 +154,7 @@
ActionGoalConstPtr action_goal = list_handle_.getElem()->getActionGoal();
- GoalID cancel_msg;
+ actionlib_msgs::GoalID cancel_msg;
cancel_msg.stamp = ros::Time(0,0);
cancel_msg.id = list_handle_.getElem()->getActionGoal()->goal_id.id;
Modified: pkg/trunk/stacks/common/actionlib/include/actionlib/client/client_helpers.h
===================================================================
--- pkg/trunk/stacks/common/actionlib/include/actionlib/client/client_helpers.h 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/include/actionlib/client/client_helpers.h 2009-08-25 05:41:33 UTC (rev 22820)
@@ -51,9 +51,8 @@
#include "actionlib/client/terminal_state.h"
// msgs
-#include "actionlib/GoalID.h"
-#include "actionlib/GoalStatusArray.h"
-#include "actionlib/RequestType.h"
+#include "actionlib_msgs/GoalID.h"
+#include "actionlib_msgs/GoalStatusArray.h"
namespace actionlib
{
@@ -74,7 +73,7 @@
typedef boost::function<void (GoalHandleT) > TransitionCallback;
typedef boost::function<void (GoalHandleT, const FeedbackConstPtr&) > FeedbackCallback;
typedef boost::function<void (const ActionGoalConstPtr)> SendGoalFunc;
- typedef boost::function<void (const GoalID&)> CancelFunc;
+ typedef boost::function<void (const actionlib_msgs::GoalID&)> CancelFunc;
GoalManager() { }
@@ -85,7 +84,7 @@
TransitionCallback transition_cb = TransitionCallback(),
FeedbackCallback feedback_cb = FeedbackCallback() );
- void updateStatuses(const GoalStatusArrayConstPtr& status_array);
+ void updateStatuses(const actionlib_msgs::GoalStatusArrayConstPtr& status_array);
void updateFeedbacks(const ActionFeedbackConstPtr& action_feedback);
void updateResults(const ActionResultConstPtr& action_result);
@@ -224,11 +223,11 @@
ActionGoalConstPtr getActionGoal() const;
CommState getCommState() const;
- GoalStatus getGoalStatus() const;
+ actionlib_msgs::GoalStatus getGoalStatus() const;
ResultConstPtr getResult() const;
// Transitions caused by messages
- void updateStatus(GoalHandleT& gh, const GoalStatusArrayConstPtr& status_array);
+ void updateStatus(GoalHandleT& gh, const actionlib_msgs::GoalStatusArrayConstPtr& status_array);
void updateFeedback(GoalHandleT& gh, const ActionFeedbackConstPtr& feedback);
void updateResult(GoalHandleT& gh, const ActionResultConstPtr& result);
@@ -242,7 +241,7 @@
// State
CommState state_;
ActionGoalConstPtr action_goal_;
- GoalStatus latest_goal_status_;
+ actionlib_msgs::GoalStatus latest_goal_status_;
ActionResultConstPtr latest_result_;
// Callbacks
@@ -253,7 +252,7 @@
//! Change the state, as well as print out ROS_DEBUG info
void setCommState(const CommState& state);
void setCommState(const CommState::StateEnum& state);
- const GoalStatus* findGoalStatus(const std::vector<GoalStatus>& status_vec) const;
+ const actionlib_msgs::GoalStatus* findGoalStatus(const std::vector<actionlib_msgs::GoalStatus>& status_vec) const;
};
}
Modified: pkg/trunk/stacks/common/actionlib/include/actionlib/client/comm_state_machine_imp.h
===================================================================
--- pkg/trunk/stacks/common/actionlib/include/actionlib/client/comm_state_machine_imp.h 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/include/actionlib/client/comm_state_machine_imp.h 2009-08-25 05:41:33 UTC (rev 22820)
@@ -64,7 +64,7 @@
}
template <class ActionSpec>
-GoalStatus CommStateMachine<ActionSpec>::getGoalStatus() const
+actionlib_msgs::GoalStatus CommStateMachine<ActionSpec>::getGoalStatus() const
{
return latest_goal_status_;
}
@@ -96,7 +96,7 @@
}
template <class ActionSpec>
-const GoalStatus* CommStateMachine<ActionSpec>::findGoalStatus(const std::vector<GoalStatus>& status_vec) const
+const actionlib_msgs::GoalStatus* CommStateMachine<ActionSpec>::findGoalStatus(const std::vector<actionlib_msgs::GoalStatus>& status_vec) const
{
for (unsigned int i=0; i<status_vec.size(); i++)
if (status_vec[i].goal_id.id == action_goal_->goal_id.id)
@@ -146,9 +146,9 @@
}
template <class ActionSpec>
-void CommStateMachine<ActionSpec>::updateStatus(GoalHandleT& gh, const GoalStatusArrayConstPtr& status_array)
+void CommStateMachine<ActionSpec>::updateStatus(GoalHandleT& gh, const actionlib_msgs::GoalStatusArrayConstPtr& status_array)
{
- const GoalStatus* goal_status = findGoalStatus(status_array->status_list);
+ const actionlib_msgs::GoalStatus* goal_status = findGoalStatus(status_array->status_list);
if (goal_status)
latest_goal_status_ = *goal_status;
@@ -171,19 +171,19 @@
{
switch (goal_status->status)
{
- case GoalStatus::PENDING:
+ case actionlib_msgs::GoalStatus::PENDING:
transitionToState(gh, CommState::PENDING); break;
- case GoalStatus::ACTIVE:
+ case actionlib_msgs::GoalStatus::ACTIVE:
transitionToState(gh, CommState::ACTIVE); break;
- case GoalStatus::PREEMPTED:
- case GoalStatus::SUCCEEDED:
- case GoalStatus::ABORTED:
- case GoalStatus::REJECTED:
- case GoalStatus::RECALLED:
+ case actionlib_msgs::GoalStatus::PREEMPTED:
+ case actionlib_msgs::GoalStatus::SUCCEEDED:
+ case actionlib_msgs::GoalStatus::ABORTED:
+ case actionlib_msgs::GoalStatus::REJECTED:
+ case actionlib_msgs::GoalStatus::RECALLED:
transitionToState(gh, CommState::WAITING_FOR_RESULT); break;
- case GoalStatus::PREEMPTING:
+ case actionlib_msgs::GoalStatus::PREEMPTING:
transitionToState(gh, CommState::PREEMPTING);
- case GoalStatus::RECALLING:
+ case actionlib_msgs::GoalStatus::RECALLING:
transitionToState(gh, CommState::RECALLING);
default:
ROS_ERROR("BUG: Got an unknown status from the ActionServer. status = %u", goal_status->status);
@@ -196,22 +196,22 @@
{
switch (goal_status->status)
{
- case GoalStatus::PENDING:
+ case actionlib_msgs::GoalStatus::PENDING:
break;
- case GoalStatus::ACTIVE:
+ case actionlib_msgs::GoalStatus::ACTIVE:
transitionToState(gh, CommState::ACTIVE);
break;
- case GoalStatus::PREEMPTED:
- case GoalStatus::SUCCEEDED:
- case GoalStatus::ABORTED:
- case GoalStatus::REJECTED:
- case GoalStatus::RECALLED:
+ case actionlib_msgs::GoalStatus::PREEMPTED:
+ case actionlib_msgs::GoalStatus::SUCCEEDED:
+ case actionlib_msgs::GoalStatus::ABORTED:
+ case actionlib_msgs::GoalStatus::REJECTED:
+ case actionlib_msgs::GoalStatus::RECALLED:
transitionToState(gh, CommState::WAITING_FOR_RESULT);
break;
- case GoalStatus::PREEMPTING:
+ case actionlib_msgs::GoalStatus::PREEMPTING:
transitionToState(gh, CommState::PREEMPTING);
break;
- case GoalStatus::RECALLING:
+ case actionlib_msgs::GoalStatus::RECALLING:
transitionToState(gh, CommState::RECALLING);
break;
default:
@@ -224,21 +224,21 @@
{
switch (goal_status->status)
{
- case GoalStatus::PENDING:
+ case actionlib_msgs::GoalStatus::PENDING:
ROS_ERROR("Invalid transition from ACTIVE to PENDING"); break;
- case GoalStatus::ACTIVE:
+ case actionlib_msgs::GoalStatus::ACTIVE:
break;
- case GoalStatus::REJECTED:
+ case actionlib_msgs::GoalStatus::REJECTED:
ROS_ERROR("Invalid transition from ACTIVE to REJECTED"); break;
- case GoalStatus::RECALLING:
+ case actionlib_msgs::GoalStatus::RECALLING:
ROS_ERROR("Invalid transition from ACTIVE to RECALLING"); break;
- case GoalStatus::RECALLED:
+ case actionlib_msgs::GoalStatus::RECALLED:
ROS_ERROR("Invalid transition from ACTIVE to RECALLED"); break;
- case GoalStatus::PREEMPTED:
- case GoalStatus::SUCCEEDED:
- case GoalStatus::ABORTED:
+ case actionlib_msgs::GoalStatus::PREEMPTED:
+ case actionlib_msgs::GoalStatus::SUCCEEDED:
+ case actionlib_msgs::GoalStatus::ABORTED:
transitionToState(gh, CommState::WAITING_FOR_RESULT); break;
- case GoalStatus::PREEMPTING:
+ case actionlib_msgs::GoalStatus::PREEMPTING:
transitionToState(gh, CommState::PREEMPTING); break;
default:
ROS_ERROR("BUG: Got an unknown goal status from the ActionServer. status = %u", goal_status->status);
@@ -250,18 +250,18 @@
{
switch (goal_status->status)
{
- case GoalStatus::PENDING :
+ case actionlib_msgs::GoalStatus::PENDING :
ROS_ERROR("Invalid Transition from WAITING_FOR_RESUT to PENDING"); break;
- case GoalStatus::PREEMPTING:
+ case actionlib_msgs::GoalStatus::PREEMPTING:
ROS_ERROR("Invalid Transition from WAITING_FOR_RESUT to PREEMPTING"); break;
- case GoalStatus::RECALLING:
+ case actionlib_msgs::GoalStatus::RECALLING:
ROS_ERROR("Invalid Transition from WAITING_FOR_RESUT to RECALLING"); break;
- case GoalStatus::ACTIVE:
- case GoalStatus::PREEMPTED:
- case GoalStatus::SUCCEEDED:
- case GoalStatus::ABORTED:
- case GoalStatus::REJECTED:
- case GoalStatus::RECALLED:
+ case actionlib_msgs::GoalStatus::ACTIVE:
+ case actionlib_msgs::GoalStatus::PREEMPTED:
+ case actionlib_msgs::GoalStatus::SUCCEEDED:
+ case actionlib_msgs::GoalStatus::ABORTED:
+ case actionlib_msgs::GoalStatus::REJECTED:
+ case actionlib_msgs::GoalStatus::RECALLED:
break;
default:
ROS_ERROR("BUG: Got an unknown state from the ActionServer. status = %u", goal_status->status);
@@ -273,19 +273,19 @@
{
switch (goal_status->status)
{
- case GoalStatus::PENDING:
+ case actionlib_msgs::GoalStatus::PENDING:
break;
- case GoalStatus::ACTIVE:
+ case actionlib_msgs::GoalStatus::ACTIVE:
break;
- case GoalStatus::PREEMPTED:
- case GoalStatus::RECALLED:
- case GoalStatus::SUCCEEDED:
- case GoalStatus::ABORTED:
- case GoalStatus::REJECTED:
+ case actionlib_msgs::GoalStatus::PREEMPTED:
+ case actionlib_msgs::GoalStatus::RECALLED:
+ case actionlib_msgs::GoalStatus::SUCCEEDED:
+ case actionlib_msgs::GoalStatus::ABORTED:
+ case actionlib_msgs::GoalStatus::REJECTED:
transitionToState(gh, CommState::WAITING_FOR_RESULT); break;
- case GoalStatus::PREEMPTING:
+ case actionlib_msgs::GoalStatus::PREEMPTING:
transitionToState(gh, CommState::PREEMPTING); break;
- case GoalStatus::RECALLING:
+ case actionlib_msgs::GoalStatus::RECALLING:
transitionToState(gh, CommState::RECALLING); break;
default:
ROS_ERROR("BUG: Got an unknown state from the ActionServer. status = %u", goal_status->status);
@@ -297,19 +297,19 @@
{
switch (goal_status->status)
{
- case GoalStatus::PENDING:
+ case actionlib_msgs::GoalStatus::PENDING:
ROS_ERROR("Invalid Transition from RECALLING to PENDING"); break;
- case GoalStatus::ACTIVE:
+ case actionlib_msgs::GoalStatus::ACTIVE:
ROS_ERROR("Invalid Transition from RECALLING to ACTIVE"); break;
- case GoalStatus::PREEMPTED:
- case GoalStatus::RECALLED:
- case GoalStatus::SUCCEEDED:
- case GoalStatus::ABORTED:
- case GoalStatus::REJECTED:
+ case actionlib_msgs::GoalStatus::PREEMPTED:
+ case actionlib_msgs::GoalStatus::RECALLED:
+ case actionlib_msgs::GoalStatus::SUCCEEDED:
+ case actionlib_msgs::GoalStatus::ABORTED:
+ case actionlib_msgs::GoalStatus::REJECTED:
transitionToState(gh, CommState::WAITING_FOR_RESULT); break;
- case GoalStatus::PREEMPTING:
+ case actionlib_msgs::GoalStatus::PREEMPTING:
transitionToState(gh, CommState::PREEMPTING); break;
- case GoalStatus::RECALLING:
+ case actionlib_msgs::GoalStatus::RECALLING:
break;
default:
ROS_ERROR("BUG: Got an unknown state from the ActionServer. status = %u", goal_status->status);
@@ -321,22 +321,22 @@
{
switch (goal_status->status)
{
- case GoalStatus::PENDING:
+ case actionlib_msgs::GoalStatus::PENDING:
ROS_ERROR("Invalid Transition from PREEMPTING to PENDING"); break;
- case GoalStatus::ACTIVE:
+ case actionlib_msgs::GoalStatus::ACTIVE:
ROS_ERROR("Invalid Transition from PREEMPTING to ACTIVE"); break;
- case GoalStatus::REJECTED:
+ case actionlib_msgs::GoalStatus::REJECTED:
ROS_ERROR("Invalid Transition from PREEMPTING to REJECTED"); break;
- case GoalStatus::RECALLING:
+ case actionlib_msgs::GoalStatus::RECALLING:
ROS_ERROR("Invalid Transition from PREEMPTING to RECALLING"); break;
- case GoalStatus::RECALLED:
+ case actionlib_msgs::GoalStatus::RECALLED:
ROS_ERROR("Invalid Transition from PREEMPTING to RECALLED"); break;
break;
- case GoalStatus::PREEMPTED:
- case GoalStatus::SUCCEEDED:
- case GoalStatus::ABORTED:
+ case actionlib_msgs::GoalStatus::PREEMPTED:
+ case actionlib_msgs::GoalStatus::SUCCEEDED:
+ case actionlib_msgs::GoalStatus::ABORTED:
transitionToState(gh, CommState::WAITING_FOR_RESULT); break;
- case GoalStatus::PREEMPTING:
+ case actionlib_msgs::GoalStatus::PREEMPTING:
break;
default:
ROS_ERROR("BUG: Got an unknown state from the ActionServer. status = %u", goal_status->status);
@@ -348,19 +348,19 @@
{
switch (goal_status->status)
{
- case GoalStatus::PENDING:
+ case actionlib_msgs::GoalStatus::PENDING:
ROS_ERROR("Invalid Transition from DONE to PENDING"); break;
- case GoalStatus::ACTIVE:
+ case actionlib_msgs::GoalStatus::ACTIVE:
ROS_ERROR("Invalid Transition from DONE to ACTIVE"); break;
- case GoalStatus::RECALLING:
+ case actionlib_msgs::GoalStatus::RECALLING:
ROS_ERROR("Invalid Transition from DONE to RECALLING"); break;
- case GoalStatus::PREEMPTING:
+ case actionlib_msgs::GoalStatus::PREEMPTING:
ROS_ERROR("Invalid Transition from DONE to PREEMPTING"); break;
- case GoalStatus::PREEMPTED:
- case GoalStatus::SUCCEEDED:
- case GoalStatus::ABORTED:
- case GoalStatus::RECALLED:
- case GoalStatus::REJECTED:
+ case actionlib_msgs::GoalStatus::PREEMPTED:
+ case actionlib_msgs::GoalStatus::SUCCEEDED:
+ case actionlib_msgs::GoalStatus::ABORTED:
+ case actionlib_msgs::GoalStatus::RECALLED:
+ case actionlib_msgs::GoalStatus::REJECTED:
break;
default:
ROS_ERROR("BUG: Got an unknown state from the ActionServer. status = %u", goal_status->status);
@@ -379,7 +379,7 @@
void CommStateMachine<ActionSpec>::processLost(GoalHandleT& gh)
{
ROS_DEBUG("Processing LOST");
- latest_goal_status_.status = GoalStatus::LOST;
+ latest_goal_status_.status = actionlib_msgs::GoalStatus::LOST;
transitionToState(gh, CommState::DONE);
}
Modified: pkg/trunk/stacks/common/actionlib/include/actionlib/client/goal_manager_imp.h
===================================================================
--- pkg/trunk/stacks/common/actionlib/include/actionlib/client/goal_manager_imp.h 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/include/actionlib/client/goal_manager_imp.h 2009-08-25 05:41:33 UTC (rev 22820)
@@ -85,7 +85,7 @@
}
template<class ActionSpec>
-void GoalManager<ActionSpec>::updateStatuses(const GoalStatusArrayConstPtr& status_array)
+void GoalManager<ActionSpec>::updateStatuses(const actionlib_msgs::GoalStatusArrayConstPtr& status_array)
{
boost::recursive_mutex::scoped_lock lock(list_mutex_);
typename ManagedListT::iterator it = list_.begin();
Modified: pkg/trunk/stacks/common/actionlib/include/actionlib/goal_id_generator.h
===================================================================
--- pkg/trunk/stacks/common/actionlib/include/actionlib/goal_id_generator.h 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/include/actionlib/goal_id_generator.h 2009-08-25 05:41:33 UTC (rev 22820)
@@ -35,9 +35,10 @@
#ifndef ACTION_LIB_GOAL_ID_GENERATOR_H_
#define ACTION_LIB_GOAL_ID_GENERATOR_H_
+#include <sstream>
#include <string>
#include "ros/time.h"
-#include "actionlib/GoalID.h"
+#include "actionlib_msgs/GoalID.h"
namespace actionlib
{
@@ -57,15 +58,17 @@
* \brief Generates a unique ID
* \return A unique GoalID for this action
*/
- GoalID generateID()
+ actionlib_msgs::GoalID generateID()
{
- GoalID id;
- id.id = ros::Time::now();
- id.stamp = id.id;
+ actionlib_msgs::GoalID id;
+ ros::Time cur_time = ros::Time::now();
+ std::stringstream ss;
+ ss << cur_time.sec << "." << cur_time.nsec;
+ id.id = ss.str();
+ id.stamp = cur_time;
return id;
}
-
private:
std::string name_ ;
Modified: pkg/trunk/stacks/common/actionlib/include/actionlib/server/action_server.h
===================================================================
--- pkg/trunk/stacks/common/actionlib/include/actionlib/server/action_server.h 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/include/actionlib/server/action_server.h 2009-08-25 05:41:33 UTC (rev 22820)
@@ -40,11 +40,11 @@
#include <ros/ros.h>
#include <boost/thread.hpp>
#include <boost/shared_ptr.hpp>
-#include <actionlib/GoalID.h>
-#include <actionlib/GoalStatusArray.h>
-#include <actionlib/GoalStatus.h>
-#include <actionlib/RequestType.h>
+#include <actionlib_msgs/GoalID.h>
+#include <actionlib_msgs/GoalStatusArray.h>
+#include <actionlib_msgs/GoalStatus.h>
#include <actionlib/enclosure_deleter.h>
+#include <actionlib/goal_id_generator.h>
#include <actionlib/action_definition.h>
#include <actionlib/server/status_tracker.h>
#include <actionlib/server/handle_tracker_deleter.h>
@@ -103,19 +103,19 @@
* @param status The status of the goal with which the result is associated
* @param result The result to publish
*/
- void publishResult(const GoalStatus& status, const Result& result);
+ void publishResult(const actionlib_msgs::GoalStatus& status, const Result& result);
/**
* @brief Publishes feedback for a given goal
* @param status The status of the goal with which the feedback is associated
* @param feedback The feedback to publish
*/
- void publishFeedback(const GoalStatus& status, const Feedback& feedback);
+ void publishFeedback(const actionlib_msgs::GoalStatus& status, const Feedback& feedback);
/**
* @brief The ROS callback for cancel requests coming into the ActionServer
*/
- void cancelCallback(const boost::shared_ptr<const GoalID>& goal_id);
+ void cancelCallback(const boost::shared_ptr<const actionlib_msgs::GoalID>& goal_id);
/**
* @brief The ROS callback for goals coming into the ActionServer
@@ -153,6 +153,7 @@
friend class ServerGoalHandle<ActionSpec>;
friend class HandleTrackerDeleter<ActionSpec>;
+ GoalIDGenerator id_generator_;
};
};
Modified: pkg/trunk/stacks/common/actionlib/include/actionlib/server/action_server_imp.h
===================================================================
--- pkg/trunk/stacks/common/actionlib/include/actionlib/server/action_server_imp.h 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/include/actionlib/server/action_server_imp.h 2009-08-25 05:41:33 UTC (rev 22820)
@@ -42,14 +42,14 @@
boost::function<void (GoalHandle)> goal_cb,
boost::function<void (GoalHandle)> cancel_cb)
: node_(n, name), goal_callback_(goal_cb), cancel_callback_(cancel_cb) {
- status_pub_ = node_.advertise<actionlib::GoalStatusArray>("status", 1);
+ status_pub_ = node_.advertise<actionlib_msgs::GoalStatusArray>("status", 1);
result_pub_ = node_.advertise<ActionResult>("result", 1);
feedback_pub_ = node_.advertise<ActionFeedback>("feedback", 1);
goal_sub_ = node_.subscribe<ActionGoal>("goal", 1,
boost::bind(&ActionServer::goalCallback, this, _1));
- cancel_sub_ = node_.subscribe<GoalID>("cancel", 1,
+ cancel_sub_ = node_.subscribe<actionlib_msgs::GoalID>("cancel", 1,
boost::bind(&ActionServer::cancelCallback, this, _1));
//read the frequency with which to publish status from the parameter server
@@ -75,7 +75,7 @@
}
template <class ActionSpec>
- void ActionServer<ActionSpec>::publishResult(const GoalStatus& status, const Result& result){
+ void ActionServer<ActionSpec>::publishResult(const actionlib_msgs::GoalStatus& status, const Result& result){
boost::recursive_mutex::scoped_lock lock(lock_);
//we'll create a shared_ptr to pass to ROS to limit copying
boost::shared_ptr<ActionResult> ar(new ActionResult);
@@ -85,7 +85,7 @@
}
template <class ActionSpec>
- void ActionServer<ActionSpec>::publishFeedback(const GoalStatus& status, const Feedback& feedback){
+ void ActionServer<ActionSpec>::publishFeedback(const actionlib_msgs::GoalStatus& status, const Feedback& feedback){
boost::recursive_mutex::scoped_lock lock(lock_);
//we'll create a shared_ptr to pass to ROS to limit copying
boost::shared_ptr<ActionFeedback> af(new ActionFeedback);
@@ -95,7 +95,7 @@
}
template <class ActionSpec>
- void ActionServer<ActionSpec>::cancelCallback(const boost::shared_ptr<const GoalID>& goal_id){
+ void ActionServer<ActionSpec>::cancelCallback(const boost::shared_ptr<const actionlib_msgs::GoalID>& goal_id){
boost::recursive_mutex::scoped_lock lock(lock_);
//we need to handle a cancel for the user
ROS_DEBUG("The action server has received a new cancel request");
@@ -104,7 +104,7 @@
//check if the goal id is zero or if it is equal to the goal id of
//the iterator or if the time of the iterator warrants a cancel
if(
- (goal_id->id == ros::Time() && goal_id->stamp == ros::Time()) //id and stamp 0 --> cancel everything
+ (goal_id->id == "" && goal_id->stamp == ros::Time()) //id and stamp 0 --> cancel everything
|| goal_id->id == (*it).status_.goal_id.id //ids match... cancel that goal
|| (goal_id->stamp != ros::Time() && (*it).status_.goal_id.stamp <= goal_id->stamp) //stamp != 0 --> cancel everything before stamp
){
@@ -137,9 +137,9 @@
}
//if the requested goal_id was not found, and it is non-zero, then we need to store the cancel request
- if(goal_id->id != ros::Time() && !goal_id_found){
+ if(goal_id->id != "" && !goal_id_found){
typename std::list<StatusTracker<ActionSpec> >::iterator it = status_list_.insert(status_list_.end(),
- StatusTracker<ActionSpec> (*goal_id, GoalStatus::RECALLING));
+ StatusTracker<ActionSpec> (*goal_id, actionlib_msgs::GoalStatus::RECALLING));
//start the timer for how long the status will live in the list without a goal handle to it
(*it).handle_destruction_time_ = ros::Time::now();
}
@@ -200,7 +200,7 @@
void ActionServer<ActionSpec>::publishStatus(){
boost::recursive_mutex::scoped_lock lock(lock_);
//build a status array
- GoalStatusArray status_array;
+ actionlib_msgs::GoalStatusArray status_array;
status_array.set_status_list_size(status_list_.size());
Modified: pkg/trunk/stacks/common/actionlib/include/actionlib/server/server_goal_handle.h
===================================================================
--- pkg/trunk/stacks/common/actionlib/include/actionlib/server/server_goal_handle.h 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/include/actionlib/server/server_goal_handle.h 2009-08-25 05:41:33 UTC (rev 22820)
@@ -34,11 +34,11 @@
*
* Author: Eitan Marder-Eppstein
*********************************************************************/
-#ifndef ACTIONLIB_SERVER_GOAL_HANDLE_H_
-#define ACTIONLIB_SERVER_GOAL_HANDLE_H_
+#ifndef ACTIONLIB_SERVER_GOAL_HANDLE_H_
+#define ACTIONLIB_SERVER_GOAL_HANDLE_H_
-#include <actionlib/GoalID.h>
-#include <actionlib/GoalStatus.h>
+#include <actionlib_msgs/GoalID.h>
+#include <actionlib_msgs/GoalStatus.h>
#include <actionlib/action_definition.h>
#include <actionlib/server/status_tracker.h>
#include <boost/shared_ptr.hpp>
@@ -113,13 +113,13 @@
* @brief Accessor for the goal id associated with the ServerGoalHandle
* @return The goal id
*/
- GoalID getGoalID() const;
+ actionlib_msgs::GoalID getGoalID() const;
/**
* @brief Accessor for the status associated with the ServerGoalHandle
* @return The goal status
*/
- GoalStatus getGoalStatus() const;
+ actionlib_msgs::GoalStatus getGoalStatus() const;
/**
* @brief Equals operator for ServerGoalHandles
Modified: pkg/trunk/stacks/common/actionlib/include/actionlib/server/server_goal_handle_imp.h
===================================================================
--- pkg/trunk/stacks/common/actionlib/include/actionlib/server/server_goal_handle_imp.h 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/include/actionlib/server/server_goal_handle_imp.h 2009-08-25 05:41:33 UTC (rev 22820)
@@ -42,18 +42,18 @@
template <class ActionSpec>
void ServerGoalHandle<ActionSpec>::setAccepted(){
- ROS_DEBUG("Accepting goal, id: %.2f, stamp: %.2f", getGoalID().id.toSec(), getGoalID().stamp.toSec());
+ ROS_DEBUG("Accepting goal, id: %s, stamp: %.2f", getGoalID().id.c_str(), getGoalID().stamp.toSec());
if(goal_){
unsigned int status = (*status_it_).status_.status;
//if we were pending before, then we'll go active
- if(status == GoalStatus::PENDING){
- (*status_it_).status_.status = GoalStatus::ACTIVE;
+ if(status == actionlib_msgs::GoalStatus::PENDING){
+ (*status_it_).status_.status = actionlib_msgs::GoalStatus::ACTIVE;
as_->publishStatus();
}
//if we were recalling before, now we'll go to preempting
- else if(status == GoalStatus::RECALLING){
- (*status_it_).status_.status = GoalStatus::PREEMPTING;
+ else if(status == actionlib_msgs::GoalStatus::RECALLING){
+ (*status_it_).status_.status = actionlib_msgs::GoalStatus::PREEMPTING;
as_->publishStatus();
}
else
@@ -66,15 +66,15 @@
template <class ActionSpec>
void ServerGoalHandle<ActionSpec>::setCanceled(const Result& result){
- ROS_DEBUG("Setting status to canceled on goal, id: %.2f, stamp: %.2f", getGoalID().id.toSec(), getGoalID().stamp.toSec());
+ ROS_DEBUG("Setting status to canceled on goal, id: %s, stamp: %.2f", getGoalID().id.c_str(), getGoalID().stamp.toSec());
if(goal_){
unsigned int status = (*status_it_).status_.status;
- if(status == GoalStatus::PENDING || status == GoalStatus::RECALLING){
- (*status_it_).status_.status = GoalStatus::RECALLED;
+ if(status == actionlib_msgs::GoalStatus::PENDING || status == actionlib_msgs::GoalStatus::RECALLING){
+ (*status_it_).status_.status = actionlib_msgs::GoalStatus::RECALLED;
as_->publishResult((*status_it_).status_, result);
}
- else if(status == GoalStatus::ACTIVE || status == GoalStatus::PREEMPTING){
- (*status_it_).status_.status = GoalStatus::PREEMPTED;
+ else if(status == actionlib_msgs::GoalStatus::ACTIVE || status == actionlib_msgs::GoalStatus::PREEMPTING){
+ (*status_it_).status_.status = actionlib_msgs::GoalStatus::PREEMPTED;
as_->publishResult((*status_it_).status_, result);
}
else
@@ -87,11 +87,11 @@
template <class ActionSpec>
void ServerGoalHandle<ActionSpec>::setRejected(const Result& result){
- ROS_DEBUG("Setting status to rejected on goal, id: %.2f, stamp: %.2f", getGoalID().id.toSec(), getGoalID().stamp.toSec());
+ ROS_DEBUG("Setting status to rejected on goal, id: %s, stamp: %.2f", getGoalID().id.c_str(), getGoalID().stamp.toSec());
if(goal_){
unsigned int status = (*status_it_).status_.status;
- if(status == GoalStatus::PENDING || status == GoalStatus::RECALLING){
- (*status_it_).status_.status = GoalStatus::REJECTED;
+ if(status == actionlib_msgs::GoalStatus::PENDING || status == actionlib_msgs::GoalStatus::RECALLING){
+ (*status_it_).status_.status = actionlib_msgs::GoalStatus::REJECTED;
as_->publishResult((*status_it_).status_, result);
}
else
@@ -104,11 +104,11 @@
template <class ActionSpec>
void ServerGoalHandle<ActionSpec>::setAborted(const Result& result){
- ROS_DEBUG("Setting status to aborted on goal, id: %.2f, stamp: %.2f", getGoalID().id.toSec(), getGoalID().stamp.toSec());
+ ROS_DEBUG("Setting status to aborted on goal, id: %s, stamp: %.2f", getGoalID().id.c_str(), getGoalID().stamp.toSec());
if(goal_){
unsigned int status = (*status_it_).status_.status;
- if(status == GoalStatus::PREEMPTING || status == GoalStatus::ACTIVE){
- (*status_it_).status_.status = GoalStatus::ABORTED;
+ if(status == actionlib_msgs::GoalStatus::PREEMPTING || status == actionlib_msgs::GoalStatus::ACTIVE){
+ (*status_it_).status_.status = actionlib_msgs::GoalStatus::ABORTED;
as_->publishResult((*status_it_).status_, result);
}
else
@@ -121,11 +121,11 @@
template <class ActionSpec>
void ServerGoalHandle<ActionSpec>::setSucceeded(const Result& result){
- ROS_DEBUG("Setting status to succeeded on goal, id: %.2f, stamp: %.2f", getGoalID().id.toSec(), getGoalID().stamp.toSec());
+ ROS_DEBUG("Setting status to succeeded on goal, id: %s, stamp: %.2f", getGoalID().id.c_str(), getGoalID().stamp.toSec());
if(goal_){
unsigned int status = (*status_it_).status_.status;
- if(status == GoalStatus::PREEMPTING || status == GoalStatus::ACTIVE){
- (*status_it_).status_.status = GoalStatus::SUCCEEDED;
+ if(status == actionlib_msgs::GoalStatus::PREEMPTING || status == actionlib_msgs::GoalStatus::ACTIVE){
+ (*status_it_).status_.status = actionlib_msgs::GoalStatus::SUCCEEDED;
as_->publishResult((*status_it_).status_, result);
}
else
@@ -138,7 +138,7 @@
template <class ActionSpec>
void ServerGoalHandle<ActionSpec>::publishFeedback(const Feedback& feedback){
- ROS_DEBUG("Publishing feedback for goal, id: %.2f, stamp: %.2f", getGoalID().id.toSec(), getGoalID().stamp.toSec());
+ ROS_DEBUG("Publishing feedback for goal, id: %s, stamp: %.2f", getGoalID().id.c_str(), getGoalID().stamp.toSec());
if(goal_) {
as_->publishFeedback((*status_it_).status_, feedback);
}
@@ -158,22 +158,22 @@
}
template <class ActionSpec>
- GoalID ServerGoalHandle<ActionSpec>::getGoalID() const{
+ actionlib_msgs::GoalID ServerGoalHandle<ActionSpec>::getGoalID() const{
if(goal_)
return (*status_it_).status_.goal_id;
else{
ROS_ERROR("Attempt to get a goal id on an uninitialized ServerGoalHandle");
- return GoalID();
+ return actionlib_msgs::GoalID();
}
}
template <class ActionSpec>
- GoalStatus ServerGoalHandle<ActionSpec>::getGoalStatus() const{
+ actionlib_msgs::GoalStatus ServerGoalHandle<ActionSpec>::getGoalStatus() const{
if(goal_)
return (*status_it_).status_;
else{
ROS_ERROR("Attempt to get goal status on an uninitialized ServerGoalHandle");
- return GoalStatus();
+ return actionlib_msgs::GoalStatus();
}
}
@@ -181,8 +181,8 @@
bool ServerGoalHandle<ActionSpec>::operator==(const ServerGoalHandle& other){
if(!goal_ || !other.goal_)
return false;
- GoalID my_id = getGoalID();
- GoalID their_id = other.getGoalID();
+ actionlib_msgs::GoalID my_id = getGoalID();
+ actionlib_msgs::GoalID their_id = other.getGoalID();
return my_id.id == their_id.id;
}
@@ -190,8 +190,8 @@
bool ServerGoalHandle<ActionSpec>::operator!=(const ServerGoalHandle& other){
if(!goal_ || !other.goal_)
return true;
- GoalID my_id = getGoalID();
- GoalID their_id = other.getGoalID();
+ actionlib_msgs::GoalID my_id = getGoalID();
+ actionlib_msgs::GoalID their_id = other.getGoalID();
return my_id.id != their_id.id;
}
@@ -203,17 +203,17 @@
template <class ActionSpec>
bool ServerGoalHandle<ActionSpec>::setCancelRequested(){
- ROS_DEBUG("Transisitoning to a cancel requested state on goal id: %.2f, stamp: %.2f", getGoalID().id.toSec(), getGoalID().stamp.toSec());
+ ROS_DEBUG("Transisitoning to a cancel requested state on goal id: %s, stamp: %.2f", getGoalID().id.c_str(), getGoalID().stamp.toSec());
if(goal_){
unsigned int status = (*status_it_).status_.status;
- if(status == GoalStatus::PENDING){
- (*status_it_).status_.status = GoalStatus::RECALLING;
+ if(status == actionlib_msgs::GoalStatus::PENDING){
+ (*status_it_).status_.status = actionlib_msgs::GoalStatus::RECALLING;
as_->publishStatus();
return true;
}
- if(status == GoalStatus::ACTIVE){
- (*status_it_).status_.status = GoalStatus::PREEMPTING;
+ if(status == actionlib_msgs::GoalStatus::ACTIVE){
+ (*status_it_).status_.status = actionlib_msgs::GoalStatus::PREEMPTING;
as_->publishStatus();
return true;
}
Modified: pkg/trunk/stacks/common/actionlib/include/actionlib/server/simple_action_server_imp.h
===================================================================
--- pkg/trunk/stacks/common/actionlib/include/actionlib/server/simple_action_server_imp.h 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/include/actionlib/server/simple_action_server_imp.h 2009-08-25 05:41:33 UTC (rev 22820)
@@ -115,7 +115,7 @@
if(!current_goal_.getGoal())
return false;
unsigned int status = current_goal_.getGoalStatus().status;
- return status == GoalStatus::ACTIVE || status == GoalStatus::PREEMPTING;
+ return status == actionlib_msgs::GoalStatus::ACTIVE || status == actionlib_msgs::GoalStatus::PREEMPTING;
}
template <class ActionSpec>
Modified: pkg/trunk/stacks/common/actionlib/include/actionlib/server/status_tracker.h
===================================================================
--- pkg/trunk/stacks/common/actionlib/include/actionlib/server/status_tracker.h 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/include/actionlib/server/status_tracker.h 2009-08-25 05:41:33 UTC (rev 22820)
@@ -37,10 +37,12 @@
#ifndef ACTIONLIB_STATUS_TRACKER_H_
#define ACTIONLIB_STATUS_TRACKER_H_
-#include <actionlib/GoalID.h>
-#include <actionlib/GoalStatus.h>
+#include <actionlib_msgs/GoalID.h>
+#include <actionlib_msgs/GoalStatus.h>
#include <actionlib/action_definition.h>
+#include <actionlib/goal_id_generator.h>
+
namespace actionlib {
/**
@@ -55,14 +57,17 @@
ACTION_DEFINITION(ActionSpec);
public:
- StatusTracker(const GoalID& goal_id, unsigned int status);
+ StatusTracker(const actionlib_msgs::GoalID& goal_id, unsigned int status);
StatusTracker(const boost::shared_ptr<const ActionGoal>& goal);
boost::shared_ptr<const ActionGoal> goal_;
boost::weak_ptr<void> handle_tracker_;
- GoalStatus status_;
+ actionlib_msgs::GoalStatus status_;
ros::Time handle_destruction_time_;
+
+ private:
+ GoalIDGenerator id_generator_;
};
};
Modified: pkg/trunk/stacks/common/actionlib/include/actionlib/server/status_tracker_imp.h
===================================================================
--- pkg/trunk/stacks/common/actionlib/include/actionlib/server/status_tracker_imp.h 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/include/actionlib/server/status_tracker_imp.h 2009-08-25 05:41:33 UTC (rev 22820)
@@ -38,7 +38,7 @@
#define ACTIONLIB_STATUS_TRACKER_IMP_H_
namespace actionlib {
template <class ActionSpec>
- StatusTracker<ActionSpec>::StatusTracker(const GoalID& goal_id, unsigned int status){
+ StatusTracker<ActionSpec>::StatusTracker(const actionlib_msgs::GoalID& goal_id, unsigned int status){
//set the goal id and status appropriately
status_.goal_id = goal_id;
status_.status = status;
@@ -51,11 +51,11 @@
status_.goal_id = goal_->goal_id;
//initialize the status of the goal to pending
- status_.status = GoalStatus::PENDING;
+ status_.status = actionlib_msgs::GoalStatus::PENDING;
//if the goal id is zero, then we need to make up an id for the goal
- if(status_.goal_id.id == ros::Time()){
- status_.goal_id.id = ros::Time::now();
+ if(status_.goal_id.id == ""){
+ status_.goal_id = id_generator_.generateID();
}
//if the timestamp of the goal is zero, then we'll set it to now()
Modified: pkg/trunk/stacks/common/actionlib/manifest.xml
===================================================================
--- pkg/trunk/stacks/common/actionlib/manifest.xml 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/manifest.xml 2009-08-25 05:41:33 UTC (rev 22820)
@@ -9,9 +9,9 @@
<review status="api cleared" notes=""/>
<url>http://ros.org/wiki/actionlib</url>
- <depend package="geometry_msgs" />
<depend package="roscpp" />
-
+ <depend package="actionlib_msgs" />
+
<export>
<cpp cflags="-I${prefix}/msg/cpp -I${prefix}/include" />
</export>
Deleted: pkg/trunk/stacks/common/actionlib/msg/GoalID.msg
===================================================================
--- pkg/trunk/stacks/common/actionlib/msg/GoalID.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/msg/GoalID.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1,2 +0,0 @@
-time stamp
-time id
Deleted: pkg/trunk/stacks/common/actionlib/msg/GoalStatus.msg
===================================================================
--- pkg/trunk/stacks/common/actionlib/msg/GoalStatus.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/msg/GoalStatus.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1,17 +0,0 @@
-GoalID goal_id
-uint8 status
-uint8 PENDING = 0
-uint8 ACTIVE = 1
-uint8 PREEMPTED = 2
-uint8 SUCCEEDED = 3
-uint8 ABORTED = 4
-uint8 REJECTED = 5
-uint8 PREEMPTING = 6
-uint8 RECALLING = 7
-uint8 RECALLED = 8
-
-# An action client can determine that a goal is LOST. This should not be sent over the wire.
-uint8 LOST = 9
-
-#Allow for the user to associate a string with GoalStatus for debugging
-string text
Deleted: pkg/trunk/stacks/common/actionlib/msg/GoalStatusArray.msg
===================================================================
--- pkg/trunk/stacks/common/actionlib/msg/GoalStatusArray.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/msg/GoalStatusArray.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1,2 +0,0 @@
-Header header
-GoalStatus[] status_list
Deleted: pkg/trunk/stacks/common/actionlib/msg/RequestType.msg
===================================================================
--- pkg/trunk/stacks/common/actionlib/msg/RequestType.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib/msg/RequestType.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1,3 +0,0 @@
-uint8 type
-uint8 GOAL_REQUEST = 0
-uint8 PREEMPT_REQUEST = 1
Modified: pkg/trunk/stacks/common/actionlib_tutorials/manifest.xml
===================================================================
--- pkg/trunk/stacks/common/actionlib_tutorials/manifest.xml 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib_tutorials/manifest.xml 2009-08-25 05:41:33 UTC (rev 22820)
@@ -14,6 +14,8 @@
<depend package="std_msgs"/>
<depend package="rosconsole"/>
<depend package="actionlib"/>
+ <depend package="actionlib_msgs"/>
+
<export>
<cpp cflags="-I${prefix}/msg/cpp" />
Modified: pkg/trunk/stacks/common/actionlib_tutorials/msg/AveragingActionFeedback.msg
===================================================================
--- pkg/trunk/stacks/common/actionlib_tutorials/msg/AveragingActionFeedback.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib_tutorials/msg/AveragingActionFeedback.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1,4 +1,4 @@
Header header
-actionlib/GoalStatus status
+actionlib_msgs/GoalStatus status
AveragingFeedback feedback
Modified: pkg/trunk/stacks/common/actionlib_tutorials/msg/AveragingActionGoal.msg
===================================================================
--- pkg/trunk/stacks/common/actionlib_tutorials/msg/AveragingActionGoal.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib_tutorials/msg/AveragingActionGoal.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1,4 +1,4 @@
Header header
-actionlib/GoalID goal_id
+actionlib_msgs/GoalID goal_id
AveragingGoal goal
Modified: pkg/trunk/stacks/common/actionlib_tutorials/msg/AveragingActionResult.msg
===================================================================
--- pkg/trunk/stacks/common/actionlib_tutorials/msg/AveragingActionResult.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib_tutorials/msg/AveragingActionResult.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1,4 +1,4 @@
Header header
-actionlib/GoalStatus status
+actionlib_msgs/GoalStatus status
AveragingResult result
Modified: pkg/trunk/stacks/common/actionlib_tutorials/msg/FibonacciActionFeedback.msg
===================================================================
--- pkg/trunk/stacks/common/actionlib_tutorials/msg/FibonacciActionFeedback.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib_tutorials/msg/FibonacciActionFeedback.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1,4 +1,4 @@
Header header
-actionlib/GoalStatus status
+actionlib_msgs/GoalStatus status
FibonacciFeedback feedback
Modified: pkg/trunk/stacks/common/actionlib_tutorials/msg/FibonacciActionGoal.msg
===================================================================
--- pkg/trunk/stacks/common/actionlib_tutorials/msg/FibonacciActionGoal.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib_tutorials/msg/FibonacciActionGoal.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1,4 +1,4 @@
Header header
-actionlib/GoalID goal_id
+actionlib_msgs/GoalID goal_id
FibonacciGoal goal
Modified: pkg/trunk/stacks/common/actionlib_tutorials/msg/FibonacciActionResult.msg
===================================================================
--- pkg/trunk/stacks/common/actionlib_tutorials/msg/FibonacciActionResult.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/common/actionlib_tutorials/msg/FibonacciActionResult.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1,4 +1,4 @@
Header header
-actionlib/GoalStatus status
+actionlib_msgs/GoalStatus status
FibonacciResult result
Copied: pkg/trunk/stacks/common_msgs/actionlib_msgs/msg/GoalID.msg (from rev 22818, pkg/trunk/stacks/common/actionlib/msg/GoalID.msg)
===================================================================
--- pkg/trunk/stacks/common_msgs/actionlib_msgs/msg/GoalID.msg (rev 0)
+++ pkg/trunk/stacks/common_msgs/actionlib_msgs/msg/GoalID.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -0,0 +1,2 @@
+time stamp
+string id
Copied: pkg/trunk/stacks/common_msgs/actionlib_msgs/msg/GoalStatus.msg (from rev 22818, pkg/trunk/stacks/common/actionlib/msg/GoalStatus.msg)
===================================================================
--- pkg/trunk/stacks/common_msgs/actionlib_msgs/msg/GoalStatus.msg (rev 0)
+++ pkg/trunk/stacks/common_msgs/actionlib_msgs/msg/GoalStatus.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -0,0 +1,17 @@
+GoalID goal_id
+uint8 status
+uint8 PENDING = 0
+uint8 ACTIVE = 1
+uint8 PREEMPTED = 2
+uint8 SUCCEEDED = 3
+uint8 ABORTED = 4
+uint8 REJECTED = 5
+uint8 PREEMPTING = 6
+uint8 RECALLING = 7
+uint8 RECALLED = 8
+
+# An action client can determine that a goal is LOST. This should not be sent over the wire.
+uint8 LOST = 9
+
+#Allow for the user to associate a string with GoalStatus for debugging
+string text
Copied: pkg/trunk/stacks/common_msgs/actionlib_msgs/msg/GoalStatusArray.msg (from rev 22818, pkg/trunk/stacks/common/actionlib/msg/GoalStatusArray.msg)
===================================================================
--- pkg/trunk/stacks/common_msgs/actionlib_msgs/msg/GoalStatusArray.msg (rev 0)
+++ pkg/trunk/stacks/common_msgs/actionlib_msgs/msg/GoalStatusArray.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -0,0 +1,2 @@
+Header header
+GoalStatus[] status_list
Modified: pkg/trunk/stacks/mechanism/mechanism_msgs/manifest.xml
===================================================================
--- pkg/trunk/stacks/mechanism/mechanism_msgs/manifest.xml 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/mechanism/mechanism_msgs/manifest.xml 2009-08-25 05:41:33 UTC (rev 22820)
@@ -7,7 +7,7 @@
<review status="unreviewed" notes=""/>
<url>http://pr.willowgarage.com/</url>
<depend package="std_msgs" />
- <depend package="actionlib" />
+ <depend package="actionlib_msgs" />
<export>
<cpp cflags="-I${prefix}/msg/cpp -I${prefix}/srv/cpp" />
</export>
Modified: pkg/trunk/stacks/mechanism/mechanism_msgs/msg/SwitchControllerActionFeedback.msg
===================================================================
--- pkg/trunk/stacks/mechanism/mechanism_msgs/msg/SwitchControllerActionFeedback.msg 2009-08-25 05:40:49 UTC (rev 22819)
+++ pkg/trunk/stacks/mechanism/mechanism_msgs/msg/SwitchControllerActionFeedback.msg 2009-08-25 05:41:33 UTC (rev 22820)
@@ -1,4 +1,4 @@
Header header
-actionlib/GoalStatus status
+actionlib_msgs/GoalStatus status
SwitchControllerFeedback feedback
Modified: pkg/trunk/stacks/mechanism/mechanism_msgs/msg/SwitchControllerActionGoal.msg
===================================================================
--- pkg/trunk/stacks/mechanism/mechanism_msgs/msg/SwitchControllerActionGoal.msg 2009-08-25 05:40:49 UTC (rev 228...
[truncated message content] |