safety_limiter.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014-2017, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <algorithm>
31 #include <cmath>
32 #include <iostream>
33 #include <limits>
34 #include <memory>
35 #include <random>
36 #include <sstream>
37 #include <string>
38 #include <utility>
39 #include <vector>
40 
41 #include <Eigen/Core>
42 #include <Eigen/Geometry>
43 
44 #include <ros/ros.h>
45 
47 #include <dynamic_reconfigure/server.h>
48 #include <geometry_msgs/Twist.h>
49 #include <safety_limiter_msgs/SafetyLimiterStatus.h>
50 #include <sensor_msgs/PointCloud.h>
51 #include <sensor_msgs/PointCloud2.h>
52 #include <std_msgs/Bool.h>
53 #include <std_msgs/Empty.h>
56 
57 #include <pcl/common/transforms.h>
58 #include <pcl/filters/voxel_grid.h>
59 #include <pcl/kdtree/kdtree_flann.h>
60 #include <pcl/point_cloud.h>
61 #include <pcl/point_types.h>
63 #include <pcl_ros/transforms.h>
64 
66 
67 #include <safety_limiter/SafetyLimiterConfig.h>
68 
69 namespace safety_limiter
70 {
71 pcl::PointXYZ operator-(const pcl::PointXYZ& a, const pcl::PointXYZ& b)
72 {
73  auto c = a;
74  c.x -= b.x;
75  c.y -= b.y;
76  c.z -= b.z;
77  return c;
78 }
79 pcl::PointXYZ operator+(const pcl::PointXYZ& a, const pcl::PointXYZ& b)
80 {
81  auto c = a;
82  c.x += b.x;
83  c.y += b.y;
84  c.z += b.z;
85  return c;
86 }
87 pcl::PointXYZ operator*(const pcl::PointXYZ& a, const float& b)
88 {
89  auto c = a;
90  c.x *= b;
91  c.y *= b;
92  c.z *= b;
93  return c;
94 }
96 {
97  return value.getType() == XmlRpc::XmlRpcValue::TypeInt ||
99 }
100 
102 {
103 protected:
110  std::vector<ros::Subscriber> sub_clouds_;
116  boost::recursive_mutex parameter_server_mutex_;
117  std::unique_ptr<dynamic_reconfigure::Server<SafetyLimiterConfig>> parameter_server_;
118 
119  geometry_msgs::Twist twist_;
121  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_accum_;
123  double hz_;
124  double timeout_;
126  double vel_[2];
127  double acc_[2];
128  double tmax_;
129  double dt_;
130  double d_margin_;
131  double d_escape_;
132  double yaw_margin_;
133  double yaw_escape_;
134  double r_lim_;
135  double max_values_[2];
136  double z_range_[2];
139  std::string fixed_frame_id_;
140  std::string base_frame_id_;
141 
147 
153 
154  constexpr static float EPSILON = 1e-6;
155 
157 
158 public:
160  : nh_()
161  , pnh_("~")
162  , tfl_(tfbuf_)
163  , cloud_accum_(new pcl::PointCloud<pcl::PointXYZ>)
164  , cloud_clear_(false)
165  , last_disable_cmd_(0)
166  , watchdog_stop_(false)
167  , has_cloud_(false)
168  , has_twist_(true)
169  , has_collision_at_now_(false)
170  , stuck_started_since_(ros::Time(0))
171  {
173  pub_twist_ = neonavigation_common::compat::advertise<geometry_msgs::Twist>(
174  nh_, "cmd_vel",
175  pnh_, "cmd_vel_out", 1, true);
176  pub_cloud_ = nh_.advertise<sensor_msgs::PointCloud>("collision", 1, true);
177  pub_status_ = pnh_.advertise<safety_limiter_msgs::SafetyLimiterStatus>("status", 1, true);
179  nh_, "cmd_vel_in",
180  pnh_, "cmd_vel_in", 1, &SafetyLimiterNode::cbTwist, this);
182  nh_, "disable_safety",
183  pnh_, "disable", 1, &SafetyLimiterNode::cbDisable, this);
185  nh_, "watchdog_reset",
186  pnh_, "watchdog_reset", 1, &SafetyLimiterNode::cbWatchdogReset, this);
187 
188  int num_input_clouds;
189  pnh_.param("num_input_clouds", num_input_clouds, 1);
190  if (num_input_clouds == 1)
191  {
192  sub_clouds_.push_back(neonavigation_common::compat::subscribe(
193  nh_, "cloud",
194  pnh_, "cloud", 1, &SafetyLimiterNode::cbCloud, this));
195  }
196  else
197  {
198  for (int i = 0; i < num_input_clouds; ++i)
199  {
200  sub_clouds_.push_back(nh_.subscribe(
201  "cloud" + std::to_string(i), 1, &SafetyLimiterNode::cbCloud, this));
202  }
203  }
204 
205  if (pnh_.hasParam("t_margin"))
206  ROS_WARN("safety_limiter: t_margin parameter is obsolated. Use d_margin and yaw_margin instead.");
207  pnh_.param("base_frame", base_frame_id_, std::string("base_link"));
208  pnh_.param("fixed_frame", fixed_frame_id_, std::string("odom"));
209  double watchdog_interval_d;
210  pnh_.param("watchdog_interval", watchdog_interval_d, 0.0);
211  watchdog_interval_ = ros::Duration(watchdog_interval_d);
212  pnh_.param("max_linear_vel", max_values_[0], std::numeric_limits<double>::infinity());
213  pnh_.param("max_angular_vel", max_values_[1], std::numeric_limits<double>::infinity());
214 
215  parameter_server_.reset(
216  new dynamic_reconfigure::Server<SafetyLimiterConfig>(parameter_server_mutex_, pnh_));
217  parameter_server_->setCallback(boost::bind(&SafetyLimiterNode::cbParameter, this, _1, _2));
218 
219  XmlRpc::XmlRpcValue footprint_xml;
220  if (!pnh_.hasParam("footprint"))
221  {
222  ROS_FATAL("Footprint doesn't specified");
223  throw std::runtime_error("Footprint doesn't specified");
224  }
225  pnh_.getParam("footprint", footprint_xml);
226  if (footprint_xml.getType() != XmlRpc::XmlRpcValue::TypeArray || footprint_xml.size() < 3)
227  {
228  ROS_FATAL("Invalid footprint");
229  throw std::runtime_error("Invalid footprint");
230  }
231  footprint_radius_ = 0;
232  for (int i = 0; i < footprint_xml.size(); i++)
233  {
234  if (!XmlRpc_isNumber(footprint_xml[i][0]) ||
235  !XmlRpc_isNumber(footprint_xml[i][1]))
236  {
237  ROS_FATAL("Invalid footprint value");
238  throw std::runtime_error("Invalid footprint value");
239  }
240 
241  vec v;
242  v[0] = static_cast<double>(footprint_xml[i][0]);
243  v[1] = static_cast<double>(footprint_xml[i][1]);
244  footprint_p.v.push_back(v);
245 
246  const float dist = std::hypot(v[0], v[1]);
247  if (dist > footprint_radius_)
248  footprint_radius_ = dist;
249  }
250  footprint_p.v.push_back(footprint_p.v.front());
251  ROS_INFO("footprint radius: %0.3f", footprint_radius_);
252 
253  diag_updater_.setHardwareID("none");
254  diag_updater_.add("Collision", this, &SafetyLimiterNode::diagnoseCollision);
255  }
256  void spin()
257  {
258  ros::Timer predict_timer =
260 
261  if (watchdog_interval_ != ros::Duration(0.0))
262  {
263  watchdog_timer_ =
264  nh_.createTimer(watchdog_interval_, &SafetyLimiterNode::cbWatchdogTimer, this);
265  }
266 
267  ros::spin();
268  }
269 
270 protected:
271  void cbWatchdogReset(const std_msgs::Empty::ConstPtr& msg)
272  {
273  watchdog_timer_.setPeriod(watchdog_interval_, true);
274  watchdog_stop_ = false;
275  }
276  void cbWatchdogTimer(const ros::TimerEvent& event)
277  {
278  ROS_WARN_THROTTLE(1.0, "safety_limiter: Watchdog timed-out");
279  watchdog_stop_ = true;
280  r_lim_ = 0;
281  geometry_msgs::Twist cmd_vel;
282  pub_twist_.publish(cmd_vel);
283 
284  diag_updater_.force_update();
285  }
286  void cbPredictTimer(const ros::TimerEvent& event)
287  {
288  if (!has_twist_)
289  return;
290  if (!has_cloud_)
291  return;
292 
293  if (ros::Time::now() - last_cloud_stamp_ > ros::Duration(timeout_))
294  {
295  ROS_WARN_THROTTLE(1.0, "safety_limiter: PointCloud timed-out");
296  geometry_msgs::Twist cmd_vel;
297  pub_twist_.publish(cmd_vel);
298 
299  cloud_accum_.reset(new pcl::PointCloud<pcl::PointXYZ>);
300  has_cloud_ = false;
301  r_lim_ = 0;
302 
303  diag_updater_.force_update();
304  return;
305  }
306 
307  ros::Time now = ros::Time::now();
308  const double r_lim_current = predict(twist_);
309 
310  if (r_lim_current < r_lim_)
311  r_lim_ = r_lim_current;
312 
313  if (r_lim_current < 1.0)
314  hold_off_ = now + hold_;
315 
316  cloud_clear_ = true;
317 
318  diag_updater_.force_update();
319  }
320  void cbParameter(const SafetyLimiterConfig& config, const uint32_t /* level */)
321  {
322  boost::recursive_mutex::scoped_lock lock(parameter_server_mutex_);
323  hz_ = config.freq;
324  timeout_ = config.cloud_timeout;
325  disable_timeout_ = config.disable_timeout;
326  vel_[0] = config.lin_vel;
327  acc_[0] = config.lin_acc;
328  vel_[1] = config.ang_vel;
329  acc_[1] = config.ang_acc;
330  max_values_[0] = config.max_linear_vel;
331  max_values_[1] = config.max_angular_vel;
332  z_range_[0] = config.z_range_min;
333  z_range_[1] = config.z_range_max;
334  dt_ = config.dt;
335  d_margin_ = config.d_margin;
336  d_escape_ = config.d_escape;
337  yaw_margin_ = config.yaw_margin;
338  yaw_escape_ = config.yaw_escape;
339  downsample_grid_ = config.downsample_grid;
340  hold_ = ros::Duration(std::max(config.hold, 1.0 / hz_));
341  allow_empty_cloud_ = config.allow_empty_cloud;
342 
343  tmax_ = 0.0;
344  for (int i = 0; i < 2; i++)
345  {
346  auto t = vel_[i] / acc_[i];
347  if (tmax_ < t)
348  tmax_ = t;
349  }
350  tmax_ *= 1.5;
351  tmax_ += std::max(d_margin_ / vel_[0], yaw_margin_ / vel_[1]);
352  r_lim_ = 1.0;
353  }
354  double predict(const geometry_msgs::Twist& in)
355  {
356  if (cloud_accum_->size() == 0)
357  {
358  if (allow_empty_cloud_)
359  {
360  return 1.0;
361  }
362  ROS_WARN_THROTTLE(1.0, "safety_limiter: Empty pointcloud passed.");
363  return 0.0;
364  }
365 
366  const bool can_transform = tfbuf_.canTransform(
367  base_frame_id_, cloud_accum_->header.frame_id,
368  pcl_conversions::fromPCL(cloud_accum_->header.stamp));
369  const ros::Time stamp =
370  can_transform ? pcl_conversions::fromPCL(cloud_accum_->header.stamp) : ros::Time(0);
371 
372  geometry_msgs::TransformStamped fixed_to_base;
373  try
374  {
375  fixed_to_base = tfbuf_.lookupTransform(
376  base_frame_id_, cloud_accum_->header.frame_id, stamp);
377  }
378  catch (tf2::TransformException& e)
379  {
380  ROS_WARN_THROTTLE(1.0, "safety_limiter: Transform failed: %s", e.what());
381  return 0.0;
382  }
383 
384  const Eigen::Affine3f fixed_to_base_eigen =
385  Eigen::Translation3f(
386  fixed_to_base.transform.translation.x,
387  fixed_to_base.transform.translation.y,
388  fixed_to_base.transform.translation.z) *
389  Eigen::Quaternionf(
390  fixed_to_base.transform.rotation.w,
391  fixed_to_base.transform.rotation.x,
392  fixed_to_base.transform.rotation.y,
393  fixed_to_base.transform.rotation.z);
394  pcl::transformPointCloud(*cloud_accum_, *cloud_accum_, fixed_to_base_eigen);
395 
396  pcl::PointCloud<pcl::PointXYZ>::Ptr pc(new pcl::PointCloud<pcl::PointXYZ>);
397  pcl::VoxelGrid<pcl::PointXYZ> ds;
398  ds.setInputCloud(cloud_accum_);
399  ds.setLeafSize(downsample_grid_, downsample_grid_, downsample_grid_);
400  ds.filter(*pc);
401 
402  auto filter_z = [this](pcl::PointXYZ& p)
403  {
404  if (p.z < this->z_range_[0] || this->z_range_[1] < p.z)
405  return true;
406  p.z = 0.0;
407  return false;
408  };
409  pc->erase(std::remove_if(pc->points.begin(), pc->points.end(), filter_z),
410  pc->points.end());
411 
412  if (pc->size() == 0)
413  {
414  if (allow_empty_cloud_)
415  {
416  return 1.0;
417  }
418  ROS_WARN_THROTTLE(1.0, "safety_limiter: Empty pointcloud passed.");
419  return 0.0;
420  }
421 
422  pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
423  kdtree.setInputCloud(pc);
424 
425  Eigen::Affine3f move;
426  Eigen::Affine3f move_inv;
427  Eigen::Affine3f motion =
428  Eigen::AngleAxisf(-twist_.angular.z * dt_, Eigen::Vector3f::UnitZ()) *
429  Eigen::Translation3f(Eigen::Vector3f(-twist_.linear.x * dt_, 0.0, 0.0));
430  Eigen::Affine3f motion_inv =
431  Eigen::Translation3f(Eigen::Vector3f(twist_.linear.x * dt_, 0.0, 0.0)) *
432  Eigen::AngleAxisf(twist_.angular.z * dt_, Eigen::Vector3f::UnitZ());
433  move.setIdentity();
434  move_inv.setIdentity();
435  sensor_msgs::PointCloud col_points;
436  col_points.header.frame_id = base_frame_id_;
437  col_points.header.stamp = ros::Time::now();
438 
439  float d_col = 0;
440  float yaw_col = 0;
441  bool has_collision = false;
442  float d_escape_remain = 0;
443  float yaw_escape_remain = 0;
444  has_collision_at_now_ = false;
445 
446  for (float t = 0; t < tmax_; t += dt_)
447  {
448  if (t != 0)
449  {
450  d_col += twist_.linear.x * dt_;
451  d_escape_remain -= std::abs(twist_.linear.x) * dt_;
452  yaw_col += twist_.angular.z * dt_;
453  yaw_escape_remain -= std::abs(twist_.angular.z) * dt_;
454  move = move * motion;
455  move_inv = move_inv * motion_inv;
456  }
457 
458  pcl::PointXYZ center;
459  center = pcl::transformPoint(center, move_inv);
460 
461  std::vector<int> indices;
462  std::vector<float> dist;
463  const int num = kdtree.radiusSearch(center, footprint_radius_, indices, dist);
464  if (num == 0)
465  continue;
466 
467  bool colliding = false;
468  for (auto& i : indices)
469  {
470  auto& p = pc->points[i];
471  auto point = pcl::transformPoint(p, move);
472  vec v(point.x, point.y);
473  if (footprint_p.inside(v))
474  {
475  geometry_msgs::Point32 pos;
476  pos.x = p.x;
477  pos.y = p.y;
478  pos.z = p.z;
479  col_points.points.push_back(pos);
480  colliding = true;
481  break;
482  }
483  }
484  if (colliding)
485  {
486  if (t == 0)
487  {
488  // The robot is already in collision.
489  // Allow movement under d_escape_ and yaw_escape_
490  d_escape_remain = d_escape_;
491  yaw_escape_remain = yaw_escape_;
492  has_collision_at_now_ = true;
493  }
494  if (d_escape_remain <= 0 || yaw_escape_remain <= 0)
495  {
496  if (has_collision_at_now_)
497  {
498  // It's not possible to escape from collision; stop completely.
499  d_col = yaw_col = 0;
500  }
501 
502  has_collision = true;
503  break;
504  }
505  }
506  }
507  pub_cloud_.publish(col_points);
508 
509  if (has_collision_at_now_)
510  {
511  if (stuck_started_since_ == ros::Time(0))
512  stuck_started_since_ = ros::Time::now();
513  }
514  else
515  {
516  if (stuck_started_since_ != ros::Time(0))
517  stuck_started_since_ = ros::Time(0);
518  }
519 
520  if (!has_collision)
521  return 1.0;
522 
523  // delay compensation:
524  // solve for d_compensated: d_compensated = d - delay * sqrt(2 * acc * d_compensated)
525  // d_compensated = d + acc * delay^2 - sqrt((acc * delay^2)^2 + 2 * d * acc * delay^2)
526 
527  const float delay = 1.0 * (1.0 / hz_) + dt_;
528  const float acc_dtsq[2] =
529  {
530  static_cast<float>(acc_[0] * std::pow(delay, 2)),
531  static_cast<float>(acc_[1] * std::pow(delay, 2)),
532  };
533 
534  d_col = std::max<float>(
535  0.0,
536  std::abs(d_col) - d_margin_ + acc_dtsq[0] -
537  std::sqrt(std::pow(acc_dtsq[0], 2) + 2 * acc_dtsq[0] * std::abs(d_col)));
538  yaw_col = std::max<float>(
539  0.0,
540  std::abs(yaw_col) - yaw_margin_ + acc_dtsq[1] -
541  std::sqrt(std::pow(acc_dtsq[1], 2) + 2 * acc_dtsq[1] * std::abs(yaw_col)));
542 
543  float d_r =
544  std::sqrt(std::abs(2 * acc_[0] * d_col)) / std::abs(twist_.linear.x);
545  float yaw_r =
546  std::sqrt(std::abs(2 * acc_[1] * yaw_col)) / std::abs(twist_.angular.z);
547  if (!std::isfinite(d_r))
548  d_r = 1.0;
549  if (!std::isfinite(yaw_r))
550  yaw_r = 1.0;
551 
552  return std::min(d_r, yaw_r);
553  }
554 
555  geometry_msgs::Twist
556  limit(const geometry_msgs::Twist& in)
557  {
558  auto out = in;
559  if (r_lim_ < 1.0 - EPSILON)
560  {
561  out.linear.x *= r_lim_;
562  out.angular.z *= r_lim_;
563  if (std::abs(in.linear.x - out.linear.x) > EPSILON ||
564  std::abs(in.angular.z - out.angular.z) > EPSILON)
565  {
567  1.0, "safety_limiter: (%0.2f, %0.2f)->(%0.2f, %0.2f)",
568  in.linear.x, in.angular.z,
569  out.linear.x, out.angular.z);
570  }
571  }
572  return out;
573  }
574 
575  geometry_msgs::Twist
576  limitMaxVelocities(const geometry_msgs::Twist& in)
577  {
578  auto out = in;
579  out.linear.x = (out.linear.x > 0) ?
580  std::min(out.linear.x, max_values_[0]) :
581  std::max(out.linear.x, -max_values_[0]);
582 
583  out.angular.z = (out.angular.z > 0) ?
584  std::min(out.angular.z, max_values_[1]) :
585  std::max(out.angular.z, -max_values_[1]);
586 
587  return out;
588  }
589 
590  class vec
591  {
592  public:
593  float c[2];
594  vec(const float x, const float y)
595  {
596  c[0] = x;
597  c[1] = y;
598  }
599  vec()
600  {
601  c[0] = c[1] = 0.0;
602  }
603  float& operator[](const int& i)
604  {
605  ROS_ASSERT(i < 2);
606  return c[i];
607  }
608  const float& operator[](const int& i) const
609  {
610  ROS_ASSERT(i < 2);
611  return c[i];
612  }
613  vec operator-(const vec& a) const
614  {
615  vec out = *this;
616  out[0] -= a[0];
617  out[1] -= a[1];
618  return out;
619  }
620  float cross(const vec& a) const
621  {
622  return (*this)[0] * a[1] - (*this)[1] * a[0];
623  }
624  float dot(const vec& a) const
625  {
626  return (*this)[0] * a[0] + (*this)[1] * a[1];
627  }
628  float dist(const vec& a) const
629  {
630  return std::hypot((*this)[0] - a[0], (*this)[1] - a[1]);
631  }
632  float dist_line(const vec& a, const vec& b) const
633  {
634  return (b - a).cross((*this) - a) / b.dist(a);
635  }
636  float dist_linestrip(const vec& a, const vec& b) const
637  {
638  if ((b - a).dot((*this) - a) <= 0)
639  return this->dist(a);
640  if ((a - b).dot((*this) - b) <= 0)
641  return this->dist(b);
642  return std::abs(this->dist_line(a, b));
643  }
644  };
645  class polygon
646  {
647  public:
648  std::vector<vec> v;
649  void move(const float& x, const float& y, const float& yaw)
650  {
651  const float cos_v = cosf(yaw);
652  const float sin_v = sinf(yaw);
653  for (auto& p : v)
654  {
655  const auto tmp = p;
656  p[0] = cos_v * tmp[0] - sin_v * tmp[1] + x;
657  p[1] = sin_v * tmp[0] + cos_v * tmp[1] + y;
658  }
659  }
660  bool inside(const vec& a) const
661  {
662  int cn = 0;
663  for (size_t i = 0; i < v.size() - 1; i++)
664  {
665  auto& v1 = v[i];
666  auto& v2 = v[i + 1];
667  if ((v1[1] <= a[1] && a[1] < v2[1]) ||
668  (v2[1] <= a[1] && a[1] < v1[1]))
669  {
670  float lx;
671  lx = v1[0] + (v2[0] - v1[0]) * (a[1] - v1[1]) / (v2[1] - v1[1]);
672  if (a[0] < lx)
673  cn++;
674  }
675  }
676  return ((cn & 1) == 1);
677  }
678  float dist(const vec& a) const
679  {
680  float dist = std::numeric_limits<float>::max();
681  for (size_t i = 0; i < v.size() - 1; i++)
682  {
683  auto& v1 = v[i];
684  auto& v2 = v[i + 1];
685  auto d = a.dist_linestrip(v1, v2);
686  if (d < dist)
687  dist = d;
688  }
689  return dist;
690  }
691  };
692 
694 
695  void cbTwist(const geometry_msgs::Twist::ConstPtr& msg)
696  {
697  ros::Time now = ros::Time::now();
698 
699  twist_ = *msg;
700  has_twist_ = true;
701 
702  if (now - last_disable_cmd_ < ros::Duration(disable_timeout_))
703  {
704  pub_twist_.publish(limitMaxVelocities(twist_));
705  }
706  else if (!has_cloud_ || watchdog_stop_)
707  {
708  geometry_msgs::Twist cmd_vel;
709  pub_twist_.publish(cmd_vel);
710  }
711  else
712  {
713  geometry_msgs::Twist cmd_vel = limitMaxVelocities(limit(twist_));
714  pub_twist_.publish(cmd_vel);
715 
716  if (now > hold_off_)
717  r_lim_ = 1.0;
718  }
719  }
720 
721  void cbCloud(const sensor_msgs::PointCloud2::ConstPtr& msg)
722  {
723  const bool can_transform = tfbuf_.canTransform(
724  fixed_frame_id_, msg->header.frame_id, msg->header.stamp);
725  const ros::Time stamp =
726  can_transform ? msg->header.stamp : ros::Time(0);
727 
728  sensor_msgs::PointCloud2 cloud_msg_fixed;
729  try
730  {
731  const geometry_msgs::TransformStamped cloud_to_fixed =
732  tfbuf_.lookupTransform(fixed_frame_id_, msg->header.frame_id, stamp);
733  tf2::doTransform(*msg, cloud_msg_fixed, cloud_to_fixed);
734  }
735  catch (tf2::TransformException& e)
736  {
737  ROS_WARN_THROTTLE(1.0, "safety_limiter: Transform failed: %s", e.what());
738  return;
739  }
740 
741  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_fixed(new pcl::PointCloud<pcl::PointXYZ>());
742  cloud_fixed->header.frame_id = fixed_frame_id_;
743  pcl::fromROSMsg(cloud_msg_fixed, *cloud_fixed);
744 
745  if (cloud_clear_)
746  {
747  cloud_clear_ = false;
748  cloud_accum_.reset(new pcl::PointCloud<pcl::PointXYZ>);
749  }
750  *cloud_accum_ += *cloud_fixed;
751  cloud_accum_->header.frame_id = fixed_frame_id_;
752  last_cloud_stamp_ = msg->header.stamp;
753  has_cloud_ = true;
754  }
755  void cbDisable(const std_msgs::Bool::ConstPtr& msg)
756  {
757  if (msg->data)
758  {
759  last_disable_cmd_ = ros::Time::now();
760  }
761  }
762 
764  {
765  safety_limiter_msgs::SafetyLimiterStatus status_msg;
766 
767  if (!has_cloud_ || watchdog_stop_)
768  {
769  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Stopped due to data timeout.");
770  }
771  else if (r_lim_ == 1.0)
772  {
773  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "OK");
774  }
775  else if (r_lim_ < EPSILON)
776  {
777  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN,
778  (has_collision_at_now_) ?
779  "Cannot escape from collision." :
780  "Trying to avoid collision, but cannot move anymore.");
781  }
782  else
783  {
784  stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
785  (has_collision_at_now_) ?
786  "Escaping from collision." :
787  "Reducing velocity to avoid collision.");
788  }
789  stat.addf("Velocity Limit Ratio", "%.2f", r_lim_);
790  stat.add("Pointcloud Availability", has_cloud_ ? "true" : "false");
791  stat.add("Watchdog Timeout", watchdog_stop_ ? "true" : "false");
792 
793  status_msg.limit_ratio = r_lim_;
794  status_msg.is_cloud_available = has_cloud_;
795  status_msg.has_watchdog_timed_out = watchdog_stop_;
796  status_msg.stuck_started_since = stuck_started_since_;
797 
798  pub_status_.publish(status_msg);
799  }
800 };
801 
802 } // namespace safety_limiter
803 
804 int main(int argc, char** argv)
805 {
806  ros::init(argc, argv, "safety_limiter");
807 
809  limiter.spin();
810 
811  return 0;
812 }
d
void cbPredictTimer(const ros::TimerEvent &event)
int main(int argc, char **argv)
#define ROS_FATAL(...)
geometry_msgs::Twist limit(const geometry_msgs::Twist &in)
#define ROS_WARN_THROTTLE(rate,...)
void publish(const boost::shared_ptr< M > &message) const
geometry_msgs::Twist limitMaxVelocities(const geometry_msgs::Twist &in)
void summary(unsigned char lvl, const std::string s)
std::unique_ptr< dynamic_reconfigure::Server< SafetyLimiterConfig > > parameter_server_
int size() const
void setHardwareID(const std::string &hwid)
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
void cbTwist(const geometry_msgs::Twist::ConstPtr &msg)
void setPeriod(const Duration &period, bool reset=true)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void add(const std::string &name, TaskFunction f)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints())
sensor_msgs::PointCloud2 PointCloud
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
Type const & getType() const
#define ROS_WARN(...)
void addf(const std::string &key, const char *format,...)
void cbWatchdogReset(const std_msgs::Empty::ConstPtr &msg)
ROSCPP_DECL void spin(Spinner &spinner)
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
std::vector< ros::Subscriber > sub_clouds_
void cbCloud(const sensor_msgs::PointCloud2::ConstPtr &msg)
float dist_line(const vec &a, const vec &b) const
bool XmlRpc_isNumber(XmlRpc::XmlRpcValue &value)
void cbDisable(const std_msgs::Bool::ConstPtr &msg)
tf2_ros::TransformListener tfl_
#define ROS_INFO(...)
void move(const float &x, const float &y, const float &yaw)
const float & operator[](const int &i) const
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
pcl::PointXYZ operator+(const pcl::PointXYZ &a, const pcl::PointXYZ &b)
diagnostic_updater::Updater diag_updater_
float dist_linestrip(const vec &a, const vec &b) const
vec(const float x, const float y)
pcl::PointXYZ operator-(const pcl::PointXYZ &a, const pcl::PointXYZ &b)
pcl::PointXYZ operator*(const pcl::PointXYZ &a, const float &b)
double predict(const geometry_msgs::Twist &in)
static Time now()
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &target_time, const ros::Duration timeout, std::string *errstr=NULL) const
void add(const std::string &key, const T &val)
#define ROS_ASSERT(cond)
void diagnoseCollision(diagnostic_updater::DiagnosticStatusWrapper &stat)
void cbParameter(const SafetyLimiterConfig &config, const uint32_t)
pcl::PointCloud< pcl::PointXYZ >::Ptr cloud_accum_
boost::recursive_mutex parameter_server_mutex_
void cbWatchdogTimer(const ros::TimerEvent &event)


safety_limiter
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:20:36