trajectory_planner.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2008, Willow Garage, Inc.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the Willow Garage nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *
00035 *********************************************************************/
00036 #ifndef TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_H_
00037 #define TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_H_
00038 
00039 #include <vector>
00040 #include <string>
00041 #include <sstream>
00042 #include <math.h>
00043 #include <ros/console.h>
00044 #include <angles/angles.h>
00045 
00046 //for creating a local cost grid
00047 #include <map_cell.h>
00048 #include <map_grid.h>
00049 
00050 //for obstacle data access
00051 #include <costmap_2d/costmap_2d.h>
00052 #include <world_model.h>
00053 
00054 #include <trajectory.h>
00055 
00056 //we'll take in a path as a vector of poses
00057 #include <geometry_msgs/PoseStamped.h>
00058 #include <geometry_msgs/Point.h>
00059 #include <geometry_msgs/Twist.h>
00060 #include <iri_ackermann_local_planner/Position2DInt.h>
00061 
00062 //for computing path distance
00063 #include <queue>
00064 
00065 //for some datatypes
00066 #include <tf/transform_datatypes.h>
00067 
00068 #include <iri_ackermann_local_planner/AckermannLocalPlannerConfig.h>
00069 #include <boost/algorithm/string.hpp>
00070 
00071 namespace iri_ackermann_local_planner {
00076   class TrajectoryPlanner{
00077     friend class TrajectoryPlannerTest; //Need this for gtest to work
00078     public:
00114       TrajectoryPlanner(WorldModel& world_model, 
00115           const costmap_2d::Costmap2D& costmap, 
00116           std::vector<geometry_msgs::Point> footprint_spec,
00117           double max_acc = 1.0, double max_vel = 0.3, double min_vel = -0.3,
00118           double max_steer_acc = 1.0, double max_steer_vel = 0.5, double min_steer_vel = -0.5,
00119           double max_steer_angle = 0.35, double min_steer_angle = -0.35, double axis_distance = 1.65,
00120           double sim_time = 10.0, double sim_granularity = 0.025, 
00121           int vx_samples = 20, int vtheta_samples = 20,
00122           double pdist_scale = 0.6, double gdist_scale = 0.8, double occdist_scale = 0.01, double hdiff_scale = 1.0,
00123           bool simple_attractor = false, double angular_sim_granularity = 0.025,int heading_points = 8, double xy_goal_tol = 0.5);
00124 
00128       ~TrajectoryPlanner();
00129 
00133       void reconfigure(AckermannLocalPlannerConfig &cfg);
00134 
00142       Trajectory findBestPath(tf::Stamped<tf::Pose> global_pose, tf::Stamped<tf::Pose> global_vel,
00143           tf::Stamped<tf::Pose>& drive_velocities,geometry_msgs::Twist &ackermann_state);
00144 
00150       void updatePlan(const std::vector<geometry_msgs::PoseStamped>& new_plan, bool compute_dists = false);
00151 
00157       void getLocalGoal(double& x, double& y);
00158 
00172       bool checkTrajectory(double x, double y, double theta, double vx, double vy, 
00173           double vtheta, double vx_samp, double vy_samp, double vtheta_samp);
00174 
00188       double scoreTrajectory(double x, double y, double theta, double vx, double vy, 
00189           double vtheta, double vx_samp, double vy_samp, double vtheta_samp);
00190 
00201       bool getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost);
00202     private:
00216       Trajectory createTrajectories(double x, double y, double theta, double vx, double vy, double vtheta, 
00217           double acc_x, double acc_y, double acc_theta);
00218 
00236       void generateTrajectory(double x, double y, double theta, double vx, double vy, 
00237           double vtheta, double vx_samp, double vy_samp, double vtheta_samp, double acc_x, double acc_y,
00238           double acc_theta, double impossible_cost, Trajectory& traj);
00239 
00247       double footprintCost(double x_i, double y_i, double theta_i);
00248 
00257       std::vector<iri_ackermann_local_planner::Position2DInt> getFootprintCells(double x_i, double y_i, double theta_i, bool fill);
00258 
00267       void getLineCells(int x0, int x1, int y0, int y1, std::vector<iri_ackermann_local_planner::Position2DInt>& pts);
00268 
00273       void getFillCells(std::vector<iri_ackermann_local_planner::Position2DInt>& footprint);
00274 
00275       MapGrid map_; 
00276       const costmap_2d::Costmap2D& costmap_; 
00277       WorldModel& world_model_; 
00278 
00279       std::vector<geometry_msgs::Point> footprint_spec_; 
00280 
00281       std::vector<geometry_msgs::PoseStamped> global_plan_; 
00282 
00283       double goal_x_,goal_y_; 
00284 
00285       double sim_time_; 
00286       double sim_granularity_; 
00287       double angular_sim_granularity_; 
00288 
00289       int vx_samples_; 
00290       int vtheta_samples_; 
00291 
00292       double pdist_scale_, gdist_scale_, occdist_scale_,hdiff_scale_; 
00293 
00294       Trajectory traj_one, traj_two; 
00295 
00296 
00297       /* ackerman parameters */
00298       double steering_speed_;
00299       /* ackerman reconfigure parameters */
00300       double ack_acc_max_;
00301       double ack_vel_min_;
00302       double ack_vel_max_;
00303       double ack_steer_acc_max_;
00304       double ack_steer_speed_max_;
00305       double ack_steer_speed_min_;
00306       double ack_steer_angle_max_;
00307       double ack_steer_angle_min_;
00308       double ack_axis_distance_;
00309 
00310       bool simple_attractor_;  
00311       int heading_points_;
00312       double xy_goal_tol_;
00313 
00314       boost::mutex configuration_mutex_;
00315 
00316       double lineCost(int x0, int x1, int y0, int y1);
00317       double pointCost(int x, int y);
00318       double headingDiff(int cell_x, int cell_y, double x, double y, double heading);
00319   };
00320 };
00321 
00322 #endif


iri_ackermann_local_planner
Author(s): Sergi Hernandez Juan
autogenerated on Fri Dec 6 2013 23:50:18