22#ifndef _ROS_MOVE_BASE_THREAD_H_
23#define _ROS_MOVE_BASE_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>
31#include <core/threading/thread.h>
32#include <interfaces/NavigatorInterface.h>
33#include <move_base_msgs/MoveBaseAction.h>
34#include <move_base_msgs/MoveBaseActionGoal.h>
35#include <move_base_msgs/MoveBaseGoal.h>
36#include <plugins/ros/aspect/ros.h>
43class NavigatorInterface;
64 typedef enum { NAVGRAPH, COLLI } ExecType;
66 typedef actionlib::ActionServer<move_base_msgs::MoveBaseAction> MoveBaseServer;
68 void action_goal_cb(MoveBaseServer::GoalHandle goal, ExecType ext);
69 void action_cancel_cb(MoveBaseServer::GoalHandle goal);
70 void message_cb(geometry_msgs::PoseStampedConstPtr goal_pose, ExecType ext);
73 move_base_msgs::MoveBaseResult create_result();
74 move_base_msgs::MoveBaseFeedback create_feedback();
81 MoveBaseServer *as_colli_;
82 MoveBaseServer *as_navgraph_;
83 ros::Subscriber sub_colli_;
84 ros::Subscriber sub_navgraph_;
86 MoveBaseServer::GoalHandle as_goal_;
87 geometry_msgs::PoseStamped goal_pose_;
89 std::string cfg_base_frame_;
90 std::string cfg_fixed_frame_;
96 unsigned int exec_msgid_;
Accept locomotion commands from ROS (emulate move_base).
RosMoveBaseThread()
Contructor.
virtual void loop()
Code to execute in the thread.
virtual void once()
Execute an action exactly once.
virtual void init()
Initialize the thread.
virtual void finalize()
Finalize 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.
NavigatorInterface Fawkes BlackBoard Interface.
Thread aspect to get access to a ROS node handle.
Thread class encapsulation of pthreads.
Fawkes library namespace.