distance_sensor.cpp
Go to the documentation of this file.
1 
9 /*
10  * Copyright 2015 Nuno Marques.
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 #include <unordered_map>
17 #include <mavros/utils.h>
18 #include <mavros/mavros_plugin.h>
20 
21 #include <sensor_msgs/Range.h>
22 
23 namespace mavros {
24 namespace extra_plugins {
25 using utils::enum_value;
26 class DistanceSensorPlugin;
27 
32 public:
34 
35  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
36 
38  is_subscriber(false),
39  send_tf(false),
40  sensor_id(0),
41  field_of_view(0),
42  orientation(-1),
43  covariance(0),
45  vertical_fov_ratio(1.0),
46  quaternion(0.f, 0.f, 0.f, 0.f),
47  owner(nullptr),
48  data_index(0)
49  { }
50 
51  // params
53  bool send_tf;
54  uint8_t sensor_id;
55  double field_of_view;
56  Eigen::Vector3d position;
58  int covariance;
59  std::string frame_id;
62  Eigen::Quaternionf quaternion;
63 
64  // topic handle
67  std::string topic_name;
68 
70 
71  void range_cb(const sensor_msgs::Range::ConstPtr &msg);
72  static Ptr create_item(DistanceSensorPlugin *owner, std::string topic_name);
73 
74 private:
75  std::vector<float> data;
76  size_t data_index;
77 
78  static constexpr size_t ACC_SIZE = 50;
79 
83  float calculate_variance(float range) {
84  if (data.size() < ACC_SIZE) {
85  // limits the size of the array to 50 elements
86  data.reserve(ACC_SIZE);
87  data.push_back(range);
88  }
89  else {
90  data[data_index] = range; // it starts rewriting the values from 1st element
91  if (++data_index > ACC_SIZE - 1)
92  data_index = 0; // restarts the index when achieves the last element
93  }
94 
95  float average, variance, sum = 0, sum_ = 0;
96 
97  /* Compute the sum of all elements */
98  for (auto d : data)
99  sum += d;
100 
101  average = sum / data.size();
102 
103  /* Compute the variance */
104  for (auto d : data)
105  sum_ += (d - average) * (d - average);
106 
107  variance = sum_ / data.size();
108 
109  return variance;
110  }
111 };
112 
120 public:
122  dist_nh("~distance_sensor")
123  { }
124 
125  void initialize(UAS &uas_) override
126  {
128 
129  dist_nh.param<std::string>("base_frame_id", base_frame_id, "base_link");
130 
131  XmlRpc::XmlRpcValue map_dict;
132  if (!dist_nh.getParam("", map_dict)) {
133  ROS_WARN_NAMED("distance_sensor", "DS: plugin not configured!");
134  return;
135  }
136 
137  ROS_ASSERT(map_dict.getType() == XmlRpc::XmlRpcValue::TypeStruct);
138 
139  for (auto &pair : map_dict) {
140  ROS_DEBUG_NAMED("distance_sensor", "DS: initializing mapping for %s", pair.first.c_str());
141  auto it = DistanceSensorItem::create_item(this, pair.first);
142 
143  if (it)
144  sensor_map[it->sensor_id] = it;
145  else
146  ROS_ERROR_NAMED("distance_sensor", "DS: bad config for %s", pair.first.c_str());
147  }
148  }
149 
151  {
152  return {
154  };
155  }
156 
157 private:
158  friend class DistanceSensorItem;
159 
161 
162  std::string base_frame_id;
163 
164  std::unordered_map<uint8_t, DistanceSensorItem::Ptr> sensor_map;
165 
166  /* -*- low-level send -*- */
167  void distance_sensor(uint32_t time_boot_ms,
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)
175  {
176  mavlink::common::msg::DISTANCE_SENSOR ds = {};
177 
178  // [[[cog:
179  // for f in ('time_boot_ms',
180  // 'min_distance',
181  // 'max_distance',
182  // 'current_distance',
183  // 'type',
184  // 'id',
185  // 'orientation',
186  // 'covariance',
187  // 'horizontal_fov',
188  // 'vertical_fov',
189  // 'quaternion'):
190  // cog.outl("ds.%s = %s;" % (f, f))
191  // ]]]
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;
196  ds.type = type;
197  ds.id = id;
198  ds.orientation = orientation;
199  ds.covariance = covariance;
200  ds.horizontal_fov = horizontal_fov;
201  ds.vertical_fov = vertical_fov;
202  ds.quaternion = quaternion;
203  // [[[end]]] (checksum: 23b6c8fb20bd494eafdf08d5888c9c76)
204 
205  UAS_FCU(m_uas)->send_message_ignore_drop(ds);
206  }
207 
208  /* -*- mid-level helpers -*- */
209 
213  void handle_distance_sensor(const mavlink::mavlink_message_t *msg, mavlink::common::msg::DISTANCE_SENSOR &dist_sen)
214  {
215  using mavlink::common::MAV_SENSOR_ORIENTATION;
216  using mavlink::common::MAV_DISTANCE_SENSOR;
217 
218  auto it = sensor_map.find(dist_sen.id);
219  if (it == sensor_map.end()) {
220  ROS_ERROR_NAMED("distance_sensor",
221  "DS: no mapping for sensor id: %d, type: %d, orientation: %d",
222  dist_sen.id, dist_sen.type, dist_sen.orientation);
223  return;
224  }
225 
226  auto sensor = it->second;
227  if (sensor->is_subscriber) {
228  ROS_ERROR_ONCE_NAMED("distance_sensor",
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);
231 
232  return;
233  }
234 
235  if (sensor->orientation >= 0 && dist_sen.orientation != sensor->orientation) {
236  ROS_ERROR_NAMED("distance_sensor",
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());
241  return;
242  }
243 
244  auto range = boost::make_shared<sensor_msgs::Range>();
245 
246  range->header = m_uas->synchronized_header(sensor->frame_id, dist_sen.time_boot_ms);
247 
248  range->min_range = dist_sen.min_distance * 1E-2;// in meters
249  range->max_range = dist_sen.max_distance * 1E-2;
250  range->field_of_view = sensor->field_of_view;
251 
252  switch (dist_sen.type) {
253  case enum_value(MAV_DISTANCE_SENSOR::LASER):
254  case enum_value(MAV_DISTANCE_SENSOR::RADAR):
255  case enum_value(MAV_DISTANCE_SENSOR::UNKNOWN):
256  range->radiation_type = sensor_msgs::Range::INFRARED;
257  break;
258  case enum_value(MAV_DISTANCE_SENSOR::ULTRASOUND):
259  range->radiation_type = sensor_msgs::Range::ULTRASOUND;
260  break;
261  default:
262  ROS_ERROR_NAMED("distance_sensor",
263  "DS: %s: Wrong/undefined type of sensor (type: %d). Droping!...",
264  sensor->topic_name.c_str(), dist_sen.type);
265  return;
266  }
267 
268  range->range = dist_sen.current_distance * 1E-2; // in meters
269 
270  if (sensor->send_tf) {
271  /* variables init */
272  auto q = utils::sensor_orientation_matching(static_cast<MAV_SENSOR_ORIENTATION>(dist_sen.orientation));
273 
274  geometry_msgs::TransformStamped transform;
275 
276  transform.header = m_uas->synchronized_header(base_frame_id, dist_sen.time_boot_ms);
277  transform.child_frame_id = sensor->frame_id;
278 
279  /* rotation and position set */
280  tf::quaternionEigenToMsg(q, transform.transform.rotation);
281  tf::vectorEigenToMsg(sensor->position, transform.transform.translation);
282 
283  /* transform broadcast */
285  }
286 
287  sensor->pub.publish(range);
288  }
289 };
290 
292 {
293  using mavlink::common::MAV_DISTANCE_SENSOR;
294 
295  uint8_t type = 0;
296  uint8_t covariance_ = 0;
297 
298  if (covariance > 0) covariance_ = covariance;
299  else covariance_ = uint8_t(calculate_variance(msg->range) * 1E2); // in cm
300 
302  ROS_DEBUG_NAMED("distance_sensor", "DS: %d: sensor variance: %f", sensor_id, calculate_variance(msg->range) * 1E2);
303 
304  // current mapping, may change later
305  if (msg->radiation_type == sensor_msgs::Range::INFRARED)
306  type = enum_value(MAV_DISTANCE_SENSOR::LASER);
307  else if (msg->radiation_type == sensor_msgs::Range::ULTRASOUND)
308  type = enum_value(MAV_DISTANCE_SENSOR::ULTRASOUND);
309 
310  std::array<float, 4> q;
312 
314  msg->header.stamp.toNSec() / 1000000,
315  msg->min_range / 1E-2,
316  msg->max_range / 1E-2,
317  msg->range / 1E-2,
318  type,
319  sensor_id,
320  orientation,
321  covariance_,
322  msg->field_of_view * horizontal_fov_ratio,
323  msg->field_of_view * vertical_fov_ratio,
324  q);
325 }
326 
328 {
329  auto p = boost::make_shared<DistanceSensorItem>();
330  std::string orientation_str;
331 
333 
334  p->owner = owner;
335  p->topic_name = topic_name;
336 
337  // load and parse params
338  // first decide the type of topic (sub or pub)
339  pnh.param("subscriber", p->is_subscriber, false);
340 
341  // sensor id
342  int id;
343  if (!pnh.getParam("id", id)) {
344  ROS_ERROR_NAMED("distance_sensor", "DS: %s: `id` not set!", topic_name.c_str());
345  p.reset(); return p; // return nullptr because of a bug related to gcc 4.6
346  }
347  p->sensor_id = id;
348 
349  // orientation, checks later
350  if (!pnh.getParam("orientation", orientation_str))
351  p->orientation = -1; // not set
352  else
353  // lookup for numeric value
354  p->orientation = utils::sensor_orientation_from_str(orientation_str);
355 
356 
357  if (!p->is_subscriber) {
358  // publisher params
359  // frame_id and FOV is required
360  if (!pnh.getParam("frame_id", p->frame_id)) {
361  ROS_ERROR_NAMED("distance_sensor", "DS: %s: `frame_id` not set!", topic_name.c_str());
362  p.reset(); return p; // nullptr
363  }
364 
365  if (!pnh.getParam("field_of_view", p->field_of_view)) {
366  ROS_ERROR_NAMED("distance_sensor", "DS: %s: sensor FOV not set!", topic_name.c_str());
367  p.reset(); return p; // nullptr
368  }
369 
370  // unset allowed, setted wrong - not
371  if (p->orientation == -1 && !orientation_str.empty()) {
372  ROS_ERROR_NAMED("distance_sensor", "DS: %s: defined orientation (%s) is not valid!",
373  topic_name.c_str(), orientation_str.c_str());
374  p.reset(); return p; // nullptr
375  }
376 
377  // optional
378  pnh.param("send_tf", p->send_tf, false);
379  if (p->send_tf) { // sensor position defined if 'send_tf' set to TRUE
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);
383  ROS_DEBUG_NAMED("sensor_position", "DS: %s: Sensor position at: %f, %f, %f", topic_name.c_str(),
384  p->position.x(), p->position.y(), p->position.z());
385  }
386  }
387  else {
388  // subscriber params
389  // orientation is required
390  if (orientation_str.empty()) {
391  ROS_ERROR_NAMED("distance_sensor", "DS: %s: orientation not set!", topic_name.c_str());
392  p.reset(); return p; // nullptr
393  }
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());
396  p.reset(); return p; // nullptr
397  }
398 
399  // optional
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)) {
404  Eigen::Vector3d rpy;
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);
409  p->quaternion = Eigen::Quaternionf(ftf::quaternion_from_rpy(rpy * DEG_TO_RAD));
410  }
411  }
412 
413  // create topic handles
414  if (!p->is_subscriber)
415  p->pub = owner->dist_nh.advertise<sensor_msgs::Range>(topic_name, 10);
416  else
418 
419  return p;
420 }
421 } // namespace extra_plugins
422 } // namespace mavros
423 
mavros::plugin::PluginBase::m_uas
UAS * m_uas
mavros::extra_plugins::DistanceSensorPlugin
Distance sensor plugin.
Definition: distance_sensor.cpp:119
mavros::UAS::tf2_broadcaster
tf2_ros::TransformBroadcaster tf2_broadcaster
mavros::plugin::PluginBase::Subscriptions
std::vector< HandlerInfo > Subscriptions
msg
msg
ros::Publisher
mavros::extra_plugins::DistanceSensorPlugin::handle_distance_sensor
void handle_distance_sensor(const mavlink::mavlink_message_t *msg, mavlink::common::msg::DISTANCE_SENSOR &dist_sen)
Definition: distance_sensor.cpp:213
boost::shared_ptr
mavros::extra_plugins::DistanceSensorItem::field_of_view
double field_of_view
FOV of the sensor.
Definition: distance_sensor.cpp:55
mavros::extra_plugins::DistanceSensorItem::owner
DistanceSensorPlugin * owner
Definition: distance_sensor.cpp:69
mavros::utils::sensor_orientation_matching
Eigen::Quaterniond sensor_orientation_matching(MAV_SENSOR_ORIENTATION orientation)
utils.h
mavros::plugin::PluginBase::PluginBase
PluginBase()
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
UAS_FCU
#define UAS_FCU(uasobjptr)
mavros::UAS
mavros::extra_plugins::DistanceSensorItem::ACC_SIZE
static constexpr size_t ACC_SIZE
Definition: distance_sensor.cpp:78
ConstPtr
std::shared_ptr< MAVConnInterface const > ConstPtr
transform
ftf::StaticTF transform
type
std::atomic< uint8_t > type
mavros::extra_plugins::DistanceSensorItem::sensor_id
uint8_t sensor_id
id of the sensor
Definition: distance_sensor.cpp:54
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
mavros::extra_plugins::DistanceSensorItem::data_index
size_t data_index
array index
Definition: distance_sensor.cpp:76
mavros::extra_plugins::DistanceSensorItem::vertical_fov_ratio
double vertical_fov_ratio
vertical fov ratio for ROS messages
Definition: distance_sensor.cpp:61
mavros::extra_plugins::DistanceSensorItem::calculate_variance
float calculate_variance(float range)
Definition: distance_sensor.cpp:83
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ROS_ERROR_ONCE_NAMED
#define ROS_ERROR_ONCE_NAMED(name,...)
XmlRpc::XmlRpcValue::TypeStruct
TypeStruct
f
f
mavros::extra_plugins::DistanceSensorItem::DistanceSensorItem
EIGEN_MAKE_ALIGNED_OPERATOR_NEW DistanceSensorItem()
Definition: distance_sensor.cpp:37
tf::vectorEigenToMsg
void vectorEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Vector3 &m)
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
tf2_ros::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
mavros_plugin.h
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
mavros::extra_plugins::DistanceSensorItem::create_item
static Ptr create_item(DistanceSensorPlugin *owner, std::string topic_name)
Definition: distance_sensor.cpp:327
eigen_msg.h
mavros::extra_plugins::DistanceSensorItem::pub
ros::Publisher pub
Definition: distance_sensor.cpp:65
mavros::extra_plugins::DistanceSensorItem::data
std::vector< float > data
array allocation for measurements
Definition: distance_sensor.cpp:75
d
d
mavros::extra_plugins::DistanceSensorPlugin::base_frame_id
std::string base_frame_id
Definition: distance_sensor.cpp:162
mavros::extra_plugins::DistanceSensorItem
Distance sensor mapping storage item.
Definition: distance_sensor.cpp:31
mavros::extra_plugins::DistanceSensorItem::covariance
int covariance
in centimeters, current specification
Definition: distance_sensor.cpp:58
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
mavros::extra_plugins::DistanceSensorItem::position
Eigen::Vector3d position
sensor position
Definition: distance_sensor.cpp:56
mavros::extra_plugins::DistanceSensorPlugin::sensor_map
std::unordered_map< uint8_t, DistanceSensorItem::Ptr > sensor_map
Definition: distance_sensor.cpp:164
mavros
mavros::extra_plugins::DistanceSensorItem::Ptr
boost::shared_ptr< DistanceSensorItem > Ptr
Definition: distance_sensor.cpp:33
mavros::utils::sensor_orientation_from_str
int sensor_orientation_from_str(const std::string &sensor_orientation)
mavros::UAS::synchronized_header
std_msgs::Header synchronized_header(const std::string &frame_id, const T time_stamp)
tf::quaternionEigenToMsg
void quaternionEigenToMsg(const Eigen::Quaterniond &e, geometry_msgs::Quaternion &m)
initialize
virtual void initialize(UAS &uas)
mavros::plugin::PluginBase
mavros::extra_plugins::DistanceSensorPlugin::get_subscriptions
Subscriptions get_subscriptions() override
Definition: distance_sensor.cpp:150
class_list_macros.hpp
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
mavros::extra_plugins::DistanceSensorItem::topic_name
std::string topic_name
Definition: distance_sensor.cpp:67
mavros::extra_plugins::DistanceSensorPlugin::distance_sensor
void distance_sensor(uint32_t time_boot_ms, uint32_t min_distance, uint32_t max_distance, uint32_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance, float horizontal_fov, float vertical_fov, std::array< float, 4 > quaternion)
Definition: distance_sensor.cpp:167
mavros::extra_plugins::DistanceSensorItem::is_subscriber
bool is_subscriber
this item is a subscriber, else is a publisher
Definition: distance_sensor.cpp:52
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
mavros::extra_plugins::DistanceSensorItem::sub
ros::Subscriber sub
Definition: distance_sensor.cpp:66
mavros::extra_plugins::DistanceSensorPlugin::initialize
void initialize(UAS &uas_) override
Definition: distance_sensor.cpp:125
mavros::extra_plugins::DistanceSensorItem::quaternion
Eigen::Quaternionf quaternion
sensor orientation in vehicle body frame for MAV_SENSOR_ROTATION_CUSTOM
Definition: distance_sensor.cpp:62
mavros::extra_plugins::DistanceSensorItem::horizontal_fov_ratio
double horizontal_fov_ratio
horizontal fov ratio for ROS messages
Definition: distance_sensor.cpp:60
mavros::ftf::quaternion_from_rpy
Eigen::Quaterniond quaternion_from_rpy(const double roll, const double pitch, const double yaw)
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::DistanceSensorItem::send_tf
bool send_tf
defines if a transform is sent or not
Definition: distance_sensor.cpp:53
ROS_ASSERT
#define ROS_ASSERT(cond)
mavros::extra_plugins::DistanceSensorItem::range_cb
void range_cb(const sensor_msgs::Range::ConstPtr &msg)
Definition: distance_sensor.cpp:291
mavros::utils::enum_value
constexpr std::underlying_type< _T >::type enum_value(_T e)
mavros::extra_plugins::DistanceSensorPlugin::DistanceSensorPlugin
DistanceSensorPlugin()
Definition: distance_sensor.cpp:121
mavros::extra_plugins::DistanceSensorItem::orientation
int orientation
check orientation of sensor if != -1
Definition: distance_sensor.cpp:57
XmlRpc::XmlRpcValue
mavros::extra_plugins::DistanceSensorItem::frame_id
std::string frame_id
frame id for send
Definition: distance_sensor.cpp:59
ros::NodeHandle
ros::Subscriber
mavros::ftf::quaternion_to_mavlink
void quaternion_to_mavlink(const Eigen::Quaternion< _Scalar > &q, std::array< float, 4 > &qmsg)
mavros::extra_plugins::DistanceSensorPlugin::dist_nh
ros::NodeHandle dist_nh
Definition: distance_sensor.cpp:160


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