Public Member Functions | Private Member Functions | Private Attributes | Friends
mavplugin::SetpointAttitudePlugin Class Reference

Setpoint attitude plugin. More...

Inheritance diagram for mavplugin::SetpointAttitudePlugin:
Inheritance graph
[legend]

List of all members.

Public Member Functions

const std::string get_name () const
 Plugin name (CamelCase)
const message_map get_rx_handlers ()
 Return map with message rx handlers.
void initialize (UAS &uas_, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
 Plugin initializer.
 SetpointAttitudePlugin ()

Private Member Functions

bool is_normalized (float throttle, const float min, const float max)
void pose_cb (const geometry_msgs::PoseStamped::ConstPtr &req)
void pose_cov_cb (const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &req)
void send_attitude_ang_velocity (const ros::Time &stamp, const float vx, const float vy, const float vz)
void send_attitude_throttle (const float throttle)
void send_attitude_transform (const tf::Transform &transform, const ros::Time &stamp)
void set_attitude_target (uint32_t time_boot_ms, uint8_t type_mask, float q[4], float roll_rate, float pitch_rate, float yaw_rate, float thrust)
void throttle_cb (const std_msgs::Float64::ConstPtr &req)
void twist_cb (const geometry_msgs::TwistStamped::ConstPtr &req)

Private Attributes

ros::Subscriber att_sub
std::string child_frame_id
std::string frame_id
bool reverse_throttle
ros::NodeHandle sp_nh
double tf_rate
ros::Subscriber throttle_sub
UASuas

Friends

class TFListenerMixin

Detailed Description

Setpoint attitude plugin.

Send setpoint attitude/orientation/thrust to FCU controller.

Definition at line 44 of file setpoint_attitude.cpp.


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


mavros
Author(s): Vladimir Ermakov
autogenerated on Wed Aug 26 2015 12:29:13