42 #include <Eigen/Geometry> 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> 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> 67 #include <safety_limiter/SafetyLimiterConfig.h> 71 pcl::PointXYZ
operator-(
const pcl::PointXYZ& a,
const pcl::PointXYZ& b)
79 pcl::PointXYZ
operator+(
const pcl::PointXYZ& a,
const pcl::PointXYZ& b)
87 pcl::PointXYZ
operator*(
const pcl::PointXYZ& a,
const float& b)
164 , cloud_clear_(false)
165 , last_disable_cmd_(0)
166 , watchdog_stop_(false)
169 , has_collision_at_now_(false)
170 , stuck_started_since_(
ros::Time(0))
173 pub_twist_ = neonavigation_common::compat::advertise<geometry_msgs::Twist>(
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);
182 nh_,
"disable_safety",
185 nh_,
"watchdog_reset",
188 int num_input_clouds;
189 pnh_.param(
"num_input_clouds", num_input_clouds, 1);
190 if (num_input_clouds == 1)
198 for (
int i = 0; i < num_input_clouds; ++i)
200 sub_clouds_.push_back(nh_.subscribe(
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);
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());
215 parameter_server_.reset(
216 new dynamic_reconfigure::Server<SafetyLimiterConfig>(parameter_server_mutex_, pnh_));
220 if (!pnh_.hasParam(
"footprint"))
222 ROS_FATAL(
"Footprint doesn't specified");
223 throw std::runtime_error(
"Footprint doesn't specified");
225 pnh_.getParam(
"footprint", footprint_xml);
229 throw std::runtime_error(
"Invalid footprint");
231 footprint_radius_ = 0;
232 for (
int i = 0; i < footprint_xml.
size(); i++)
238 throw std::runtime_error(
"Invalid footprint value");
242 v[0] =
static_cast<double>(footprint_xml[i][0]);
243 v[1] =
static_cast<double>(footprint_xml[i][1]);
246 const float dist = std::hypot(v[0], v[1]);
247 if (dist > footprint_radius_)
248 footprint_radius_ = dist;
251 ROS_INFO(
"footprint radius: %0.3f", footprint_radius_);
273 watchdog_timer_.
setPeriod(watchdog_interval_,
true);
274 watchdog_stop_ =
false;
279 watchdog_stop_ =
true;
281 geometry_msgs::Twist cmd_vel;
296 geometry_msgs::Twist cmd_vel;
299 cloud_accum_.reset(
new pcl::PointCloud<pcl::PointXYZ>);
308 const double r_lim_current =
predict(twist_);
310 if (r_lim_current < r_lim_)
311 r_lim_ = r_lim_current;
313 if (r_lim_current < 1.0)
314 hold_off_ = now +
hold_;
320 void cbParameter(
const SafetyLimiterConfig& config,
const uint32_t )
322 boost::recursive_mutex::scoped_lock lock(parameter_server_mutex_);
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;
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;
341 allow_empty_cloud_ = config.allow_empty_cloud;
344 for (
int i = 0; i < 2; i++)
346 auto t = vel_[i] / acc_[i];
351 tmax_ += std::max(d_margin_ / vel_[0], yaw_margin_ / vel_[1]);
354 double predict(
const geometry_msgs::Twist& in)
356 if (cloud_accum_->size() == 0)
358 if (allow_empty_cloud_)
367 base_frame_id_, cloud_accum_->header.frame_id,
372 geometry_msgs::TransformStamped fixed_to_base;
376 base_frame_id_, cloud_accum_->header.frame_id, stamp);
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) *
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);
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_);
402 auto filter_z = [
this](pcl::PointXYZ& p)
404 if (p.z < this->z_range_[0] || this->z_range_[1] < p.z)
409 pc->erase(std::remove_if(pc->points.begin(), pc->points.end(), filter_z),
414 if (allow_empty_cloud_)
422 pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
423 kdtree.setInputCloud(pc);
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());
434 move_inv.setIdentity();
435 sensor_msgs::PointCloud col_points;
441 bool has_collision =
false;
442 float d_escape_remain = 0;
443 float yaw_escape_remain = 0;
444 has_collision_at_now_ =
false;
446 for (
float t = 0; t <
tmax_; t +=
dt_)
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;
458 pcl::PointXYZ center;
459 center = pcl::transformPoint(center, move_inv);
461 std::vector<int> indices;
462 std::vector<float> dist;
463 const int num = kdtree.radiusSearch(center, footprint_radius_, indices, dist);
467 bool colliding =
false;
468 for (
auto& i : indices)
470 auto& p = pc->points[i];
471 auto point = pcl::transformPoint(p, move);
472 vec v(point.x, point.y);
475 geometry_msgs::Point32 pos;
479 col_points.points.push_back(pos);
492 has_collision_at_now_ =
true;
494 if (d_escape_remain <= 0 || yaw_escape_remain <= 0)
496 if (has_collision_at_now_)
502 has_collision =
true;
507 pub_cloud_.
publish(col_points);
509 if (has_collision_at_now_)
511 if (stuck_started_since_ ==
ros::Time(0))
516 if (stuck_started_since_ !=
ros::Time(0))
527 const float delay = 1.0 * (1.0 /
hz_) + dt_;
528 const float acc_dtsq[2] =
530 static_cast<float>(acc_[0] * std::pow(delay, 2)),
531 static_cast<float>(acc_[1] * std::pow(delay, 2)),
534 d_col = std::max<float>(
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>(
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)));
544 std::sqrt(std::abs(2 * acc_[0] * d_col)) / std::abs(twist_.linear.x);
546 std::sqrt(std::abs(2 * acc_[1] * yaw_col)) / std::abs(twist_.angular.z);
547 if (!std::isfinite(d_r))
549 if (!std::isfinite(yaw_r))
552 return std::min(d_r, yaw_r);
556 limit(
const geometry_msgs::Twist& in)
559 if (r_lim_ < 1.0 - EPSILON)
563 if (std::abs(in.linear.x - out.linear.x) > EPSILON ||
564 std::abs(in.angular.z - out.angular.z) > EPSILON)
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);
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]);
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]);
594 vec(
const float x,
const float y)
622 return (*
this)[0] * a[1] - (*this)[1] * a[0];
626 return (*
this)[0] * a[0] + (*this)[1] * a[1];
630 return std::hypot((*
this)[0] - a[0], (*
this)[1] - a[1]);
634 return (b - a).cross((*
this) - a) / b.
dist(a);
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);
649 void move(
const float& x,
const float& y,
const float& yaw)
651 const float cos_v = cosf(yaw);
652 const float sin_v = sinf(yaw);
656 p[0] = cos_v * tmp[0] - sin_v * tmp[1] + x;
657 p[1] = sin_v * tmp[0] + cos_v * tmp[1] + y;
663 for (
size_t i = 0; i < v.size() - 1; i++)
667 if ((v1[1] <= a[1] && a[1] < v2[1]) ||
668 (v2[1] <= a[1] && a[1] < v1[1]))
671 lx = v1[0] + (v2[0] - v1[0]) * (a[1] - v1[1]) / (v2[1] - v1[1]);
676 return ((cn & 1) == 1);
680 float dist = std::numeric_limits<float>::max();
681 for (
size_t i = 0; i < v.size() - 1; i++)
695 void cbTwist(
const geometry_msgs::Twist::ConstPtr& msg)
702 if (now - last_disable_cmd_ <
ros::Duration(disable_timeout_))
706 else if (!has_cloud_ || watchdog_stop_)
708 geometry_msgs::Twist cmd_vel;
721 void cbCloud(
const sensor_msgs::PointCloud2::ConstPtr& msg)
724 fixed_frame_id_, msg->header.frame_id, msg->header.stamp);
726 can_transform ? msg->header.stamp :
ros::Time(0);
728 sensor_msgs::PointCloud2 cloud_msg_fixed;
731 const geometry_msgs::TransformStamped cloud_to_fixed =
741 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_fixed(
new pcl::PointCloud<pcl::PointXYZ>());
747 cloud_clear_ =
false;
748 cloud_accum_.reset(
new pcl::PointCloud<pcl::PointXYZ>);
750 *cloud_accum_ += *cloud_fixed;
752 last_cloud_stamp_ = msg->header.stamp;
765 safety_limiter_msgs::SafetyLimiterStatus status_msg;
767 if (!has_cloud_ || watchdog_stop_)
769 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Stopped due to data timeout.");
771 else if (r_lim_ == 1.0)
773 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"OK");
775 else if (r_lim_ < EPSILON)
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.");
784 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
785 (has_collision_at_now_) ?
786 "Escaping from collision." :
787 "Reducing velocity to avoid collision.");
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");
793 status_msg.limit_ratio =
r_lim_;
798 pub_status_.
publish(status_msg);
804 int main(
int argc,
char** argv)
void cbPredictTimer(const ros::TimerEvent &event)
int main(int argc, char **argv)
geometry_msgs::Twist limit(const geometry_msgs::Twist &in)
#define ROS_WARN_THROTTLE(rate,...)
void publish(const boost::shared_ptr< M > &message) const
static constexpr float EPSILON
ros::Publisher pub_cloud_
float dot(const vec &a) const
geometry_msgs::Twist limitMaxVelocities(const geometry_msgs::Twist &in)
void summary(unsigned char lvl, const std::string s)
ros::Time stuck_started_since_
std::unique_ptr< dynamic_reconfigure::Server< SafetyLimiterConfig > > parameter_server_
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
ros::Publisher pub_twist_
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
Type const & getType() const
void addf(const std::string &key, const char *format,...)
void cbWatchdogReset(const std_msgs::Empty::ConstPtr &msg)
ROSCPP_DECL void spin(Spinner &spinner)
ros::Time last_cloud_stamp_
float cross(const vec &a) const
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
ros::Publisher pub_status_
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)
vec operator-(const vec &a) const
void cbDisable(const std_msgs::Bool::ConstPtr &msg)
tf2_ros::TransformListener tfl_
float & operator[](const int &i)
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
ros::Subscriber sub_watchdog_
ros::Subscriber sub_disable_
ros::Subscriber sub_twist_
pcl::PointXYZ operator+(const pcl::PointXYZ &a, const pcl::PointXYZ &b)
diagnostic_updater::Updater diag_updater_
ros::Time last_disable_cmd_
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)
bool inside(const vec &a) const
std::string fixed_frame_id_
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
std::string base_frame_id_
float dist(const vec &a) const
float dist(const vec &a) const
void add(const std::string &key, const T &val)
bool has_collision_at_now_
void diagnoseCollision(diagnostic_updater::DiagnosticStatusWrapper &stat)
ros::Duration watchdog_interval_
ros::Timer watchdog_timer_
void cbParameter(const SafetyLimiterConfig &config, const uint32_t)
pcl::PointCloud< pcl::PointXYZ >::Ptr cloud_accum_
boost::recursive_mutex parameter_server_mutex_
geometry_msgs::Twist twist_
void cbWatchdogTimer(const ros::TimerEvent &event)