16 #include <unordered_map>
21 #include <sensor_msgs/Range.h>
24 namespace extra_plugins {
26 class DistanceSensorPlugin;
35 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
87 data.push_back(range);
95 float average, variance, sum = 0, sum_ = 0;
101 average = sum /
data.size();
105 sum_ += (
d - average) * (
d - average);
107 variance = sum_ /
data.size();
139 for (
auto &pair : map_dict) {
140 ROS_DEBUG_NAMED(
"distance_sensor",
"DS: initializing mapping for %s", pair.first.c_str());
146 ROS_ERROR_NAMED(
"distance_sensor",
"DS: bad config for %s", pair.first.c_str());
164 std::unordered_map<uint8_t, DistanceSensorItem::Ptr>
sensor_map;
168 uint32_t min_distance,
169 uint32_t max_distance,
170 uint32_t current_distance,
171 uint8_t
type, uint8_t
id,
172 uint8_t orientation, uint8_t covariance,
173 float horizontal_fov,
float vertical_fov,
174 std::array<float, 4> quaternion)
176 mavlink::common::msg::DISTANCE_SENSOR ds = {};
192 ds.time_boot_ms = time_boot_ms;
193 ds.min_distance = min_distance;
194 ds.max_distance = max_distance;
195 ds.current_distance = current_distance;
198 ds.orientation = orientation;
199 ds.covariance = covariance;
200 ds.horizontal_fov = horizontal_fov;
201 ds.vertical_fov = vertical_fov;
202 ds.quaternion = quaternion;
215 using mavlink::common::MAV_SENSOR_ORIENTATION;
216 using mavlink::common::MAV_DISTANCE_SENSOR;
221 "DS: no mapping for sensor id: %d, type: %d, orientation: %d",
222 dist_sen.id, dist_sen.type, dist_sen.orientation);
226 auto sensor = it->second;
227 if (sensor->is_subscriber) {
229 "DS: %s (id %d) is subscriber, but i got sensor data for that id from FCU",
230 sensor->topic_name.c_str(), sensor->sensor_id);
235 if (sensor->orientation >= 0 && dist_sen.orientation != sensor->orientation) {
237 "DS: %s: received sensor data has different orientation (%s) than in config (%s)!",
238 sensor->topic_name.c_str(),
239 utils::to_string_enum<MAV_SENSOR_ORIENTATION>(dist_sen.orientation).c_str(),
240 utils::to_string_enum<MAV_SENSOR_ORIENTATION>(sensor->orientation).c_str());
244 auto range = boost::make_shared<sensor_msgs::Range>();
248 range->min_range = dist_sen.min_distance * 1E-2;
249 range->max_range = dist_sen.max_distance * 1E-2;
250 range->field_of_view = sensor->field_of_view;
252 switch (dist_sen.type) {
255 case enum_value(MAV_DISTANCE_SENSOR::UNKNOWN):
256 range->radiation_type = sensor_msgs::Range::INFRARED;
258 case enum_value(MAV_DISTANCE_SENSOR::ULTRASOUND):
259 range->radiation_type = sensor_msgs::Range::ULTRASOUND;
263 "DS: %s: Wrong/undefined type of sensor (type: %d). Droping!...",
264 sensor->topic_name.c_str(), dist_sen.type);
268 range->range = dist_sen.current_distance * 1E-2;
270 if (sensor->send_tf) {
274 geometry_msgs::TransformStamped
transform;
277 transform.child_frame_id = sensor->frame_id;
287 sensor->pub.publish(range);
293 using mavlink::common::MAV_DISTANCE_SENSOR;
296 uint8_t covariance_ = 0;
305 if (
msg->radiation_type == sensor_msgs::Range::INFRARED)
307 else if (
msg->radiation_type == sensor_msgs::Range::ULTRASOUND)
310 std::array<float, 4> q;
314 msg->header.stamp.toNSec() / 1000000,
315 msg->min_range / 1E-2,
316 msg->max_range / 1E-2,
329 auto p = boost::make_shared<DistanceSensorItem>();
330 std::string orientation_str;
339 pnh.
param(
"subscriber", p->is_subscriber,
false);
350 if (!pnh.
getParam(
"orientation", orientation_str))
357 if (!p->is_subscriber) {
360 if (!pnh.
getParam(
"frame_id", p->frame_id)) {
365 if (!pnh.
getParam(
"field_of_view", p->field_of_view)) {
371 if (p->orientation == -1 && !orientation_str.empty()) {
372 ROS_ERROR_NAMED(
"distance_sensor",
"DS: %s: defined orientation (%s) is not valid!",
378 pnh.
param(
"send_tf", p->send_tf,
false);
380 pnh.
param(
"sensor_position/x", p->position.x(), 0.0);
381 pnh.
param(
"sensor_position/y", p->position.y(), 0.0);
382 pnh.
param(
"sensor_position/z", p->position.z(), 0.0);
384 p->position.x(), p->position.y(), p->position.z());
390 if (orientation_str.empty()) {
394 else if (p->orientation == -1) {
395 ROS_ERROR_NAMED(
"distance_sensor",
"DS: %s: defined orientation (%s) is not valid!",
topic_name.c_str(), orientation_str.c_str());
400 pnh.
param(
"covariance", p->covariance, 0);
401 pnh.
param(
"horizontal_fov_ratio", p->horizontal_fov_ratio, 1.0);
402 pnh.
param(
"vertical_fov_ratio", p->vertical_fov_ratio, 1.0);
403 if (p->orientation ==
enum_value(mavlink::common::MAV_SENSOR_ORIENTATION::ROTATION_CUSTOM)) {
405 pnh.
param(
"custom_orientation/roll", rpy.x(), 0.0);
406 pnh.
param(
"custom_orientation/pitch", rpy.y(), 0.0);
407 pnh.
param(
"custom_orientation/yaw", rpy.z(), 0.0);
408 constexpr
auto DEG_TO_RAD = (M_PI / 180.0);
414 if (!p->is_subscriber)