BaseDistance.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2009, Ingo Kresse <kresse@in.tum.de>
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 Willow Garage, Inc. 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 
64 #ifndef BASE_DISTANCE_H
65 #define BASE_DISTANCE_H
66 
67 #include <string>
68 #include <vector>
69 
70 #include <math.h>
71 
72 #include <boost/thread.hpp>
73 #include <boost/shared_ptr.hpp>
74 
75 #include "ros/ros.h"
76 #include <tf/transform_listener.h>
77 #include <sensor_msgs/LaserScan.h>
78 
79 
80 class BaseDistance {
81 
82 public:
83 
87  class Vector2 {
88  public:
89  double x, y;
90  Vector2() {}
91  Vector2(double x_, double y_) : x(x_), y(y_) {}
92 
93  double len2() { return x * x + y * y; }
94  double len() { return sqrt(len2()); }
95  };
96 
100  BaseDistance();
101 
105  void setFootprint(double front, double rear, double left, double right, double tolerance);
106 
111  void setSafetyLimits(double safety_dist, double slowdown_near, double slowdown_far, double rate);
112 
113 
117  bool fresh_scans(double watchdog_timeout);
118 
119 
130  bool compute_pose2d(const char* from, const char* to, const ros::Time time, double *x, double *y, double *th);
131 
146  double distance(std::vector<Vector2> &points, Vector2 *nearest, double dx=0, double dy=0, double dth=0);
147 
154  void compute_distance_keeping(double *vx, double *vy, double *vth);
155 
156 
157 private:
158 
160 
166 
167 
171  double d_;
172 
178 
185 
189  double tolerance_;
190 
195 
200 
204  double safety_dist_;
205 
210 
217 
223 
231 
236  std::vector<Vector2> blind_spots_;
237 
243  //boost::shared_ptr<std::vector<Vector2> > current_points_; //!< should replace the points argument of distance(), project(), grad() and brake().
244 
249 
254 
259 
269  int mode_;
270 
271 
273 
277  double marker_size_;
278 
282 
284 
286 
287  boost::mutex lock;
288 
293 
300  bool interpolateBlindPoints(int n, const Vector2 &pt1, const Vector2 &pt2);
301 
308  void laserCallback(int index, const sensor_msgs::LaserScan::ConstPtr& scan);
309 
319  Vector2 transform(const Vector2 &v, double x, double y, double th);
320 
332  double brake(std::vector<Vector2> &points, double *vx, double *vy, double *vth);
333 
343  double grad(std::vector<Vector2> &points, double *gx, double *gy, double *gth);
344 
354  double project(std::vector<Vector2> &points, double *vx, double *vy, double *vth);
355 
360  void publishLaserMarker(const Vector2 &pt, const std::string &ns, int id=0);
361 
366  void publishNearestPoint();
367 
372  void publishBaseMarker();
373 
379  void publishPoints(const std::vector<Vector2> &points);
380 };
381 
382 #endif
The Vector2 helper class to store 2D coordinates.
Definition: BaseDistance.h:87
double repelling_gain_max_
Definition: BaseDistance.h:209
double slowdown_far_
slowdown_far_ Distance from footprint edges to closest obstacle point from when to start slowing ...
Definition: BaseDistance.h:194
ros::Time laser_1_last_msg_time_
Definition: BaseDistance.h:165
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.
Definition: BaseDistance.cc:70
int mode_
mode_ Defined the movement mode for the base. Can be one of the modes defined in the cpp file: MODE_F...
Definition: BaseDistance.h:269
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
Definition: BaseDistance.h:258
ros::Publisher laser_points_pub_
Definition: BaseDistance.h:280
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.
Definition: BaseDistance.h:204
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...
double vth_last_
Definition: BaseDistance.h:258
ros::Subscriber laser_subscriptions_[2]
Definition: BaseDistance.h:285
ros::Publisher debug_pub_
Definition: BaseDistance.h:281
double rob_x_
rob_x_, rob_y_, rob_th_ Pose of the base_link_frame_ in odom_frame_
Definition: BaseDistance.h:253
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.
ros::NodeHandle n_
Definition: BaseDistance.h:272
boost::mutex lock
Definition: BaseDistance.h:287
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_
Definition: BaseDistance.h:159
int n_lasers_
n_lasers_ Number of laser scanners that create the base scan. Note: laser_points_ is of size 2...
Definition: BaseDistance.h:177
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_)
Definition: BaseDistance.h:91
double tolerance_
tolerance_ Error in the footprint measurements in meters.
Definition: BaseDistance.h:189
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...
Definition: BaseDistance.h:242
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...
Definition: BaseDistance.h:222
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.
Definition: BaseDistance.h:164
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...
Definition: BaseDistance.h:184
tf::TransformListener tf_
Definition: BaseDistance.h:283
double d_
d_ duration of one time frame, i.e. dt or Tdot
Definition: BaseDistance.h:171
double slowdown_near_
slowdown_near_ Distance from footprint edges to closest obstacle point from when to slow aggressively...
Definition: BaseDistance.h:199
double rob_th_
Definition: BaseDistance.h:253
double repelling_gain_
Definition: BaseDistance.h:209
std::vector< Vector2 > blind_spots_
blind_spots_ A vector of interpolated coordinates for the blind spots Defined in the odom_frame_ ...
Definition: BaseDistance.h:236
std::string odom_frame_
Definition: BaseDistance.h:159
double marker_size_
marker_size_ When publishing points to RViz, in meters
Definition: BaseDistance.h:277
Vector2 nearest_
nearest_ The nearest point to the base
Definition: BaseDistance.h:248
double blind_spot_threshold_
blind_spot_threshold_ Distance from base_link_frame to the end of a blind spot. Non-parallel lines al...
Definition: BaseDistance.h:230
ros::Publisher marker_pub_
Definition: BaseDistance.h:279
double vy_last_
Definition: BaseDistance.h:258
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...
Definition: BaseDistance.h:216
double repelling_dist_
repelling_dist_ Distance from footprint edges to closest obstacle point from when to start backing up...
Definition: BaseDistance.h:209
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.


nav_pcontroller
Author(s): Ingo Kresse
autogenerated on Thu Jun 6 2019 19:20:56