1 #ifndef __RTT_ACTION_SERVER_H 2 #define __RTT_ACTION_SERVER_H 20 template<
class ActionSpec>
24 template<
class ActionSpec>
48 template<
class ActionSpec>
58 RTTActionServer(
const double status_period = 0.200,
const int sched = ORO_SCHED_OTHER);
59 RTTActionServer(
const std::string name,
const double status_period = 0.200,
const int sched = ORO_SCHED_OTHER);
63 const std::string
getName()
const {
return name_; };
67 const bool create_topics =
false,
68 const std::string &topic_namespace =
"");
80 virtual void publishResult(
const actionlib_msgs::GoalStatus& status,
const Result& result);
83 virtual void publishFeedback(
const actionlib_msgs::GoalStatus& status,
const Feedback& feedback);
86 virtual void publishStatus();
89 goal_operation_ = operation;
94 cancel_operation_ = operation;
105 void goalCallbackWrapper(GoalHandle gh);
130 template <
class ActionSpec>
133 name_(
"action_server"),
134 status_period_(status_period),
135 status_timer_(*this,sched)
139 template <
class ActionSpec>
149 template <
class ActionSpec>
155 template <
class ActionSpec>
168 template <
class ActionSpec>
174 template <
class ActionSpec>
180 template <
class ActionSpec>
183 const bool create_topics,
184 const std::string &topic_namespace)
195 service->addEventPort(
198 .doc(
"Actionlib goal port. Do not read from this port directly.");
200 service->addEventPort(
203 .doc(
"Actionlib cancel port. Do not read from this port directly.");
206 .doc(
"Actionlib result port. Do not write to this port directly.");
209 .doc(
"Actionlib result port. Do not write to this port directly.");
212 .doc(
"Actionlib result port. Do not write to this port directly.");
226 template <
class ActionSpec>
234 boost::make_shared<const ActionGoal>(goal));
238 template <
class ActionSpec>
246 template <
class ActionSpec>
249 actionlib_msgs::GoalID goal_id;
254 boost::make_shared<const actionlib_msgs::GoalID>(goal_id));
258 template <
class ActionSpec>
260 const actionlib_msgs::GoalStatus& status,
261 const Result& result)
265 boost::recursive_mutex::scoped_lock lock(this->
lock_);
268 ActionResult action_result;
270 action_result.status = status;
271 action_result.result = result;
281 template <
class ActionSpec>
283 const actionlib_msgs::GoalStatus& status,
284 const Feedback& feedback)
288 boost::recursive_mutex::scoped_lock lock(this->
lock_);
291 ActionFeedback action_feedback;
293 action_feedback.status = status;
294 action_feedback.feedback = feedback;
302 template <
class ActionSpec>
305 boost::recursive_mutex::scoped_lock lock(this->
lock_);
308 actionlib_msgs::GoalStatusArray status_array;
312 status_array.status_list.resize(this->
status_list_.size());
319 status_array.status_list[i] = (*it).status_;
322 if((*it).handle_destruction_time_ !=
ros::Time() &&
338 #endif // ifndef __RTT_ACTION_SERVER_H void goalCallback(const boost::shared_ptr< const ActionGoal > &goal)
Orocos RTT-Based Action Server.
actionlib::ServerGoalHandle< ActionSpec > GoalHandle
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.
virtual void publishFeedback(const actionlib_msgs::GoalStatus &status, const Feedback &feedback)
Publishes feedback for a given goal.
void goalCallback(RTT::base::PortInterface *port)
void registerGoalOperation(RTT::OperationInterfacePart *operation)
virtual ~RTTActionServerStatusTimer()
rtt_actionlib::ActionBridge action_bridge_
Action bridge container for RTT ports corresponding to the action interface.
void cancelCallback(RTT::base::PortInterface *port)
RTT::OutputPort< actionlib_msgs::GoalStatusArray > & statusOutput()
Get the status output port.
base::ActivityInterface * mThread
void registerCancelOperation(RTT::OperationInterfacePart *operation)
RTTActionServerStatusTimer(RTTActionServer< ActionSpec > &server, int scheduler=ORO_SCHED_OTHER)
virtual void publishResult(const actionlib_msgs::GoalStatus &status, const Result &result)
Publishes a result for a given goal.
RTTActionServer(const double status_period=0.200, const int sched=ORO_SCHED_OTHER)
Constructor.
ACTION_DEFINITION(ActionSpec)
RTT::ConnPolicy topic(const std::string &name)
boost::recursive_mutex lock_
RTT::InputPort< actionlib_msgs::GoalID > & cancelInput()
Get the cancel input port.
bool createServerPorts()
Add actionlib ports to a given rtt service.
ros::Duration status_list_timeout_
virtual void timeout(RTT::os::Timer::TimerId timer_id)
Publish the action server status.
RTT::InputPort< typename ActionSpec::_action_goal_type > & goalInput()
Get the goal input port.
RTT::OperationCaller< void(GoalHandle)> cancel_operation_
RTT::OperationCaller< void(GoalHandle)> goal_operation_
bool setPortsFromService(RTT::Service::shared_ptr service)
Store the required RTT ports from a given RTT service.
bool allConnected() const
True if all existing ports are connected.
void shutdown()
Shutdown internal timer.
std::list< StatusTracker< ActionSpec > > status_list_
bool ready()
Check if the server is ready to be started.
virtual void publishStatus()
Explicitly publish status.
ActionServerBase(boost::function< void(GoalHandle)> goal_cb, boost::function< void(GoalHandle)> cancel_cb, bool auto_start=false)
double status_period_
Period (Hz) at which the status should be published.
#define ACTION_DEFINITION(ActionSpec)
virtual ~RTTActionServer()
RTT::OutputPort< typename ActionSpec::_action_result_type > & resultOutput()
Get the result output port.
virtual void initialize()
Set up status publishing timers.
ROSCONSOLE_DECL void shutdown()
RTT::OutputPort< typename ActionSpec::_action_feedback_type > & feedbackOutput()
Get the feedback output port.
const ros::Time host_now()
RTTActionServer< ActionSpec > & server_
A reference to the owning action server.
std::string name_
Server name (used for naming timers and other resources)
void cancelCallback(const boost::shared_ptr< const actionlib_msgs::GoalID > &goal_id)
const std::string getName() const
Get the name.
Timer to trigger status publications.
static Logger::LogFunction endlog()
void goalCallbackWrapper(GoalHandle gh)
RTTActionServerStatusTimer< ActionSpec > status_timer_
RTT Timer for periodic status updates.