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 
00030 #ifndef BASE_DISTANCE_H
00031 #define BASE_DISTANCE_H
00032 
00033 #include <boost/thread.hpp>
00034 #include <boost/shared_ptr.hpp>
00035 
00036 #include <math.h>
00037 
00038 #include "ros/ros.h"
00039 #include <tf/transform_listener.h>
00040 #include <sensor_msgs/LaserScan.h>
00041 
00042 class BaseDistance {
00043 public:
00044   // helper class
00045   class Vector2
00046   {
00047   public:
00048     double x, y;
00049     Vector2() {}
00050     Vector2(double x_, double y_) : x(x_), y(y_) {}
00051 
00052     double len2() { return x*x + y*y; }
00053     double len() {return sqrt(len2()); }
00054   };
00055 
00056   BaseDistance();
00057 
00058   bool compute_pose2d(const char* from, const char* to, const ros::Time time, double *x, double *y, double *th);
00059   void setFootprint(double front, double rear, double left, double right, double tolerance);
00060 
00061   void setSafetyLimits(double safety_dist, double slowdown_near, double slowdown_far, double rate);
00062 
00063   void compute_distance_keeping(double *vx, double *vy, double *vth);
00064 
00065   double distance(std::vector<Vector2> &points, Vector2 *nearest, double dx=0, double dy=0, double dth=0);
00066 private:
00067 
00068   Vector2 transform(const Vector2 &v, double x, double y, double th);
00069 
00070   double brake(std::vector<Vector2> &points, double *vx, double *vy, double *vth);
00071   double grad(std::vector<Vector2> &points, double *gx, double *gy, double *gth);
00072   double project(std::vector<Vector2> &points, double *vx, double *vy, double *vth);
00073 
00074   double marker_size_;
00075   double early_reject_distance_;
00076   double front_, rear_, left_, right_;
00077   double tolerance_;
00078   double d_, safety_dist_, slowdown_near_, slowdown_far_, repelling_dist_, repelling_gain_, repelling_gain_max_;
00079 
00080   std::string odom_frame_, base_link_frame_;
00081   int n_lasers_;
00082   bool complete_blind_spots_;
00083   double blind_spot_threshold_;
00084 
00085   ros::NodeHandle n_;
00086 
00087   std::vector<Vector2> blind_spots_;
00088   boost::shared_ptr<std::vector<Vector2> > laser_points_[2];
00089 
00090   //boost::shared_ptr<std::vector<Vector2> > current_points_;  //!< should replace the points argument of distance(), project(), grad() and brake().
00091   double rob_x_, rob_y_, rob_th_;
00092   double vx_last_, vy_last_, vth_last_;
00093   Vector2 nearest_;
00094   int mode_;
00095 
00096   ros::Subscriber laser_subscriptions_[2];
00097   
00098   ros::Publisher marker_pub_;
00099   ros::Publisher laser_points_pub_;
00100   ros::Publisher debug_pub_;
00101   tf::TransformListener tf_;
00102   
00103   //double reading_blind_front_, reading_blind_left_, reading_blind_right_, reading_blind_rear_;
00104   //double laser_x_front_, laser_y_front_, laser_x_rear_, laser_y_rear_;
00105 
00106   boost::mutex lock;
00107 
00112   bool interpolateBlindPoints(int n, const Vector2 &pt1, const Vector2 &pt2);
00113   void laserCallback(int index, const sensor_msgs::LaserScan::ConstPtr& scan);
00114   void publishLaserMarker(const Vector2 &pt, const std::string &ns, int id=0);
00115   void publishNearestPoint();
00116   void publishBaseMarker();
00117   void publishPoints(const std::vector<Vector2> &points);
00118 
00119   void calculateEarlyRejectDistance();
00120 
00121   //void swap_point_buffers();
00122 };
00123 
00124 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


nav_pcontroller
Author(s): Ingo Kresse
autogenerated on Thu May 23 2013 09:13:23