Go to the documentation of this file.
19 #include <mavros_msgs/CompanionProcessStatus.h>
22 namespace extra_plugins {
26 using mavlink::minimal::MAV_COMPONENT;
67 mavlink::minimal::msg::HEARTBEAT heartbeat {};
69 heartbeat.type =
enum_value(MAV_TYPE::ONBOARD_CONTROLLER);
70 heartbeat.autopilot =
enum_value(MAV_AUTOPILOT::PX4);
71 heartbeat.base_mode =
enum_value(MAV_MODE_FLAG::CUSTOM_MODE_ENABLED);
72 heartbeat.system_status = req->state;
75 utils::to_string_enum<MAV_COMPONENT>(req->component) <<
" companion process status: " <<
76 utils::to_string_enum<MAV_STATE>(heartbeat.system_status) << std::endl << heartbeat.to_yaml());
78 UAS_FCU(
m_uas)->send_message_ignore_drop(heartbeat, req->component);
std::vector< HandlerInfo > Subscriptions
Subscriptions get_subscriptions() override
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define UAS_FCU(uasobjptr)
CompanionProcessStatusPlugin()
std::shared_ptr< MAVConnInterface const > ConstPtr
ros::Subscriber status_sub
void status_cb(const mavros_msgs::CompanionProcessStatus::ConstPtr &req)
Send companion process status to FCU over a heartbeat message.
void initialize(UAS &uas_) override
ros::NodeHandle status_nh
mavlink::minimal::MAV_AUTOPILOT MAV_AUTOPILOT
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
virtual void initialize(UAS &uas)
mavlink::minimal::MAV_TYPE MAV_TYPE
mavlink::minimal::MAV_MODE_FLAG MAV_MODE_FLAG
constexpr std::underlying_type< _T >::type enum_value(_T e)
mavlink::minimal::MAV_STATE MAV_STATE
mavros_extras
Author(s): Vladimir Ermakov
, Amilcar Lucas
autogenerated on Tue May 6 2025 02:34:08