1 #ifndef RTT_SIMPLE_ACTION_SERVER_HPP 2 #define RTT_SIMPLE_ACTION_SERVER_HPP 5 #include <boost/bind.hpp> 6 #include <boost/function.hpp> 46 if (!owner_service)
throw std::invalid_argument(
"RTTSimpleActionServer: owner pointer must be valid.");
47 action_server.
addPorts(owner_service);
56 return action_server.
ready();
76 return goal_active.
isValid() && goal_active.
getGoalStatus().status == actionlib_msgs::GoalStatus::ACTIVE;
83 return goal_active.
isValid() && goal_active.
getGoalStatus().status == actionlib_msgs::GoalStatus::PREEMPTING;
90 return goal_pending.
isValid() && goal_pending.
getGoalStatus().status == actionlib_msgs::GoalStatus::PENDING;
117 bool acceptPending(
const Result& result,
const std::string& msg =
"");
125 bool rejectPending(
const Result& result,
const std::string& msg =
"");
141 bool abortActive(
const Result& result,
const std::string& msg =
"");
149 bool cancelActive(
const Result& result,
const std::string& msg =
"");
157 bool succeedActive(
const Result& result,
const std::string& msg =
"");
163 void setGoalHook(boost::function<
void(
const Goal&)> _newGoalHook) {
164 newGoalHook = _newGoalHook;
172 cancelGoalHook = _cancelGoalHook;
179 action_server.
start();
190 case actionlib_msgs::GoalStatus::ACTIVE:
191 case actionlib_msgs::GoalStatus::PREEMPTING:
208 if (!goal_pending.
isValid())
return false;
210 case actionlib_msgs::GoalStatus::PENDING:
211 case actionlib_msgs::GoalStatus::RECALLING:
227 if (!goal_active.
isValid())
return false;
229 case actionlib_msgs::GoalStatus::ACTIVE:
230 case actionlib_msgs::GoalStatus::PREEMPTING:
239 if (!goal_active.
isValid())
return false;
241 case actionlib_msgs::GoalStatus::ACTIVE:
242 case actionlib_msgs::GoalStatus::PREEMPTING:
251 if (!goal_active.
isValid())
return false;
253 case actionlib_msgs::GoalStatus::ACTIVE:
254 case actionlib_msgs::GoalStatus::PREEMPTING:
265 case actionlib_msgs::GoalStatus::PENDING:
266 case actionlib_msgs::GoalStatus::RECALLING:
267 goal_pending.
setRejected(Result(),
"Pending goal is replaced by new received goal.");
280 case actionlib_msgs::GoalStatus::ACTIVE:
281 case actionlib_msgs::GoalStatus::PREEMPTING:
282 case actionlib_msgs::GoalStatus::PENDING:
283 case actionlib_msgs::GoalStatus::RECALLING:
284 if (goal_active == gh) {
288 else if (goal_pending == gh) {
289 gh.
setCanceled(Result(),
"Pending goal is canceled by client request.");
void publishFeedback(const Feedback &feedback)
Orocos RTT-Based Action Server.
bool addPorts(RTT::Service::shared_ptr service, const bool create_topics=false, const std::string &topic_namespace="")
Add actionlib ports to a given rtt service.
void setGoalHook(boost::function< void(const Goal &)> _newGoalHook)
Setup goal hook.
actionlib::ServerGoalHandle< ActionSpec > GoalHandle
bool succeedActive(const Result &result, const std::string &msg="")
Succeed active goal. Succeed active goal with given result, do nothing if there is no active goal...
void setRejected(const Result &result=Result(), const std::string &text=std::string(""))
boost::shared_ptr< const Goal > getGoal() const
bool publishFeedback(const Feedback &feedpack)
Publish feedback on active goal. Publish feedback on active goal, do nothing if there is no active go...
void setCancelHook(boost::function< void()> _cancelGoalHook)
Setup cancel hook.
boost::shared_ptr< const Goal > getActiveGoal() const
void setCanceled(const Result &result=Result(), const std::string &text=std::string(""))
void setAccepted(const std::string &text=std::string(""))
void registerGoalCallback(boost::function< void(GoalHandle)> cb)
RTTSimpleActionServer(boost::shared_ptr< RTT::Service > owner_service)
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
void shutdown()
Shutdown internal timer.
bool ready()
Check if the server is ready to be started.
bool isPreempting() const
void registerCancelCallback(boost::function< void(GoalHandle)> cb)
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
boost::function< void(const Goal &)> newGoalHook
boost::function< void()> cancelGoalHook
RTTActionServer< ActionSpec > action_server
void goalCallback(GoalHandle gh)
boost::shared_ptr< const Goal > getPendingGoal() const
bool rejectPending(const Result &result, const std::string &msg="")
Reject pending goal. Reject pending goal with result, do nothing if there is no pending goal...
bool cancelActive(const Result &result, const std::string &msg="")
Cancel active goal. Cancel active goal with given result, do nothing if there is no active goal...
bool acceptPending(const Result &result, const std::string &msg="")
Accept pending goal. Accept pending goal, preempt the active goal with result if present. Do nothing if there is no pending goal.
ACTION_DEFINITION(ActionSpec)
void cancelCallback(GoalHandle gh)
actionlib_msgs::GoalStatus getGoalStatus() const
bool abortActive(const Result &result, const std::string &msg="")
Abort active goal. Abort active goal with given result, do nothing if there is no active goal...