Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes | List of all members
mavros::std_plugins::SystemStatusPlugin Class Reference

System status plugin. More...

Inheritance diagram for mavros::std_plugins::SystemStatusPlugin:
Inheritance graph
[legend]

Public Member Functions

Subscriptions get_subscriptions () override
 Return vector of MAVLink message subscriptions (handlers) More...
 
void initialize (UAS &uas_) override
 Plugin initializer. More...
 
 SystemStatusPlugin ()
 
- Public Member Functions inherited from mavros::plugin::PluginBase
virtual ~PluginBase ()
 

Private Types

using M_VehicleInfo = std::unordered_map< uint16_t, mavros_msgs::VehicleInfo >
 

Private Member Functions

void autopilot_version_cb (const ros::WallTimerEvent &event)
 
void connection_cb (bool connected) override
 
M_VehicleInfo::iterator find_or_create_vehicle_info (uint8_t sysid, uint8_t compid)
 
uint16_t get_vehicle_key (uint8_t sysid, uint8_t compid)
 
void handle_autopilot_version (const mavlink::mavlink_message_t *msg, mavlink::common::msg::AUTOPILOT_VERSION &apv)
 
void handle_battery_status (const mavlink::mavlink_message_t *msg, mavlink::common::msg::BATTERY_STATUS &bs)
 
void handle_estimator_status (const mavlink::mavlink_message_t *msg, mavlink::common::msg::ESTIMATOR_STATUS &status)
 
void handle_extended_sys_state (const mavlink::mavlink_message_t *msg, mavlink::common::msg::EXTENDED_SYS_STATE &state)
 
void handle_heartbeat (const mavlink::mavlink_message_t *msg, mavlink::minimal::msg::HEARTBEAT &hb)
 
void handle_hwstatus (const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::HWSTATUS &hwst)
 
void handle_meminfo (const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::MEMINFO &mem)
 
void handle_statustext (const mavlink::mavlink_message_t *msg, mavlink::common::msg::STATUSTEXT &textm)
 
void handle_sys_status (const mavlink::mavlink_message_t *msg, mavlink::common::msg::SYS_STATUS &stat)
 
void heartbeat_cb (const ros::WallTimerEvent &event)
 
void process_autopilot_version_apm_quirk (mavlink::common::msg::AUTOPILOT_VERSION &apv, uint8_t sysid, uint8_t compid)
 
void process_autopilot_version_normal (mavlink::common::msg::AUTOPILOT_VERSION &apv, uint8_t sysid, uint8_t compid)
 
void process_statustext_normal (uint8_t severity, std::string &text)
 
void publish_disconnection ()
 
bool set_message_interval_cb (mavros_msgs::MessageInterval::Request &req, mavros_msgs::MessageInterval::Response &res)
 
bool set_mode_cb (mavros_msgs::SetMode::Request &req, mavros_msgs::SetMode::Response &res)
 
bool set_rate_cb (mavros_msgs::StreamRate::Request &req, mavros_msgs::StreamRate::Response &res)
 
void statustext_cb (const mavros_msgs::StatusText::ConstPtr &req)
 
void timeout_cb (const ros::WallTimerEvent &event)
 
bool vehicle_info_get_cb (mavros_msgs::VehicleInfoGet::Request &req, mavros_msgs::VehicleInfoGet::Response &res)
 

Static Private Member Functions

static std::string custom_version_to_hex_string (std::array< uint8_t, 8 > &array)
 

Private Attributes

ros::WallTimer autopilot_version_timer
 
std::vector< BatteryStatusDiagbatt_diag
 
ros::Publisher batt_pub
 
MAV_TYPE conn_heartbeat_mav_type
 
bool disable_diag
 
ros::Publisher estimator_status_pub
 
ros::Publisher extended_state_pub
 
bool has_battery_status0
 
HeartbeatStatus hb_diag
 
ros::WallTimer heartbeat_timer
 
HwStatus hwst_diag
 
MemInfo mem_diag
 
ros::ServiceServer message_interval_srv
 
ros::ServiceServer mode_srv
 
ros::NodeHandle nh
 
ros::ServiceServer rate_srv
 
ros::Publisher state_pub
 
ros::Publisher statustext_pub
 
ros::Subscriber statustext_sub
 
SystemStatusDiag sys_diag
 
ros::WallTimer timeout_timer
 
ros::ServiceServer vehicle_info_get_srv
 
M_VehicleInfo vehicles
 
int version_retries
 

Static Private Attributes

static constexpr int RETRIES_COUNT = 6
 

Additional Inherited Members

- Public Types inherited from mavros::plugin::PluginBase
using ConstPtr = boost::shared_ptr< PluginBase const >
 
using HandlerCb = mavconn::MAVConnInterface::ReceivedCb
 generic message handler callback More...
 
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. More...
 
using Ptr = boost::shared_ptr< PluginBase >
 
using Subscriptions = std::vector< HandlerInfo >
 Subscriptions vector. More...
 
- Protected Member Functions inherited from mavros::plugin::PluginBase
virtual void capabilities_cb (UAS::MAV_CAP capabilities)
 
void enable_capabilities_cb ()
 
void enable_connection_cb ()
 
template<class _C >
HandlerInfo make_handler (const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
 
template<class _C , class _T >
HandlerInfo make_handler (void(_C::*fn)(const mavlink::mavlink_message_t *, _T &))
 
 PluginBase ()
 Plugin constructor Should not do anything before initialize() More...
 
- Protected Attributes inherited from mavros::plugin::PluginBase
UASm_uas
 

Detailed Description

System status plugin.

Required by all plugins.

Definition at line 481 of file sys_status.cpp.


The documentation for this class was generated from the following file:


mavros
Author(s): Vladimir Ermakov
autogenerated on Tue Jun 13 2023 02:17:50