22#ifndef _ROS_SKILLER_THREAD_H_
23#define _ROS_SKILLER_THREAD_H_
25#include <actionlib/server/simple_action_server.h>
26#include <aspect/blackboard.h>
27#include <aspect/blocked_timing.h>
28#include <aspect/configurable.h>
29#include <aspect/logging.h>
30#include <core/threading/thread.h>
31#include <fawkes_msgs/ExecSkillAction.h>
32#include <fawkes_msgs/ExecSkillActionGoal.h>
33#include <fawkes_msgs/ExecSkillGoal.h>
34#include <interfaces/SkillerInterface.h>
35#include <plugins/ros/aspect/ros.h>
37#include <std_msgs/String.h>
42class SkillerInterface;
62 typedef actionlib::ActionServer<fawkes_msgs::ExecSkillAction> SkillerServer;
64 void action_goal_cb(SkillerServer::GoalHandle goal);
65 void action_cancel_cb(SkillerServer::GoalHandle goal);
66 void message_cb(
const std_msgs::String::ConstPtr &goal);
69 fawkes_msgs::ExecSkillResult create_result(
const std::string &errmsg);
70 fawkes_msgs::ExecSkillFeedback create_feedback();
72 bool assure_control();
73 void release_control();
78 SkillerServer * server_;
79 ros::Subscriber sub_cmd_;
80 ros::Publisher pub_status_;
82 SkillerServer::GoalHandle as_goal_;
88 unsigned int exec_msgid_;
89 std::string exec_skill_string_;
90 unsigned int loops_waited_;
Accept skiller commands from ROS.
virtual void once()
Execute an action exactly once.
virtual void finalize()
Finalize the thread.
RosSkillerThread()
Contructor.
virtual void loop()
Code to execute in the thread.
virtual void init()
Initialize the thread.
Thread aspect to access to BlackBoard.
Thread aspect to use blocked timing.
Thread aspect to access configuration data.
Thread aspect to log output.
Thread aspect to get access to a ROS node handle.
SkillerInterface Fawkes BlackBoard Interface.
Thread class encapsulation of pthreads.
Fawkes library namespace.