19 #include <mavros_msgs/DebugValue.h>
23 namespace extra_plugins {
76 using DV = mavros_msgs::DebugValue;
78 std::string name = (dv.name ==
"") ?
"UNK" : dv.name;
80 std::ostringstream ss;
81 if (dv.type == DV::TYPE_NAMED_VALUE_INT) {
84 else if (dv.type == DV::TYPE_DEBUG_VECT) {
87 for (
auto v : dv.data) {
104 << dv.header.stamp <<
"\t"
106 << dv.index <<
"]\tvalue:"
118 void handle_debug(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::DEBUG &debug)
143 auto dv_msg = boost::make_shared<mavros_msgs::DebugValue>();
145 dv_msg->type = mavros_msgs::DebugValue::TYPE_DEBUG;
146 dv_msg->index = debug.ind;
147 dv_msg->array_id = -1;
148 dv_msg->value_float = debug.value;
172 auto dv_msg = boost::make_shared<mavros_msgs::DebugValue>();
174 dv_msg->type = mavros_msgs::DebugValue::TYPE_DEBUG_VECT;
176 dv_msg->array_id = -1;
178 dv_msg->data.resize(3);
179 dv_msg->data[0] = debug.x;
180 dv_msg->data[1] = debug.y;
181 dv_msg->data[2] = debug.z;
202 auto dv_msg = boost::make_shared<mavros_msgs::DebugValue>();
204 dv_msg->type = mavros_msgs::DebugValue::TYPE_DEBUG_FLOAT_ARRAY;
207 dv_msg->array_id = debug.array_id;
208 dv_msg->data.assign(debug.data.begin(), debug.data.end());
228 auto dv_msg = boost::make_shared<mavros_msgs::DebugValue>();
230 dv_msg->type = mavros_msgs::DebugValue::TYPE_NAMED_VALUE_FLOAT;
232 dv_msg->array_id = -1;
234 dv_msg->value_float = value.value;
253 auto dv_msg = boost::make_shared<mavros_msgs::DebugValue>();
255 dv_msg->type = mavros_msgs::DebugValue::TYPE_NAMED_VALUE_INT;
257 dv_msg->array_id = -1;
259 dv_msg->value_int = value.value;
275 case mavros_msgs::DebugValue::TYPE_DEBUG: {
276 mavlink::common::msg::DEBUG debug {};
278 debug.time_boot_ms = req->header.stamp.toNSec() / 1000000;
279 debug.ind = req->index;
280 debug.value = req->value_float;
285 case mavros_msgs::DebugValue::TYPE_DEBUG_VECT: {
286 mavlink::common::msg::DEBUG_VECT debug {};
288 debug.time_usec = req->header.stamp.toNSec() / 1000;
289 mavlink::set_string(debug.name, req->name);
294 debug.x = req->data[0];
295 debug.y = req->data[1];
296 debug.z = req->data[2];
302 case mavros_msgs::DebugValue::TYPE_DEBUG_FLOAT_ARRAY: {
303 mavlink::common::msg::DEBUG_FLOAT_ARRAY debug {};
305 debug.time_usec = req->header.stamp.toNSec() / 1000;
306 mavlink::set_string(debug.name, req->name);
307 std::copy_n(req->data.begin(), std::min(req->data.size(), debug.data.size()), std::begin(debug.data));
312 case mavros_msgs::DebugValue::TYPE_NAMED_VALUE_FLOAT: {
313 mavlink::common::msg::NAMED_VALUE_FLOAT value {};
315 value.time_boot_ms = req->header.stamp.toNSec() / 1000000;
316 mavlink::set_string(value.name, req->name);
317 value.value = req->value_float;
322 case mavros_msgs::DebugValue::TYPE_NAMED_VALUE_INT: {
323 mavlink::common::msg::NAMED_VALUE_INT value {};
325 value.time_boot_ms = req->header.stamp.toNSec() / 1000000;
326 mavlink::set_string(value.name, req->name);
327 value.value = req->value_int;
333 ROS_ERROR_NAMED(
"debug",
"Wrong debug type (%d). Droping!...", req->type);