vfr_hud.cpp
Go to the documentation of this file.
1 
9 /*
10  * Copyright 2014,2016 Vladimir Ermakov.
11  *
12  * This file is part of the mavros package and subject to the license terms
13  * in the top-level LICENSE file of the mavros repository.
14  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
15  */
16 
17 #include <angles/angles.h>
18 #include <mavros/mavros_plugin.h>
19 
20 #include <mavros_msgs/VFR_HUD.h>
21 
22 namespace mavros {
23 namespace std_plugins {
28 public:
30  nh("~")
31  { }
32 
36  void initialize(UAS &uas_)
37  {
38  PluginBase::initialize(uas_);
39 
40  vfr_pub = nh.advertise<mavros_msgs::VFR_HUD>("vfr_hud", 10);
41  }
42 
44  {
45  return {
47  };
48  }
49 
50 private:
52 
54 
55  void handle_vfr_hud(const mavlink::mavlink_message_t *msg, mavlink::common::msg::VFR_HUD &vfr_hud)
56  {
57  auto vmsg = boost::make_shared<mavros_msgs::VFR_HUD>();
58  vmsg->header.stamp = ros::Time::now();
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; // comes in 0..100 range
63  vmsg->altitude = vfr_hud.alt;
64  vmsg->climb = vfr_hud.climb;
65 
66  vfr_pub.publish(vmsg);
67  }
68 };
69 } // namespace std_plugins
70 } // namespace mavros
71 
MAVROS Plugin base class.
Definition: mavros_plugin.h:37
void publish(const boost::shared_ptr< M > &message) const
MAVROS Plugin base.
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
Definition: mavros_plugin.h:88
PluginBase()
Plugin constructor Should not do anything before initialize()
Definition: mavros_plugin.h:75
UAS for plugins.
Definition: mavros_uas.h:66
Subscriptions get_subscriptions()
Return vector of MAVLink message subscriptions (handlers)
Definition: vfr_hud.cpp:43
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
Definition: mavros_plugin.h:48
static Time now()
#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)
Definition: vfr_hud.cpp:55


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