Classes | Public Member Functions | Private Types | Private Attributes | List of all members
hector_quadrotor::Teleop Class Reference

Classes

struct  Axis
 
struct  Button
 

Public Member Functions

bool enableMotors (bool enable)
 
double getAxis (const sensor_msgs::JoyConstPtr &joy, const Axis &axis)
 
bool getButton (const sensor_msgs::JoyConstPtr &joy, const Button &button)
 
void joyAttitudeCallback (const sensor_msgs::JoyConstPtr &joy)
 
void joyPoseCallback (const sensor_msgs::JoyConstPtr &joy)
 
void joyTwistCallback (const sensor_msgs::JoyConstPtr &joy)
 
void stop ()
 
 Teleop ()
 
 ~Teleop ()
 

Private Types

typedef actionlib::SimpleActionClient< hector_uav_msgs::LandingAction > LandingClient
 
typedef actionlib::SimpleActionClient< hector_uav_msgs::PoseAction > PoseClient
 
typedef actionlib::SimpleActionClient< hector_uav_msgs::TakeoffAction > TakeoffClient
 

Private Attributes

ros::Publisher attitude_publisher_
 
struct {
   Axis   thrust
 
   Axis   x
 
   Axis   y
 
   Axis   yaw
 
   Axis   z
 
axes_
 
std::string base_link_frame_
 
std::string base_stabilized_frame_
 
struct {
   Button   go
 
   Button   interrupt
 
   Button   slow
 
   Button   stop
 
buttons_
 
ros::Subscriber joy_subscriber_
 
boost::shared_ptr< LandingClientlanding_client_
 
ros::ServiceClient motor_enable_service_
 
ros::NodeHandle node_handle_
 
geometry_msgs::PoseStamped pose_
 
boost::shared_ptr< PoseClientpose_client_
 
double slow_factor_
 
boost::shared_ptr< TakeoffClienttakeoff_client_
 
ros::Publisher thrust_publisher_
 
ros::Publisher velocity_publisher_
 
std::string world_frame_
 
double yaw_
 
ros::Publisher yawrate_publisher_
 

Detailed Description

Definition at line 47 of file quadrotor_teleop.cpp.

Member Typedef Documentation

typedef actionlib::SimpleActionClient<hector_uav_msgs::LandingAction> hector_quadrotor::Teleop::LandingClient
private

Definition at line 50 of file quadrotor_teleop.cpp.

typedef actionlib::SimpleActionClient<hector_uav_msgs::PoseAction> hector_quadrotor::Teleop::PoseClient
private

Definition at line 52 of file quadrotor_teleop.cpp.

typedef actionlib::SimpleActionClient<hector_uav_msgs::TakeoffAction> hector_quadrotor::Teleop::TakeoffClient
private

Definition at line 51 of file quadrotor_teleop.cpp.

Constructor & Destructor Documentation

hector_quadrotor::Teleop::Teleop ( )
inline

Definition at line 106 of file quadrotor_teleop.cpp.

hector_quadrotor::Teleop::~Teleop ( )
inline

Definition at line 192 of file quadrotor_teleop.cpp.

Member Function Documentation

bool hector_quadrotor::Teleop::enableMotors ( bool  enable)
inline

Definition at line 332 of file quadrotor_teleop.cpp.

double hector_quadrotor::Teleop::getAxis ( const sensor_msgs::JoyConstPtr &  joy,
const Axis axis 
)
inline

Definition at line 302 of file quadrotor_teleop.cpp.

bool hector_quadrotor::Teleop::getButton ( const sensor_msgs::JoyConstPtr &  joy,
const Button button 
)
inline

Definition at line 321 of file quadrotor_teleop.cpp.

void hector_quadrotor::Teleop::joyAttitudeCallback ( const sensor_msgs::JoyConstPtr &  joy)
inline

Definition at line 197 of file quadrotor_teleop.cpp.

void hector_quadrotor::Teleop::joyPoseCallback ( const sensor_msgs::JoyConstPtr &  joy)
inline

Definition at line 267 of file quadrotor_teleop.cpp.

void hector_quadrotor::Teleop::joyTwistCallback ( const sensor_msgs::JoyConstPtr &  joy)
inline

Definition at line 238 of file quadrotor_teleop.cpp.

void hector_quadrotor::Teleop::stop ( )
inline

Definition at line 345 of file quadrotor_teleop.cpp.

Member Data Documentation

ros::Publisher hector_quadrotor::Teleop::attitude_publisher_
private

Definition at line 56 of file quadrotor_teleop.cpp.

struct { ... } hector_quadrotor::Teleop::axes_
std::string hector_quadrotor::Teleop::base_link_frame_
private

Definition at line 103 of file quadrotor_teleop.cpp.

std::string hector_quadrotor::Teleop::base_stabilized_frame_
private

Definition at line 103 of file quadrotor_teleop.cpp.

struct { ... } hector_quadrotor::Teleop::buttons_
Button hector_quadrotor::Teleop::go

Definition at line 97 of file quadrotor_teleop.cpp.

Button hector_quadrotor::Teleop::interrupt

Definition at line 99 of file quadrotor_teleop.cpp.

ros::Subscriber hector_quadrotor::Teleop::joy_subscriber_
private

Definition at line 55 of file quadrotor_teleop.cpp.

boost::shared_ptr<LandingClient> hector_quadrotor::Teleop::landing_client_
private

Definition at line 58 of file quadrotor_teleop.cpp.

ros::ServiceClient hector_quadrotor::Teleop::motor_enable_service_
private

Definition at line 57 of file quadrotor_teleop.cpp.

ros::NodeHandle hector_quadrotor::Teleop::node_handle_
private

Definition at line 54 of file quadrotor_teleop.cpp.

geometry_msgs::PoseStamped hector_quadrotor::Teleop::pose_
private

Definition at line 62 of file quadrotor_teleop.cpp.

boost::shared_ptr<PoseClient> hector_quadrotor::Teleop::pose_client_
private

Definition at line 60 of file quadrotor_teleop.cpp.

Button hector_quadrotor::Teleop::slow

Definition at line 96 of file quadrotor_teleop.cpp.

double hector_quadrotor::Teleop::slow_factor_
private

Definition at line 102 of file quadrotor_teleop.cpp.

Button hector_quadrotor::Teleop::stop

Definition at line 98 of file quadrotor_teleop.cpp.

boost::shared_ptr<TakeoffClient> hector_quadrotor::Teleop::takeoff_client_
private

Definition at line 59 of file quadrotor_teleop.cpp.

Axis hector_quadrotor::Teleop::thrust

Definition at line 90 of file quadrotor_teleop.cpp.

ros::Publisher hector_quadrotor::Teleop::thrust_publisher_
private

Definition at line 56 of file quadrotor_teleop.cpp.

ros::Publisher hector_quadrotor::Teleop::velocity_publisher_
private

Definition at line 56 of file quadrotor_teleop.cpp.

std::string hector_quadrotor::Teleop::world_frame_
private

Definition at line 103 of file quadrotor_teleop.cpp.

Axis hector_quadrotor::Teleop::x

Definition at line 87 of file quadrotor_teleop.cpp.

Axis hector_quadrotor::Teleop::y

Definition at line 88 of file quadrotor_teleop.cpp.

Axis hector_quadrotor::Teleop::yaw

Definition at line 91 of file quadrotor_teleop.cpp.

double hector_quadrotor::Teleop::yaw_
private

Definition at line 63 of file quadrotor_teleop.cpp.

ros::Publisher hector_quadrotor::Teleop::yawrate_publisher_
private

Definition at line 56 of file quadrotor_teleop.cpp.

Axis hector_quadrotor::Teleop::z

Definition at line 89 of file quadrotor_teleop.cpp.


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


hector_quadrotor_teleop
Author(s): Johannes Meyer
autogenerated on Mon Jun 10 2019 13:37:04