BaseDistance.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2009, Ingo Kresse <kresse@in.tum.de>
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00064 #ifndef BASE_DISTANCE_H
00065 #define BASE_DISTANCE_H
00066 
00067 #include <string>
00068 #include <vector>
00069 
00070 #include <math.h>
00071 
00072 #include <boost/thread.hpp>
00073 #include <boost/shared_ptr.hpp>
00074 
00075 #include "ros/ros.h"
00076 #include <tf/transform_listener.h>
00077 #include <sensor_msgs/LaserScan.h>
00078 
00079 
00080 class BaseDistance {
00081 
00082 public:
00083 
00087   class Vector2 {
00088   public:
00089     double x, y;
00090     Vector2() {}
00091     Vector2(double x_, double y_) : x(x_), y(y_) {}
00092 
00093     double len2() { return x * x + y * y; }
00094     double len() { return sqrt(len2()); }
00095   };
00096 
00100   BaseDistance();
00101 
00105   void setFootprint(double front, double rear, double left, double right, double tolerance);
00106 
00111   void setSafetyLimits(double safety_dist, double slowdown_near, double slowdown_far, double rate);
00112 
00113 
00117   bool fresh_scans(double watchdog_timeout);
00118 
00119 
00130   bool compute_pose2d(const char* from, const char* to, const ros::Time time, double *x, double *y, double *th);
00131 
00146   double distance(std::vector<Vector2> &points, Vector2 *nearest, double dx=0, double dy=0, double dth=0);
00147 
00154   void compute_distance_keeping(double *vx, double *vy, double *vth);
00155 
00156 
00157 private:
00158 
00159   std::string odom_frame_, base_link_frame_;
00160 
00164   ros::Time laser_0_last_msg_time_;
00165   ros::Time laser_1_last_msg_time_;
00166 
00167 
00171   double d_;
00172 
00177   int n_lasers_;
00178 
00184   double front_, rear_, left_, right_;
00185 
00189   double tolerance_;
00190 
00194   double slowdown_far_;
00195 
00199   double slowdown_near_;
00200 
00204   double safety_dist_;
00205 
00209   double repelling_dist_, repelling_gain_, repelling_gain_max_;
00210 
00216   double early_reject_distance_;
00217 
00222   bool complete_blind_spots_;
00223 
00230   double blind_spot_threshold_;
00231 
00236   std::vector<Vector2> blind_spots_;
00237 
00242   boost::shared_ptr<std::vector<Vector2> > laser_points_[2];
00243   //boost::shared_ptr<std::vector<Vector2> > current_points_; //!< should replace the points argument of distance(), project(), grad() and brake().
00244 
00248   Vector2 nearest_;
00249 
00253   double rob_x_, rob_y_, rob_th_;
00254 
00258   double vx_last_, vy_last_, vth_last_;
00259 
00269   int mode_;
00270 
00271 
00272   ros::NodeHandle n_;
00273 
00277   double marker_size_;
00278 
00279   ros::Publisher marker_pub_;
00280   ros::Publisher laser_points_pub_;
00281   ros::Publisher debug_pub_;
00282 
00283   tf::TransformListener tf_;
00284 
00285   ros::Subscriber laser_subscriptions_[2];
00286 
00287   boost::mutex lock;
00288 
00292   void calculateEarlyRejectDistance();
00293 
00300   bool interpolateBlindPoints(int n, const Vector2 &pt1, const Vector2 &pt2);
00301 
00308   void laserCallback(int index, const sensor_msgs::LaserScan::ConstPtr& scan);
00309 
00319   Vector2 transform(const Vector2 &v, double x, double y, double th);
00320 
00332   double brake(std::vector<Vector2> &points, double *vx, double *vy, double *vth);
00333 
00343   double grad(std::vector<Vector2> &points, double *gx, double *gy, double *gth);
00344 
00354   double project(std::vector<Vector2> &points, double *vx, double *vy, double *vth);
00355 
00360   void publishLaserMarker(const Vector2 &pt, const std::string &ns, int id=0);
00361 
00366   void publishNearestPoint();
00367 
00372   void publishBaseMarker();
00373 
00379   void publishPoints(const std::vector<Vector2> &points);
00380 };
00381 
00382 #endif


nav_pcontroller
Author(s): Ingo Kresse
autogenerated on Wed Aug 2 2017 02:30:35