Public Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
mavros::std_plugins::SetpointAttitudePlugin Class Reference

Setpoint attitude plugin. More...

Inheritance diagram for mavros::std_plugins::SetpointAttitudePlugin:
Inheritance graph
[legend]

Public Member Functions

Subscriptions get_subscriptions ()
 Return vector of MAVLink message subscriptions (handlers) More...
 
void initialize (UAS &uas_)
 Plugin initializer. More...
 
 SetpointAttitudePlugin ()
 
- Public Member Functions inherited from mavros::plugin::PluginBase
virtual ~PluginBase ()
 

Private Member Functions

void attitude_pose_cb (const geometry_msgs::PoseStamped::ConstPtr &pose_msg, const mavros_msgs::Thrust::ConstPtr &thrust_msg)
 
void attitude_twist_cb (const geometry_msgs::TwistStamped::ConstPtr &req, const mavros_msgs::Thrust::ConstPtr &thrust_msg)
 
bool is_normalized (float thrust)
 Function to verify if the thrust values are normalized; considers also the reversed trust values. More...
 
void send_attitude_ang_velocity (const ros::Time &stamp, const Eigen::Vector3d &ang_vel, const float thrust)
 Send angular velocity setpoint and thrust to FCU attitude controller. More...
 
void send_attitude_quaternion (const ros::Time &stamp, const Eigen::Affine3d &tr, const float thrust)
 Send attitude setpoint and thrust to FCU attitude controller. More...
 
void transform_cb (const geometry_msgs::TransformStamped &transform, const mavros_msgs::Thrust::ConstPtr &thrust_msg)
 
- Private Member Functions inherited from mavros::plugin::SetAttitudeTargetMixin< SetpointAttitudePlugin >
void set_attitude_target (uint32_t time_boot_ms, uint8_t type_mask, Eigen::Quaterniond orientation, Eigen::Vector3d body_rate, float thrust)
 Message sepecification: https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET. More...
 
- Private Member Functions inherited from mavros::plugin::TF2ListenerMixin< SetpointAttitudePlugin >
void tf2_start (const char *_thd_name, void(SetpointAttitudePlugin::*cbp)(const geometry_msgs::TransformStamped &))
 start tf listener More...
 
void tf2_start (const char *_thd_name, message_filters::Subscriber< T > &topic_sub, void(SetpointAttitudePlugin::*cbp)(const geometry_msgs::TransformStamped &, const typename T::ConstPtr &))
 start tf listener syncronized with another topic More...
 

Private Attributes

float normalized_thrust
 
message_filters::Subscriber< geometry_msgs::PoseStamped > pose_sub
 
bool reverse_thrust
 
ros::NodeHandle sp_nh
 
std::unique_ptr< SyncPoseThrustsync_pose
 
std::unique_ptr< SyncTwistThrustsync_twist
 
std::string tf_child_frame_id
 
std::string tf_frame_id
 
bool tf_listen
 
double tf_rate
 
message_filters::Subscriber< mavros_msgs::Thrust > th_sub
 
message_filters::Subscriber< geometry_msgs::TwistStamped > twist_sub
 
bool use_quaternion
 
- Private Attributes inherited from mavros::plugin::TF2ListenerMixin< SetpointAttitudePlugin >
std::string tf_thd_name
 
std::thread tf_thread
 

Friends

class SetAttitudeTargetMixin
 
class TF2ListenerMixin
 

Additional Inherited Members

- Public Types inherited from mavros::plugin::PluginBase
using ConstPtr = boost::shared_ptr< PluginBase const >
 
using HandlerCb = mavconn::MAVConnInterface::ReceivedCb
 generic message handler callback More...
 
using HandlerInfo = std::tuple< mavlink::msgid_t, const char *, size_t, HandlerCb >
 Tuple: MSG ID, MSG NAME, message type into hash_code, message handler callback. More...
 
using Ptr = boost::shared_ptr< PluginBase >
 
using Subscriptions = std::vector< HandlerInfo >
 Subscriptions vector. More...
 
- Protected Member Functions inherited from mavros::plugin::PluginBase
virtual void connection_cb (bool connected)
 
void enable_connection_cb ()
 
template<class _C >
HandlerInfo make_handler (const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
 
template<class _C , class _T >
HandlerInfo make_handler (void(_C::*fn)(const mavlink::mavlink_message_t *, _T &))
 
 PluginBase ()
 Plugin constructor Should not do anything before initialize() More...
 
- Protected Attributes inherited from mavros::plugin::PluginBase
UASm_uas
 

Detailed Description

Setpoint attitude plugin.

Send setpoint attitude/orientation/thrust to FCU controller.

Definition at line 43 of file setpoint_attitude.cpp.


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


mavros
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:11