19 #include <mavros_msgs/DebugValue.h> 22 namespace extra_plugins {
72 using DV = mavros_msgs::DebugValue;
74 std::string
name = (dv.name ==
"") ?
"UNK" : dv.name;
76 std::ostringstream ss;
77 if (dv.type == DV::TYPE_NAMED_VALUE_INT) {
80 else if (dv.type == DV::TYPE_DEBUG_VECT) {
83 for (
auto v : dv.data) {
100 << dv.header.stamp <<
"\t" 102 << dv.index <<
"]\tvalue:" 114 void handle_debug(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::DEBUG &debug)
137 auto dv_msg = boost::make_shared<mavros_msgs::DebugValue>();
139 dv_msg->type = mavros_msgs::DebugValue::TYPE_DEBUG;
140 dv_msg->index = debug.ind;
141 dv_msg->value_float = debug.value;
165 auto dv_msg = boost::make_shared<mavros_msgs::DebugValue>();
167 dv_msg->type = mavros_msgs::DebugValue::TYPE_DEBUG_VECT;
170 dv_msg->data.resize(3);
171 dv_msg->data[0] = debug.x;
172 dv_msg->data[1] = debug.y;
173 dv_msg->data[2] = debug.z;
177 debug_vector_pub.
publish(dv_msg);
197 auto dv_msg = boost::make_shared<mavros_msgs::DebugValue>();
199 dv_msg->type = mavros_msgs::DebugValue::TYPE_NAMED_VALUE_FLOAT;
202 dv_msg->value_float = value.value;
206 named_value_float_pub.
publish(dv_msg);
221 auto dv_msg = boost::make_shared<mavros_msgs::DebugValue>();
223 dv_msg->type = mavros_msgs::DebugValue::TYPE_NAMED_VALUE_INT;
226 dv_msg->value_int = value.value;
230 named_value_int_pub.
publish(dv_msg);
242 case mavros_msgs::DebugValue::TYPE_DEBUG: {
243 mavlink::common::msg::DEBUG debug {};
245 debug.time_boot_ms = req->header.stamp.toNSec() / 1000000;
246 debug.ind = req->index;
247 debug.value = req->value_float;
252 case mavros_msgs::DebugValue::TYPE_DEBUG_VECT: {
253 mavlink::common::msg::DEBUG_VECT debug {};
255 debug.time_usec = req->header.stamp.toNSec() / 1000;
261 debug.x = req->data[0];
262 debug.y = req->data[1];
263 debug.z = req->data[2];
272 case mavros_msgs::DebugValue::TYPE_NAMED_VALUE_FLOAT: {
273 mavlink::common::msg::NAMED_VALUE_FLOAT value {};
275 value.time_boot_ms = req->header.stamp.toNSec() / 1000000;
277 value.value = req->value_float;
282 case mavros_msgs::DebugValue::TYPE_NAMED_VALUE_INT: {
283 mavlink::common::msg::NAMED_VALUE_INT value {};
285 value.time_boot_ms = req->header.stamp.toNSec() / 1000000;
287 value.value = req->value_int;
293 ROS_ERROR_NAMED(
"debug",
"Wrong debug type (%d). Droping!...", req->type);
std::shared_ptr< MAVConnInterface const > ConstPtr
#define ROS_DEBUG_STREAM_NAMED(name, args)
Subscriptions get_subscriptions()
void publish(const boost::shared_ptr< M > &message) const
void debug_cb(const mavros_msgs::DebugValue::ConstPtr &req)
Debug callbacks.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
ros::Publisher named_value_float_pub
void initialize(UAS &uas_)
void debug_logger(const std::string &type, const mavros_msgs::DebugValue &dv)
Helper function to log debug messages.
std::atomic< uint8_t > type
#define UAS_FCU(uasobjptr)
ros::Time synchronise_stamp(uint32_t time_boot_ms)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void handle_named_value_float(const mavlink::mavlink_message_t *msg, mavlink::common::msg::NAMED_VALUE_FLOAT &value)
Handle NAMED_VALUE_FLOAT message. Message specification: https://mavlink.io/en/messages/common.html#NAMED_VALUE_FLOAT.
ros::Publisher named_value_int_pub
void handle_debug_vector(const mavlink::mavlink_message_t *msg, mavlink::common::msg::DEBUG_VECT &debug)
Handle DEBUG_VECT message. Message specification: https://mavlink.io/en/messages/common.html#DEBUG_VECT.
std::vector< HandlerInfo > Subscriptions
void initialize(UAS &uas_)
void set_string(std::array< char, _N > &a, const std::string &s)
ros::Subscriber debug_sub
#define ROS_ERROR_NAMED(name,...)
void handle_debug(const mavlink::mavlink_message_t *msg, mavlink::common::msg::DEBUG &debug)
Handle DEBUG message. Message specification: https://mavlink.io/en/messages/common.html#DEBUG.
ros::Publisher debug_vector_pub
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void handle_named_value_int(const mavlink::mavlink_message_t *msg, mavlink::common::msg::NAMED_VALUE_INT &value)
Handle NAMED_VALUE_INT message. Message specification: https://mavlink.io/en/messages/common.html#NAMED_VALUE_INT.
std::string to_string(const std::array< char, _N > &a)