Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
hector_quadrotor_actions::BaseActionServer< ActionSpec > Class Template Reference

#include <base_action.h>

Public Types

typedef actionlib::SimpleActionServer< ActionSpec > ActionServer
 

Public Member Functions

 BaseActionServer (ros::NodeHandle nh, std::string server_name, typename ActionServer::ExecuteCallback callback)
 
bool enableMotors (bool enable)
 
boost::shared_ptr< ActionServerget ()
 
geometry_msgs::PoseStampedConstPtr getPose ()
 

Private Member Functions

void startCb ()
 

Private Attributes

boost::shared_ptr< ActionServeras_
 
double connection_timeout_
 
ros::ServiceClient motor_enable_service_
 
hector_quadrotor_interface::PoseSubscriberHelper pose_sub_
 
std::string server_name_
 
ros::Timer start_timer_
 

Detailed Description

template<class ActionSpec>
class hector_quadrotor_actions::BaseActionServer< ActionSpec >

Definition at line 42 of file base_action.h.

Member Typedef Documentation

template<class ActionSpec>
typedef actionlib::SimpleActionServer<ActionSpec> hector_quadrotor_actions::BaseActionServer< ActionSpec >::ActionServer

Definition at line 46 of file base_action.h.

Constructor & Destructor Documentation

template<class ActionSpec>
hector_quadrotor_actions::BaseActionServer< ActionSpec >::BaseActionServer ( ros::NodeHandle  nh,
std::string  server_name,
typename ActionServer::ExecuteCallback  callback 
)
inline

Definition at line 48 of file base_action.h.

Member Function Documentation

template<class ActionSpec>
bool hector_quadrotor_actions::BaseActionServer< ActionSpec >::enableMotors ( bool  enable)
inline

Definition at line 74 of file base_action.h.

template<class ActionSpec>
boost::shared_ptr<ActionServer> hector_quadrotor_actions::BaseActionServer< ActionSpec >::get ( )
inline

Definition at line 72 of file base_action.h.

template<class ActionSpec>
geometry_msgs::PoseStampedConstPtr hector_quadrotor_actions::BaseActionServer< ActionSpec >::getPose ( )
inline

Definition at line 67 of file base_action.h.

template<class ActionSpec>
void hector_quadrotor_actions::BaseActionServer< ActionSpec >::startCb ( )
inlineprivate

Definition at line 83 of file base_action.h.

Member Data Documentation

template<class ActionSpec>
boost::shared_ptr<ActionServer> hector_quadrotor_actions::BaseActionServer< ActionSpec >::as_
private

Definition at line 98 of file base_action.h.

template<class ActionSpec>
double hector_quadrotor_actions::BaseActionServer< ActionSpec >::connection_timeout_
private

Definition at line 105 of file base_action.h.

template<class ActionSpec>
ros::ServiceClient hector_quadrotor_actions::BaseActionServer< ActionSpec >::motor_enable_service_
private

Definition at line 103 of file base_action.h.

template<class ActionSpec>
hector_quadrotor_interface::PoseSubscriberHelper hector_quadrotor_actions::BaseActionServer< ActionSpec >::pose_sub_
private

Definition at line 102 of file base_action.h.

template<class ActionSpec>
std::string hector_quadrotor_actions::BaseActionServer< ActionSpec >::server_name_
private

Definition at line 100 of file base_action.h.

template<class ActionSpec>
ros::Timer hector_quadrotor_actions::BaseActionServer< ActionSpec >::start_timer_
private

Definition at line 101 of file base_action.h.


The documentation for this class was generated from the following file:


hector_quadrotor_actions
Author(s): Paul Bovbel
autogenerated on Mon Jun 10 2019 13:36:49