Go to the documentation of this file.
19 #include <mavros_msgs/Altitude.h>
22 namespace std_plugins {
37 PluginBase::initialize(uas_);
56 void handle_altitude(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::ALTITUDE &altitude)
58 auto ros_msg = boost::make_shared<mavros_msgs::Altitude>();
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;
void initialize(UAS &uas_) override
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
PluginBase()
Plugin constructor Should not do anything before initialize()
Subscriptions get_subscriptions() override
Return vector of MAVLink message subscriptions (handlers)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
void handle_altitude(const mavlink::mavlink_message_t *msg, mavlink::common::msg::ALTITUDE &altitude)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
ros::Publisher altitude_pub
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.
MAVROS Plugin base class.
T param(const std::string ¶m_name, const T &default_val) const
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
mavros
Author(s): Vladimir Ermakov
autogenerated on Tue May 6 2025 02:34:03