20 #include <mavros_msgs/VFR_HUD.h> 23 namespace std_plugins {
38 PluginBase::initialize(uas_);
55 void handle_vfr_hud(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::VFR_HUD &vfr_hud)
57 auto vmsg = boost::make_shared<mavros_msgs::VFR_HUD>();
59 vmsg->airspeed = vfr_hud.airspeed;
60 vmsg->groundspeed = vfr_hud.groundspeed;
61 vmsg->heading = vfr_hud.heading;
62 vmsg->throttle = vfr_hud.throttle / 100.0;
63 vmsg->altitude = vfr_hud.alt;
64 vmsg->climb = vfr_hud.climb;
MAVROS Plugin base class.
void publish(const boost::shared_ptr< M > &message) const
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
void initialize(UAS &uas_)
PluginBase()
Plugin constructor Should not do anything before initialize()
Subscriptions get_subscriptions()
Return vector of MAVLink message subscriptions (handlers)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void handle_vfr_hud(const mavlink::mavlink_message_t *msg, mavlink::common::msg::VFR_HUD &vfr_hud)