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),
44  owner(nullptr),
45  data_index(0)
46  { }
47 
48  // params
50  bool send_tf;
51  uint8_t sensor_id;
52  double field_of_view;
53  Eigen::Vector3d position;
55  int covariance;
56  std::string frame_id;
57 
58  // topic handle
61  std::string topic_name;
62 
64 
65  void range_cb(const sensor_msgs::Range::ConstPtr &msg);
66  static Ptr create_item(DistanceSensorPlugin *owner, std::string topic_name);
67 
68 private:
69  std::vector<float> data;
70  size_t data_index;
71 
72  static constexpr size_t ACC_SIZE = 50;
73 
77  float calculate_variance(float range) {
78  if (data.size() < ACC_SIZE) {
79  // limits the size of the array to 50 elements
80  data.reserve(ACC_SIZE);
81  data.push_back(range);
82  }
83  else {
84  data[data_index] = range; // it starts rewriting the values from 1st element
85  if (++data_index > ACC_SIZE - 1)
86  data_index = 0; // restarts the index when achieves the last element
87  }
88 
89  float average, variance, sum = 0, sum_ = 0;
90 
91  /* Compute the sum of all elements */
92  for (auto d : data)
93  sum += d;
94 
95  average = sum / data.size();
96 
97  /* Compute the variance */
98  for (auto d : data)
99  sum_ += (d - average) * (d - average);
100 
101  variance = sum_ / data.size();
102 
103  return variance;
104  }
105 };
106 
114 public:
116  dist_nh("~distance_sensor")
117  { }
118 
119  void initialize(UAS &uas_)
120  {
122 
123  dist_nh.param<std::string>("base_frame_id", base_frame_id, "base_link");
124 
125  XmlRpc::XmlRpcValue map_dict;
126  if (!dist_nh.getParam("", map_dict)) {
127  ROS_WARN_NAMED("distance_sensor", "DS: plugin not configured!");
128  return;
129  }
130 
131  ROS_ASSERT(map_dict.getType() == XmlRpc::XmlRpcValue::TypeStruct);
132 
133  for (auto &pair : map_dict) {
134  ROS_DEBUG_NAMED("distance_sensor", "DS: initializing mapping for %s", pair.first.c_str());
135  auto it = DistanceSensorItem::create_item(this, pair.first);
136 
137  if (it)
138  sensor_map[it->sensor_id] = it;
139  else
140  ROS_ERROR_NAMED("distance_sensor", "DS: bad config for %s", pair.first.c_str());
141  }
142  }
143 
145  {
146  return {
148  };
149  }
150 
151 private:
152  friend class DistanceSensorItem;
153 
155 
156  std::string base_frame_id;
157 
158  std::unordered_map<uint8_t, DistanceSensorItem::Ptr> sensor_map;
159 
160  /* -*- low-level send -*- */
161  void distance_sensor(uint32_t time_boot_ms,
162  uint32_t min_distance,
163  uint32_t max_distance,
164  uint32_t current_distance,
165  uint8_t type, uint8_t id,
166  uint8_t orientation, uint8_t covariance)
167  {
168  mavlink::common::msg::DISTANCE_SENSOR ds;
169 
170  // [[[cog:
171  // for f in ('time_boot_ms',
172  // 'min_distance',
173  // 'max_distance',
174  // 'current_distance',
175  // 'type',
176  // 'id',
177  // 'orientation',
178  // 'covariance'):
179  // cog.outl("ds.%s = %s;" % (f, f))
180  // ]]]
181  ds.time_boot_ms = time_boot_ms;
182  ds.min_distance = min_distance;
183  ds.max_distance = max_distance;
184  ds.current_distance = current_distance;
185  ds.type = type;
186  ds.id = id;
187  ds.orientation = orientation;
188  ds.covariance = covariance;
189  // [[[end]]] (checksum: 6f6f9449d926ab618a3293e2091c7035)
190 
191  UAS_FCU(m_uas)->send_message_ignore_drop(ds);
192  }
193 
194  /* -*- mid-level helpers -*- */
195 
199  void handle_distance_sensor(const mavlink::mavlink_message_t *msg, mavlink::common::msg::DISTANCE_SENSOR &dist_sen)
200  {
201  using mavlink::common::MAV_SENSOR_ORIENTATION;
202  using mavlink::common::MAV_DISTANCE_SENSOR;
203 
204  auto it = sensor_map.find(dist_sen.id);
205  if (it == sensor_map.end()) {
206  ROS_ERROR_NAMED("distance_sensor",
207  "DS: no mapping for sensor id: %d, type: %d, orientation: %d",
208  dist_sen.id, dist_sen.type, dist_sen.orientation);
209  return;
210  }
211 
212  auto sensor = it->second;
213  if (sensor->is_subscriber) {
214  ROS_ERROR_ONCE_NAMED("distance_sensor",
215  "DS: %s (id %d) is subscriber, but i got sensor data for that id from FCU",
216  sensor->topic_name.c_str(), sensor->sensor_id);
217 
218  return;
219  }
220 
221  if (sensor->orientation >= 0 && dist_sen.orientation != sensor->orientation) {
222  ROS_ERROR_NAMED("distance_sensor",
223  "DS: %s: received sensor data has different orientation (%s) than in config (%s)!",
224  sensor->topic_name.c_str(),
225  utils::to_string_enum<MAV_SENSOR_ORIENTATION>(dist_sen.orientation).c_str(),
226  utils::to_string_enum<MAV_SENSOR_ORIENTATION>(sensor->orientation).c_str());
227  }
228 
229  auto range = boost::make_shared<sensor_msgs::Range>();
230 
231  range->header = m_uas->synchronized_header(sensor->frame_id, dist_sen.time_boot_ms);
232 
233  range->min_range = dist_sen.min_distance * 1E-2;// in meters
234  range->max_range = dist_sen.max_distance * 1E-2;
235  range->field_of_view = sensor->field_of_view;
236 
237  switch (dist_sen.type) {
238  case enum_value(MAV_DISTANCE_SENSOR::LASER):
239  case enum_value(MAV_DISTANCE_SENSOR::RADAR):
240  case enum_value(MAV_DISTANCE_SENSOR::UNKNOWN):
241  range->radiation_type = sensor_msgs::Range::INFRARED;
242  break;
243  case enum_value(MAV_DISTANCE_SENSOR::ULTRASOUND):
244  range->radiation_type = sensor_msgs::Range::ULTRASOUND;
245  break;
246  default:
247  ROS_ERROR_NAMED("distance_sensor",
248  "DS: %s: Wrong/undefined type of sensor (type: %d). Droping!...",
249  sensor->topic_name.c_str(), dist_sen.type);
250  return;
251  }
252 
253  range->range = dist_sen.current_distance * 1E-2; // in meters
254 
255  if (sensor->send_tf) {
256  /* variables init */
257  auto q = utils::sensor_orientation_matching(static_cast<MAV_SENSOR_ORIENTATION>(dist_sen.orientation));
258 
259  geometry_msgs::TransformStamped transform;
260 
261  transform.header = m_uas->synchronized_header(base_frame_id, dist_sen.time_boot_ms);
262  transform.child_frame_id = sensor->frame_id;
263 
264  /* rotation and position set */
265  tf::quaternionEigenToMsg(q, transform.transform.rotation);
266  tf::vectorEigenToMsg(sensor->position, transform.transform.translation);
267 
268  /* transform broadcast */
269  m_uas->tf2_broadcaster.sendTransform(transform);
270  }
271 
272  sensor->pub.publish(range);
273  }
274 };
275 
277 {
278  using mavlink::common::MAV_DISTANCE_SENSOR;
279 
280  uint8_t type = 0;
281  uint8_t covariance_ = 0;
282 
283  if (covariance > 0) covariance_ = covariance;
284  else covariance_ = uint8_t(calculate_variance(msg->range) * 1E2); // in cm
285 
287  ROS_DEBUG_NAMED("distance_sensor", "DS: %d: sensor variance: %f", sensor_id, calculate_variance(msg->range) * 1E2);
288 
289  // current mapping, may change later
290  if (msg->radiation_type == sensor_msgs::Range::INFRARED)
291  type = enum_value(MAV_DISTANCE_SENSOR::LASER);
292  else if (msg->radiation_type == sensor_msgs::Range::ULTRASOUND)
293  type = enum_value(MAV_DISTANCE_SENSOR::ULTRASOUND);
294 
296  msg->header.stamp.toNSec() / 1000000,
297  msg->min_range / 1E-2,
298  msg->max_range / 1E-2,
299  msg->range / 1E-2,
300  type,
301  sensor_id,
302  orientation,
303  covariance_);
304 }
305 
307 {
308  auto p = boost::make_shared<DistanceSensorItem>();
309  std::string orientation_str;
310 
311  ros::NodeHandle pnh(owner->dist_nh, topic_name);
312 
313  p->owner = owner;
314  p->topic_name = topic_name;
315 
316  // load and parse params
317  // first decide the type of topic (sub or pub)
318  pnh.param("subscriber", p->is_subscriber, false);
319 
320  // sensor id
321  int id;
322  if (!pnh.getParam("id", id)) {
323  ROS_ERROR_NAMED("distance_sensor", "DS: %s: `id` not set!", topic_name.c_str());
324  p.reset(); return p; // return nullptr because of a bug related to gcc 4.6
325  }
326  p->sensor_id = id;
327 
328  // orientation, checks later
329  if (!pnh.getParam("orientation", orientation_str))
330  p->orientation = -1; // not set
331  else
332  // lookup for numeric value
333  p->orientation = utils::sensor_orientation_from_str(orientation_str);
334 
335 
336  if (!p->is_subscriber) {
337  // publisher params
338  // frame_id and FOV is required
339  if (!pnh.getParam("frame_id", p->frame_id)) {
340  ROS_ERROR_NAMED("distance_sensor", "DS: %s: `frame_id` not set!", topic_name.c_str());
341  p.reset(); return p; // nullptr
342  }
343 
344  if (!pnh.getParam("field_of_view", p->field_of_view)) {
345  ROS_ERROR_NAMED("distance_sensor", "DS: %s: sensor FOV not set!", topic_name.c_str());
346  p.reset(); return p; // nullptr
347  }
348 
349  // unset allowed, setted wrong - not
350  if (p->orientation == -1 && !orientation_str.empty()) {
351  ROS_ERROR_NAMED("distance_sensor", "DS: %s: defined orientation (%s) is not valid!",
352  topic_name.c_str(), orientation_str.c_str());
353  p.reset(); return p; // nullptr
354  }
355 
356  // optional
357  pnh.param("send_tf", p->send_tf, false);
358  if (p->send_tf) { // sensor position defined if 'send_tf' set to TRUE
359  pnh.param("sensor_position/x", p->position.x(), 0.0);
360  pnh.param("sensor_position/y", p->position.y(), 0.0);
361  pnh.param("sensor_position/z", p->position.z(), 0.0);
362  ROS_DEBUG_NAMED("sensor_position", "DS: %s: Sensor position at: %f, %f, %f", topic_name.c_str(),
363  p->position.x(), p->position.y(), p->position.z());
364  }
365  }
366  else {
367  // subscriber params
368  // orientation is required
369  if (orientation_str.empty()) {
370  ROS_ERROR_NAMED("distance_sensor", "DS: %s: orientation not set!", topic_name.c_str());
371  p.reset(); return p; // nullptr
372  }
373  else if (p->orientation == -1) {
374  ROS_ERROR_NAMED("distance_sensor", "DS: %s: defined orientation (%s) is not valid!", topic_name.c_str(), orientation_str.c_str());
375  p.reset(); return p; // nullptr
376  }
377 
378  // optional
379  pnh.param("covariance", p->covariance, 0);
380  }
381 
382  // create topic handles
383  if (!p->is_subscriber)
384  p->pub = owner->dist_nh.advertise<sensor_msgs::Range>(topic_name, 10);
385  else
386  p->sub = owner->dist_nh.subscribe(topic_name, 10, &DistanceSensorItem::range_cb, p.get());
387 
388  return p;
389 }
390 } // namespace extra_plugins
391 } // namespace mavros
392 
d
void range_cb(const sensor_msgs::Range::ConstPtr &msg)
int covariance
in centimeters, current specification
std::shared_ptr< MAVConnInterface const > ConstPtr
Distance sensor mapping storage item.
#define ROS_WARN_NAMED(name,...)
void quaternionEigenToMsg(const Eigen::Quaterniond &e, geometry_msgs::Quaternion &m)
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))
int orientation
check orientation of sensor if != -1
Eigen::Vector3d position
sensor position
static Ptr create_item(DistanceSensorPlugin *owner, std::string topic_name)
std::string frame_id
frame id for send
#define ROS_ERROR_ONCE_NAMED(name,...)
std::unordered_map< uint8_t, DistanceSensorItem::Ptr > sensor_map
Eigen::Quaterniond sensor_orientation_matching(mavlink::common::MAV_SENSOR_ORIENTATION orientation)
#define ROS_DEBUG_NAMED(name,...)
std::atomic< uint8_t > type
bool is_subscriber
this item is a subscriber, else is a publisher
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void vectorEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Vector3 &m)
#define UAS_FCU(uasobjptr)
PluginBase(const PluginBase &)=delete
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool send_tf
defines if a transform is sent or not
int sensor_orientation_from_str(const std::string &sensor_orientation)
UAS * m_uas
std::vector< HandlerInfo > Subscriptions
void initialize(UAS &uas_)
bool getParam(const std::string &key, std::string &s) const
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)
#define ROS_ERROR_NAMED(name,...)
void handle_distance_sensor(const mavlink::mavlink_message_t *msg, mavlink::common::msg::DISTANCE_SENSOR &dist_sen)
#define ROS_ASSERT(cond)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
boost::shared_ptr< DistanceSensorItem > Ptr
std::vector< float > data
array allocation for measurements
constexpr std::underlying_type< _T >::type enum_value(_T e)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW DistanceSensorItem()


mavros_extras
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:18