29 #ifndef HECTOR_QUADROTOR_ACTIONS_BASE_ACTION_H 30 #define HECTOR_QUADROTOR_ACTIONS_BASE_ACTION_H 35 #include "geometry_msgs/PoseStamped.h" 36 #include <hector_uav_msgs/EnableMotors.h> 41 template <
class ActionSpec>
50 as_(
boost::make_shared<ActionServer>(nh, server_name, callback, false))
67 geometry_msgs::PoseStampedConstPtr
getPose()
76 hector_uav_msgs::EnableMotors srv;
77 srv.request.enable = enable;
111 #endif //HECTOR_QUADROTOR_ACTIONS_BASE_ACTION_H hector_quadrotor_interface::PoseSubscriberHelper pose_sub_
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
std::string resolveName(const std::string &name, bool remap=true) const
bool call(MReq &req, MRes &res)
geometry_msgs::PoseStampedConstPtr get() const
bool enableMotors(bool enable)
boost::function< void(const GoalConstPtr &)> ExecuteCallback
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
actionlib::SimpleActionServer< ActionSpec > ActionServer
geometry_msgs::PoseStampedConstPtr getPose()
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
BaseActionServer(ros::NodeHandle nh, std::string server_name, typename ActionServer::ExecuteCallback callback)
#define ROS_INFO_STREAM(args)
ros::ServiceClient motor_enable_service_
#define ROS_ERROR_STREAM(args)
#define ROS_INFO_STREAM_THROTTLE(rate, args)
double connection_timeout_
boost::shared_ptr< ActionServer > as_