64 #ifndef BASE_DISTANCE_H 65 #define BASE_DISTANCE_H 72 #include <boost/thread.hpp> 73 #include <boost/shared_ptr.hpp> 77 #include <sensor_msgs/LaserScan.h> 91 Vector2(
double x_,
double y_) : x(x_), y(y_) {}
93 double len2() {
return x * x + y *
y; }
105 void setFootprint(
double front,
double rear,
double left,
double right,
double tolerance);
111 void setSafetyLimits(
double safety_dist,
double slowdown_near,
double slowdown_far,
double rate);
146 double distance(std::vector<Vector2> &points,
Vector2 *nearest,
double dx=0,
double dy=0,
double dth=0);
308 void laserCallback(
int index,
const sensor_msgs::LaserScan::ConstPtr& scan);
332 double brake(std::vector<Vector2> &points,
double *vx,
double *vy,
double *vth);
343 double grad(std::vector<Vector2> &points,
double *gx,
double *gy,
double *gth);
354 double project(std::vector<Vector2> &points,
double *vx,
double *vy,
double *vth);
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 ...
BaseDistance()
Gets the parameters from ROS parameter server and initializes arguments with that.
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.
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_
double rob_x_
rob_x_, rob_y_, rob_th_ Pose of the base_link_frame_ in odom_frame_
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.
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.
Vector2(double x_, double y_)
double tolerance_
tolerance_ Error in the footprint measurements in meters.
void setSafetyLimits(double safety_dist, double slowdown_near, double slowdown_far, double rate)
Sets safety_dist_, slowdown_near_, slowdown_far_, and d_ = 1 / rate.
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...
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?
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.