36 #include <boost/bind.hpp> 38 #include <visualization_msgs/Marker.h> 39 #include <visualization_msgs/MarkerArray.h> 40 #include <std_msgs/Float64MultiArray.h> 58 #define MODE_PROJECTING 1 59 #define MODE_HARD_PROJECTING 2 60 #define MODE_BRAKING 3 61 #define MODE_REPELLING 4 62 #define MODE_PROJECTION_MASK 3 64 #if !ROS_VERSION_MINIMUM(1, 8, 0) 81 if(n_lasers_ < 1 || n_lasers_ > 2)
101 laser_subscriptions_[1] =
n_.
subscribe<sensor_msgs::LaserScan>
134 double movement_tolerance = 0.2;
143 ROS_INFO(
"setting footprint. x : %f .. %f y : %f .. %f", rear, front, right, left);
166 return Vector2(v.
x*cos(th) - v.
y*sin(th) + x,
167 v.
x*sin(th) + v.
y*cos(th) + y);
180 ROS_WARN(
"no localization information yet (%s -> %s)", from, to);
188 *th = atan2(m[1][0], m[0][0]);
199 points->reserve(scan->ranges.size());
206 int i, first_scan = 0, last_scan = 0;
212 for(
int i = scan->ranges.size() - 1; i >= 0; i--)
214 if(scan->ranges[i] > scan->range_min &&
215 scan->ranges[i] < scan->range_max)
222 for(angle = scan->angle_min, i = 0;
223 i < (
int) scan->ranges.size();
224 i++, angle += scan->angle_increment)
227 if(scan->ranges[i] <= scan->range_min ||
228 scan->ranges[i] >= scan->range_max)
241 double xl = scan->ranges[i] * cos(angle);
242 double yl = scan->ranges[i] * sin(angle);
274 }
else if (index == 1) {
291 for(
int i = 0; i < n; i++)
294 double t = (i / (n - 1.0));
296 t * pt1.
y + (1.0 - t) * pt2.
y));
316 Vector2 rnearest(0, 0), lnearest(0, 0);
317 double rqdistance=INFINITY, ldistance=INFINITY;
321 if(points.size() == 0)
322 ROS_WARN(
"No points received. Maybe the laser topic is wrong?");
331 sin(dth), cos(dth), dy,
342 for(
unsigned int i=0; i < points.size(); i++) {
344 double px = points[i].x * m[0][0] + points[i].y * m[0][1] + m[0][2];
345 double py = points[i].x * m[1][0] + points[i].y * m[1][1] + m[1][2];
348 double dright = -py +
right_;
349 double dleft = py -
left_;
350 double drear = -px +
rear_;
351 double dfront = px -
front_;
362 double rqdist=INFINITY, ldist=INFINITY;
364 case(
RIGHT): ldist = dright;
break;
365 case(
LEFT): ldist = dleft;
break;
366 case(
REAR): ldist = drear;
break;
367 case(
FRONT): ldist = dfront;
break;
369 case(
LEFT |
REAR): rqdist = dleft*dleft + drear*drear;
break;
370 case(
LEFT |
FRONT): rqdist = dleft*dleft + dfront*dfront;
break;
371 case(
RIGHT |
REAR): rqdist = dright*dright + drear*drear;
break;
372 case(
RIGHT |
FRONT): rqdist = dright*dright + dfront*dfront;
break;
375 if(ldist < ldistance) {
381 if(rqdist < rqdistance) {
389 double rdistance = sqrt(rqdistance);
390 if(rdistance < ldistance) {
404 #define CLAMP(x, min, max) (x < min) ? min : ((x > max) ? max : x) 408 if(!gx || !gy || !gth)
411 double d0, dx_p, dy_p, dth_p, dx_n, dy_n, dth_n;
418 double dd =
CLAMP(v_len*
d_*2, 0.005, 0.15);
424 dx_p =
distance(points, 0, dd, 0, 0);
425 dx_n =
distance(points, 0, -dd, 0, 0);
427 dy_p =
distance(points, 0, 0, dd, 0);
428 dy_n =
distance(points, 0, 0, -dd, 0);
430 dth_p =
distance(points, 0, 0, 0, dd);
431 dth_n =
distance(points, 0, 0, 0, -dd);
433 *gx = (dx_p - dx_n) / (2.0 * dd);
434 *gy = (dy_p - dy_n) / (2.0 * dd);
435 *gth = (dth_p - dth_n) / (2.0 * dd);
438 double g2x = (dx_p + dx_n - 2*d0) / (dd*dd);
439 double g2y = (dy_p + dy_n - 2*d0) / (dd*dd);
440 double g2th = (dth_p + dth_n - 2*d0) / (dd*dd);
446 double g2_scaledown = 2.0;
447 double gx_damp = (fabs(g2x) < g2_scaledown) ? 1.0 : g2_scaledown / fabs(g2x);
448 double gy_damp = (fabs(g2y) < g2_scaledown) ? 1.0 : g2_scaledown / fabs(g2y);
449 double gth_damp = (fabs(g2th) < g2_scaledown) ? 1.0 : g2_scaledown / fabs(g2th);
453 *gth = *gth * gth_damp;
455 std_msgs::Float64MultiArray msg;
476 double d =
distance(points, 0, -*vx*
d_*factor, -*vy*
d_*factor, -*vth*
d_*factor);
489 double d, gx, gy, gth, factor = 0;
490 d =
grad(points, &gx, &gy, >h);
493 double l_grad = 1/sqrt(gx*gx + gy*gy + gth*gth);
500 double dp = *vx*gx + *vy*gy + *vth*gth;
513 *vx -= gx *dp*factor;
514 *vy -= gy *dp*factor;
515 *vth -= gth*dp*factor;
521 double l_grad_2d = 1/sqrt(gx*gx + gy*gy);
528 *vx -= gx * l_grad_2d * a;
529 *vy -= gy * l_grad_2d * a;
543 std::vector<Vector2> current_points;
556 std::back_insert_iterator<std::vector<Vector2> >(current_points));
561 std::back_insert_iterator<std::vector<Vector2> >(current_points));
564 std::back_insert_iterator<std::vector<Vector2> >(current_points));
570 project(current_points, vx, vy, vth);
573 brake(current_points, vx, vy, vth);
587 visualization_msgs::Marker marker;
591 marker.type = visualization_msgs::Marker::CUBE;
592 marker.action = visualization_msgs::Marker::ADD;
593 marker.pose.position.z = 0.55;
594 marker.pose.orientation.x = 0.0;
595 marker.pose.orientation.y = 0.0;
596 marker.pose.orientation.z = 0.0;
597 marker.pose.orientation.w = 1.0;
604 marker.color.a = 1.0;
607 marker.pose.position.x = pt.
x;
608 marker.pose.position.y = pt.
y;
609 marker.pose.orientation.w = 1.0;
617 visualization_msgs::Marker marker;
620 marker.ns =
"nearest_point";
624 marker.type = visualization_msgs::Marker::SPHERE;
626 marker.type = visualization_msgs::Marker::CUBE;
628 marker.action = visualization_msgs::Marker::ADD;
631 marker.pose.position.z = 0.55;
632 marker.pose.orientation.x = 0.0;
633 marker.pose.orientation.y = 0.0;
634 marker.pose.orientation.z = 0.0;
635 marker.pose.orientation.w = 1.0;
643 marker.color.r = 0.0f;
644 marker.color.g = 1.0f;
647 marker.color.r = 0.0f;
648 marker.color.g = 1.0f;
651 marker.color.r = 1.0f;
652 marker.color.g = 0.5f;
655 marker.color.r = 1.0f;
656 marker.color.g = 0.0f;
659 marker.color.b = 0.0f;
660 marker.color.a = 1.0;
669 visualization_msgs::Marker marker;
672 marker.ns =
"base_footprint";
674 marker.type = visualization_msgs::Marker::CUBE;
675 marker.action = visualization_msgs::Marker::ADD;
678 marker.pose.position.z = 0.3;
679 marker.pose.orientation.x = 0.0;
680 marker.pose.orientation.y = 0.0;
681 marker.pose.orientation.z = 0.0;
682 marker.pose.orientation.w = 1.0;
685 marker.scale.z = 0.6;
686 marker.color.r = 0.5f;
687 marker.color.g = 0.5f;
688 marker.color.b = 1.0f;
689 marker.color.a = 0.5;
697 sensor_msgs::PointCloud cloud;
699 cloud.points.resize(points.size());
701 std::vector<Vector2>::const_iterator src_it;
702 sensor_msgs::PointCloud::_points_type::iterator dest_it;
706 for(src_it=points.begin(), dest_it=cloud.points.begin();
707 src_it != points.end();
710 dest_it->x = src_it->x;
711 dest_it->y = src_it->y;
716 if(points.size() == 0)
718 cloud.points.resize(1);
719 cloud.points[0].x = 0.0;
720 cloud.points[0].y = 0.0;
721 cloud.points[0].z = 0.0;
The Vector2 helper class to store 2D coordinates.
double repelling_gain_max_
double slowdown_far_
slowdown_far_ Distance from footprint edges to closest obstacle point from when to start slowing ...
ros::Time laser_1_last_msg_time_
double brake(std::vector< Vector2 > &points, double *vx, double *vy, double *vth)
If distance to closest point when moving with given velocity is short, brake. Given velocity here is ...
#define MODE_PROJECTION_MASK
BaseDistance()
Gets the parameters from ROS parameter server and initializes arguments with that.
void publish(const boost::shared_ptr< M > &message) const
int mode_
mode_ Defined the movement mode for the base. Can be one of the modes defined in the cpp file: MODE_F...
bool fresh_scans(double watchdog_timeout)
Check if the laser scans are older than a certain timeout, to use with a watchdog.
void calculateEarlyRejectDistance()
early_reject_distance_ = diameter + slowdown_far_ + tolerance_ + movement_tolerance; ...
double vx_last_
vx_last_, vy_last_, vth_last_ Robot velocity to drive with in next time frame
ros::Publisher laser_points_pub_
Vector2 transform(const Vector2 &v, double x, double y, double th)
Applies ridig transformation to the input vector, i.e. rotation and translation I.e. gets transformed into a coordinate system defined by x, y and th.
double safety_dist_
safety_dist_ Distance in meters when to brake when moving with current velocity.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
double distance(std::vector< Vector2 > &points, Vector2 *nearest, double dx=0, double dy=0, double dth=0)
Calculates the distance to closest of points from nearest footprint wall The distance is calculated n...
void setFootprint(double front, double rear, double left, double right, double tolerance)
Sets front_, rear_, left_, right_, tolerance_, and early_reject_distance_.
void publishNearestPoint()
Publishes nearest_ as a cube or a sphere of corresponding color nearest_ is defined in base_link_fram...
ros::Subscriber laser_subscriptions_[2]
ros::Publisher debug_pub_
TFSIMD_FORCE_INLINE const tfScalar & y() const
double rob_x_
rob_x_, rob_y_, rob_th_ Pose of the base_link_frame_ in odom_frame_
#define CLAMP(x, min, max)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
void publishLaserMarker(const Vector2 &pt, const std::string &ns, int id=0)
Publishes a red cube at the coordinates of pt using marker_pub_.
void publishPoints(const std::vector< Vector2 > &points)
Publishes coordinates in points as a point cloud Uses laser_points_pub_ to publish.
bool compute_pose2d(const char *from, const char *to, const ros::Time time, double *x, double *y, double *th)
Computes the translation and rotation from one frame to another.
TFSIMD_FORCE_INLINE const tfScalar & x() const
std::string base_link_frame_
int n_lasers_
n_lasers_ Number of laser scanners that create the base scan. Note: laser_points_ is of size 2...
double project(std::vector< Vector2 > &points, double *vx, double *vy, double *vth)
Adapts the velocity given in parameters to slow down or back up Adjusts mode_, vx, vy and vth.
double tolerance_
tolerance_ Error in the footprint measurements in meters.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void setSafetyLimits(double safety_dist, double slowdown_near, double slowdown_far, double rate)
Sets safety_dist_, slowdown_near_, slowdown_far_, and d_ = 1 / rate.
TFSIMD_FORCE_INLINE const tfScalar & y() const
TFSIMD_FORCE_INLINE const tfScalar & x() const
boost::shared_ptr< std::vector< Vector2 > > laser_points_[2]
laser_points_ Data from lasers filtered and converted into the odom frame. The size is 2 for 2 lasers...
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void publishBaseMarker()
Publishes a purple cube at the position of the robot in odom_frame_ The size of the cube is the size ...
bool complete_blind_spots_
complete_blind_spots_ If the laser/s have blind spots, wheter to complete them. The completion will b...
bool interpolateBlindPoints(int n, const Vector2 &pt1, const Vector2 &pt2)
Interpolates n points between pt1 and pt2 and adds them to blind_spots_ Interpolation is linear and c...
ros::Time laser_0_last_msg_time_
Stores the last time when we received laser messages.
void compute_distance_keeping(double *vx, double *vy, double *vth)
Sets vx_last_, vy_last and vth_last_ to input parameters, adjusting them.
double front_
Footprint of the robot, coordinates of front edge, back edge, etc. in the footprint coordinate system...
tf::TransformListener tf_
double d_
d_ duration of one time frame, i.e. dt or Tdot
double slowdown_near_
slowdown_near_ Distance from footprint edges to closest obstacle point from when to slow aggressively...
std::vector< Vector2 > blind_spots_
blind_spots_ A vector of interpolated coordinates for the blind spots Defined in the odom_frame_ ...
double marker_size_
marker_size_ When publishing points to RViz, in meters
Vector2 nearest_
nearest_ The nearest point to the base
double blind_spot_threshold_
blind_spot_threshold_ Distance from base_link_frame to the end of a blind spot. Non-parallel lines al...
ros::Publisher marker_pub_
double grad(std::vector< Vector2 > &points, double *gx, double *gy, double *gth)
Calculates the gradient of the distance to the closes point of points Is it increasing? Is it decreasing? How fast?
#define MODE_HARD_PROJECTING
double early_reject_distance_
early_reject_distance_ From how many meters to discard laser measurements. Laser is used to avoid obs...
double repelling_dist_
repelling_dist_ Distance from footprint edges to closest obstacle point from when to start backing up...
void laserCallback(int index, const sensor_msgs::LaserScan::ConstPtr &scan)
laserCallback Sets the laser_points_ to filtered data from lasers in the odom frame. Completes blind spots if complete_blind_spots is set to true.