Public Member Functions | Private Member Functions | Private Attributes | List of all members
mavros::extra_plugins::MountControlPlugin Class Reference

Mount Control plugin. More...

Inheritance diagram for mavros::extra_plugins::MountControlPlugin:
Inheritance graph
[legend]

Public Member Functions

Subscriptions get_subscriptions () override
 
void initialize (UAS &uas_) override
 
 MountControlPlugin ()
 
- Public Member Functions inherited from mavros::plugin::PluginBase
virtual ~PluginBase ()
 

Private Member Functions

void command_cb (const mavros_msgs::MountControl::ConstPtr &req)
 Send mount control commands to vehicle. More...
 
void handle_mount_orientation (const mavlink::mavlink_message_t *msg, mavlink::common::msg::MOUNT_ORIENTATION &mo)
 Publish the mount orientation. More...
 
bool mount_configure_cb (mavros_msgs::MountConfigure::Request &req, mavros_msgs::MountConfigure::Response &res)
 

Private Attributes

ros::Subscriber command_sub
 
ros::ServiceServer configure_srv
 
ros::NodeHandle mount_nh
 
ros::Publisher mount_orientation_pub
 
ros::NodeHandle nh
 

Additional Inherited Members

- Public Types inherited from mavros::plugin::PluginBase
typedef boost::shared_ptr< PluginBase const > ConstPtr
 
typedef mavconn::MAVConnInterface::ReceivedCb HandlerCb
 
typedef std::tuple< mavlink::msgid_t, const char *, size_t, HandlerCbHandlerInfo
 
typedef boost::shared_ptr< PluginBasePtr
 
typedef std::vector< HandlerInfoSubscriptions
 
- Protected Member Functions inherited from mavros::plugin::PluginBase
virtual void capabilities_cb (UAS::MAV_CAP capabilities)
 
virtual void connection_cb (bool connected)
 
void enable_capabilities_cb ()
 
void enable_connection_cb ()
 
HandlerInfo make_handler (const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
 
HandlerInfo make_handler (void(_C::*fn)(const mavlink::mavlink_message_t *, _T &))
 
 PluginBase ()
 
- Protected Attributes inherited from mavros::plugin::PluginBase
UASm_uas
 

Detailed Description

Mount Control plugin.

Publishes Mission commands to control the camera or antenna mount.

See also
command_cb()

Definition at line 38 of file mount_control.cpp.


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


mavros_extras
Author(s): Vladimir Ermakov , Amilcar Lucas
autogenerated on Tue Jun 1 2021 02:36:37