altitude.cpp
Go to the documentation of this file.
1 
9 /*
10  * Copyright 2015 Andreas Antener <andreas@uaventure.com>.
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 <mavros/mavros_plugin.h>
18 
19 #include <mavros_msgs/Altitude.h>
20 
21 namespace mavros {
22 namespace std_plugins {
27 public:
29  nh("~")
30  { }
31 
35  void initialize(UAS &uas_) override
36  {
37  PluginBase::initialize(uas_);
38 
39  nh.param<std::string>("frame_id", frame_id, "map");
40  altitude_pub = nh.advertise<mavros_msgs::Altitude>("altitude", 10);
41  }
42 
44  {
45  return {
47  };
48  }
49 
50 private:
52  std::string frame_id;
53 
55 
56  void handle_altitude(const mavlink::mavlink_message_t *msg, mavlink::common::msg::ALTITUDE &altitude)
57  {
58  auto ros_msg = boost::make_shared<mavros_msgs::Altitude>();
59  ros_msg->header = m_uas->synchronized_header(frame_id, altitude.time_usec);
60 
61  ros_msg->monotonic = altitude.altitude_monotonic;
62  ros_msg->amsl = altitude.altitude_amsl;
63  ros_msg->local = altitude.altitude_local;
64  ros_msg->relative = altitude.altitude_relative;
65  ros_msg->terrain = altitude.altitude_terrain;
66  ros_msg->bottom_clearance = altitude.bottom_clearance;
67 
68  altitude_pub.publish(ros_msg);
69  }
70 };
71 } // namespace std_plugins
72 } // namespace mavros
73 
mavros::std_plugins::AltitudePlugin::initialize
void initialize(UAS &uas_) override
Definition: altitude.cpp:35
mavros::plugin::PluginBase::m_uas
UAS * m_uas
Definition: mavros_plugin.h:74
mavros::std_plugins::AltitudePlugin::frame_id
std::string frame_id
Definition: altitude.cpp:52
mavros::plugin::PluginBase::Subscriptions
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
Definition: mavros_plugin.h:47
ros::Publisher
mavros::plugin::PluginBase::PluginBase
PluginBase()
Plugin constructor Should not do anything before initialize()
Definition: mavros_plugin.h:74
mavros::std_plugins::AltitudePlugin::get_subscriptions
Subscriptions get_subscriptions() override
Return vector of MAVLink message subscriptions (handlers)
Definition: altitude.cpp:43
mavros::UAS
UAS for plugins.
Definition: mavros_uas.h:67
mavros::std_plugins::AltitudePlugin::nh
ros::NodeHandle nh
Definition: altitude.cpp:51
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
mavros::std_plugins::AltitudePlugin::handle_altitude
void handle_altitude(const mavlink::mavlink_message_t *msg, mavlink::common::msg::ALTITUDE &altitude)
Definition: altitude.cpp:56
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
mavros::std_plugins::AltitudePlugin::AltitudePlugin
AltitudePlugin()
Definition: altitude.cpp:28
mavros::std_plugins::AltitudePlugin::altitude_pub
ros::Publisher altitude_pub
Definition: altitude.cpp:54
mavros_plugin.h
MAVROS Plugin base.
mavros
Definition: frame_tf.h:34
mavros::UAS::synchronized_header
std_msgs::Header synchronized_header(const std::string &frame_id, const T time_stamp)
Create message header from time_boot_ms or time_usec stamps and frame_id.
Definition: mavros_uas.h:375
mavros::std_plugins::AltitudePlugin
Altitude plugin.
Definition: altitude.cpp:26
mavros::plugin::PluginBase
MAVROS Plugin base class.
Definition: mavros_plugin.h:36
class_list_macros.hpp
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
mavros::plugin::PluginBase::make_handler
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:87
ros::NodeHandle


mavros
Author(s): Vladimir Ermakov
autogenerated on Tue May 6 2025 02:34:03