esc_status.cpp
Go to the documentation of this file.
1 
9 /*
10  * Copyright 2020 Ricardo Marques <marques.ricardo17@gmail.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 #include <mavros_msgs/ESCInfo.h>
19 #include <mavros_msgs/ESCStatus.h>
20 
21 namespace mavros
22 {
23 namespace extra_plugins
24 {
29 {
30 public:
32  nh("~"),
33  _max_esc_count(0),
36  {}
37 
38  void initialize(UAS &uas_) override
39  {
41 
42  esc_info_pub = nh.advertise<mavros_msgs::ESCInfo>("esc_info", 10);
43  esc_status_pub = nh.advertise<mavros_msgs::ESCStatus>("esc_status", 10);
44 
46  }
47 
49  {
50  return {
53  };
54  }
55 
56 private:
57  using lock_guard = std::lock_guard<std::mutex>;
59 
61 
64  mavros_msgs::ESCInfo _esc_info;
65  mavros_msgs::ESCStatus _esc_status;
66  uint8_t _max_esc_count;
69  const uint8_t batch_size = 4;
70 
71  void handle_esc_info(const mavlink::mavlink_message_t *msg, mavlink::common::msg::ESC_INFO &esc_info)
72  {
73  lock_guard lock(mutex);
74 
75  _esc_info.header.stamp = m_uas->synchronise_stamp(esc_info.time_usec);
76 
77  uint8_t esc_index = esc_info.index;
78 
79  _esc_info.counter = esc_info.counter;
80  _esc_info.count = esc_info.count;
81  _esc_info.connection_type = esc_info.connection_type;
82  _esc_info.info = esc_info.info;
83 
84  if (_esc_info.count > _max_esc_count)
85  {
86  _max_esc_count = _esc_info.count;
87  }
88 
89  if (_esc_info.esc_info.size() < _max_esc_count)
90  {
91  _esc_info.esc_info.resize(_max_esc_count);
92  }
93 
94  for (int i = 0; i < std::min<ssize_t>(batch_size, ssize_t(_max_esc_count) - esc_index); i++)
95  {
96  _esc_info.esc_info[esc_index + i].header = _esc_info.header;
97  _esc_info.esc_info[esc_index + i].failure_flags = esc_info.failure_flags[i];
98  _esc_info.esc_info[esc_index + i].error_count = esc_info.error_count[i];
99  _esc_info.esc_info[esc_index + i].temperature = esc_info.temperature[i] * 1E2;
100  }
101 
102  _max_esc_info_index = std::max(_max_esc_info_index, esc_info.index);
103 
104  if (_max_esc_info_index == esc_info.index)
105  {
107  }
108  }
109 
110  void handle_esc_status(const mavlink::mavlink_message_t *msg, mavlink::common::msg::ESC_STATUS &esc_status)
111  {
112  lock_guard lock(mutex);
113 
114  uint8_t esc_index = esc_status.index;
115 
116  if (_esc_status.esc_status.size() < _max_esc_count)
117  {
118  _esc_status.esc_status.resize(_max_esc_count);
119  }
120 
121  _esc_status.header.stamp = m_uas->synchronise_stamp(esc_status.time_usec);
122 
123  for (int i = 0; i < std::min<ssize_t>(batch_size, ssize_t(_max_esc_count) - esc_index); i++)
124  {
125  _esc_status.esc_status[esc_index + i].header = _esc_status.header;
126  _esc_status.esc_status[esc_index + i].rpm = esc_status.rpm[i];
127  _esc_status.esc_status[esc_index + i].voltage = esc_status.voltage[i];
128  _esc_status.esc_status[esc_index + i].current = esc_status.current[i];
129  }
130 
131  _max_esc_status_index = std::max(_max_esc_status_index, esc_status.index);
132 
133  if (_max_esc_status_index == esc_status.index)
134  {
136  }
137  }
138 
139  void connection_cb(bool connected) override
140  {
141  lock_guard lock(mutex);
142 
143  _max_esc_count = 0;
146  _esc_info.esc_info.resize(0);
147  _esc_status.esc_status.resize(0);
148  }
149 };
150 } // namespace extra_plugins
151 } // namespace mavros
152 
mavros::extra_plugins::ESCStatusPlugin::_max_esc_status_index
uint8_t _max_esc_status_index
Definition: esc_status.cpp:68
mavros::plugin::PluginBase::m_uas
UAS * m_uas
mavros::extra_plugins::ESCStatusPlugin::handle_esc_status
void handle_esc_status(const mavlink::mavlink_message_t *msg, mavlink::common::msg::ESC_STATUS &esc_status)
Definition: esc_status.cpp:110
mavros::plugin::PluginBase::Subscriptions
std::vector< HandlerInfo > Subscriptions
ros::Publisher
mavros::extra_plugins::ESCStatusPlugin::_max_esc_count
uint8_t _max_esc_count
Definition: esc_status.cpp:66
mavros::extra_plugins::ESCStatusPlugin::lock_guard
std::lock_guard< std::mutex > lock_guard
Definition: esc_status.cpp:57
mavros::extra_plugins::ESCStatusPlugin
ESC status plugin.
Definition: esc_status.cpp:28
mavros::plugin::PluginBase::PluginBase
PluginBase()
mavros::UAS
mutex
std::recursive_mutex mutex
mavros::extra_plugins::ESCStatusPlugin::_max_esc_info_index
uint8_t _max_esc_info_index
Definition: esc_status.cpp:67
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
connected
std::atomic< bool > connected
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
mavros_plugin.h
mavros::extra_plugins::ESCStatusPlugin::esc_status_pub
ros::Publisher esc_status_pub
Definition: esc_status.cpp:63
mavros::extra_plugins::ESCStatusPlugin::ESCStatusPlugin
ESCStatusPlugin()
Definition: esc_status.cpp:31
mavros::extra_plugins::ESCStatusPlugin::batch_size
const uint8_t batch_size
Definition: esc_status.cpp:69
mavros::extra_plugins::ESCStatusPlugin::handle_esc_info
void handle_esc_info(const mavlink::mavlink_message_t *msg, mavlink::common::msg::ESC_INFO &esc_info)
Definition: esc_status.cpp:71
mavros
mavros::extra_plugins::ESCStatusPlugin::esc_info_pub
ros::Publisher esc_info_pub
Definition: esc_status.cpp:62
initialize
virtual void initialize(UAS &uas)
mavros::plugin::PluginBase
mavros::UAS::synchronise_stamp
ros::Time synchronise_stamp(uint32_t time_boot_ms)
mavros::extra_plugins::ESCStatusPlugin::_esc_status
mavros_msgs::ESCStatus _esc_status
Definition: esc_status.cpp:65
class_list_macros.hpp
mavros::plugin::PluginBase::enable_connection_cb
void enable_connection_cb()
mavros::extra_plugins::ESCStatusPlugin::nh
ros::NodeHandle nh
Definition: esc_status.cpp:60
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))
mavros::extra_plugins::ESCStatusPlugin::get_subscriptions
Subscriptions get_subscriptions() override
Definition: esc_status.cpp:48
mavros::extra_plugins::ESCStatusPlugin::_esc_info
mavros_msgs::ESCInfo _esc_info
Definition: esc_status.cpp:64
mavros::extra_plugins::ESCStatusPlugin::connection_cb
void connection_cb(bool connected) override
Definition: esc_status.cpp:139
mavros::extra_plugins::ESCStatusPlugin::mutex
std::mutex mutex
Definition: esc_status.cpp:58
ros::NodeHandle
mavros::extra_plugins::ESCStatusPlugin::initialize
void initialize(UAS &uas_) override
Definition: esc_status.cpp:38


mavros_extras
Author(s): Vladimir Ermakov , Amilcar Lucas
autogenerated on Tue May 6 2025 02:34:08