Class Plugin

Inheritance Relationships

Base Type

  • public std::enable_shared_from_this< Plugin >

Derived Type

Class Documentation

class Plugin : public std::enable_shared_from_this<Plugin>

MAVROS Plugin base class.

Subclassed by mavros::plugin::MissionBase

Public Types

using HandlerCb = mavconn::MAVConnInterface::ReceivedCb

generic message handler callback

using HandlerInfo = std::tuple<mavlink::msgid_t, const char*, size_t, HandlerCb>

Tuple: MSG ID, MSG NAME, message type into hash_code, message handler callback.

using Subscriptions = std::vector<HandlerInfo>

Subscriptions vector.

Public Functions

inline explicit Plugin(UASPtr uas_)
inline explicit Plugin(UASPtr uas_, const std::string &subnode, const rclcpp::NodeOptions &options = rclcpp::NodeOptions())
virtual ~Plugin() = default
virtual Subscriptions get_subscriptions() = 0

Return vector of MAVLink message subscriptions (handlers)

inline virtual rclcpp::Node::SharedPtr get_node() const
inline virtual rclcpp::Logger get_logger() const
inline virtual rclcpp::Clock::SharedPtr get_clock() const

Protected Types

using SetParametersResult = rcl_interfaces::msg::SetParametersResult
using ParameterFunctorT = std::function<void(const rclcpp::Parameter &p)>

Protected Functions

Make subscription to raw message.

Parameters:
  • id[in] message id

  • fn[in] pointer to member function (handler)

Make subscription to message with automatic decoding.

Parameters:

fn[in] pointer to member function (handler)

inline virtual void connection_cb(bool connected)

Common callback called on connection change

void enable_connection_cb()

Shortcut for connection_cb() registration

inline virtual void capabilities_cb(uas::MAV_CAP capabilities)

Common callback called only when capabilities change

void enable_capabilities_cb()

Shortcut for capabilities_cb() registration

virtual SetParametersResult node_on_set_parameters_cb(const std::vector<rclcpp::Parameter> &parameters)

Default implmentation of that watch would use watch_parameters

void enable_node_watch_parameters()

Shourtcut to enable default parameters watch impl

template<typename ParameterT>
inline auto node_declare_and_watch_parameter(const std::string &name, ParameterFunctorT cb, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor = rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override = false)

Adds parameter to watch and declares it

template<typename ParameterT>
inline auto node_declare_and_watch_parameter(const std::string &name, const ParameterT &default_value, ParameterFunctorT cb, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor = rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override = false)
inline uint64_t get_time_usec(const builtin_interfaces::msg::Time &t)

Helper to convert ros time to mavlink time_usec field.

inline uint64_t get_time_usec()

Helper to convert ros now time to mavlink time_usec field.

inline uint32_t get_time_boot_ms(const builtin_interfaces::msg::Time &t)

Helper to convert ros time to mavlink time_boot_ms field.

inline uint32_t get_time_boot_ms()

Helper to convert ros now time to mavlink time_boot_ms field.

Protected Attributes

UASPtr uas
rclcpp::Node::SharedPtr node
std::unordered_map<std::string, ParameterFunctorT> node_watch_parameters
rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr node_set_parameters_handle_ptr