ESC status plugin. More...
Public Member Functions | |
ESCStatusPlugin () | |
Subscriptions | get_subscriptions () override |
void | initialize (UAS &uas_) override |
Public Member Functions inherited from mavros::plugin::PluginBase | |
virtual | ~PluginBase () |
Private Types | |
using | lock_guard = std::lock_guard< std::mutex > |
Private Member Functions | |
void | connection_cb (bool connected) override |
void | handle_esc_info (const mavlink::mavlink_message_t *msg, mavlink::common::msg::ESC_INFO &esc_info) |
void | handle_esc_status (const mavlink::mavlink_message_t *msg, mavlink::common::msg::ESC_STATUS &esc_status) |
Private Attributes | |
mavros_msgs::ESCInfo | _esc_info |
mavros_msgs::ESCStatus | _esc_status |
uint8_t | _max_esc_count |
uint8_t | _max_esc_info_index |
uint8_t | _max_esc_status_index |
const uint8_t | batch_size = 4 |
ros::Publisher | esc_info_pub |
ros::Publisher | esc_status_pub |
std::mutex | mutex |
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, HandlerCb > | HandlerInfo |
typedef boost::shared_ptr< PluginBase > | Ptr |
typedef std::vector< HandlerInfo > | Subscriptions |
Protected Member Functions inherited from mavros::plugin::PluginBase | |
virtual void | capabilities_cb (UAS::MAV_CAP capabilities) |
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 | |
UAS * | m_uas |
ESC status plugin.
Definition at line 28 of file esc_status.cpp.