safe_trajectory_planner.h
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2008, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of the Willow Garage nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 *********************************************************************/
37 #ifndef SAFE_TRAJECTORY_PLANNER_H_
38 #define SAFE_TRAJECTORY_PLANNER_H_
39 
40 #include <vector>
41 #include <math.h>
42 #include <ros/console.h>
43 #include <angles/angles.h>
44 
45 //for creating a local cost grid
48 
49 //for obstacle data access
50 #include <costmap_2d/costmap_2d.h>
51 #include <costmap_2d/cost_values.h>
53 
55 
56 //we'll take in a path as a vector of poses
57 #include <geometry_msgs/PoseStamped.h>
58 #include <geometry_msgs/Point.h>
59 #include <base_local_planner/Position2DInt.h>
60 
61 //for computing path distance
62 #include <queue>
63 
64 //for some datatypes
65 #include <tf/transform_datatypes.h>
66 
67 namespace safe_teleop {
73  friend class SafeTrajectoryPlannerTest; //Need this for gtest to work
74  public:
106  const costmap_2d::Costmap2D& costmap,
107  std::vector<geometry_msgs::Point> footprint_spec,
108  double inscribed_radius, double circumscribed_radius,
109  double acc_lim_x = 1.0, double acc_lim_y = 1.0, double acc_lim_theta = 1.0,
110  double sim_time = 1.0, double sim_granularity = 0.025,
111  int vx_samples = 10, int vy_samples = 10, int vtheta_samples = 10,
112  double userdist_scale = 0.8, double occdist_scale = 0.2,
113  double max_vel_x = 0.5, double min_vel_x = 0.1,
114  double max_vel_y = 0.2, double min_vel_y = -0.2,
115  double max_vel_th = 1.0, double min_vel_th = -1.0,
116  bool holonomic_robot = true, bool dwa = false);
117 
122 
131  tf::Stamped<tf::Pose> user_vel, tf::Stamped<tf::Pose>& drive_velocities);
132 
141  tf::Stamped<tf::Pose> user_vel);
142 
143  private:
160  base_local_planner::Trajectory createTrajectories(double x, double y, double theta, double vx, double vy, double vtheta,
161  double acc_x, double acc_y, double acc_theta, double dx, double dy, double dtheta);
162 
183  void generateTrajectory(double x, double y, double theta, double vx, double vy,
184  double vtheta, double vx_samp, double vy_samp, double vtheta_samp, double acc_x, double acc_y,
185  double acc_theta, double impossible_cost, double dx, double dy, double dtheta,
187 
195  double footprintCost(double x_i, double y_i, double theta_i);
196 
205  std::vector<base_local_planner::Position2DInt> getFootprintCells(double x_i, double y_i, double theta_i, bool fill);
206 
215  void getLineCells(int x0, int x1, int y0, int y1, std::vector<base_local_planner::Position2DInt>& pts);
216 
221  void getFillCells(std::vector<base_local_planner::Position2DInt>& footprint);
222 
226 
227  std::vector<geometry_msgs::Point> footprint_spec_;
229 
230  double sim_time_;
232 
236 
239 
241 
243 
245 
246  bool dwa_;
247 
248 
258  inline double computeNewXPosition(double xi, double vx, double vy, double theta, double dt){
259  return xi + (vx * cos(theta) + vy * cos(M_PI_2 + theta)) * dt;
260  }
261 
271  inline double computeNewYPosition(double yi, double vx, double vy, double theta, double dt){
272  return yi + (vx * sin(theta) + vy * sin(M_PI_2 + theta)) * dt;
273  }
274 
282  inline double computeNewThetaPosition(double thetai, double vth, double dt){
283  return thetai + vth * dt;
284  }
285 
286  //compute velocity based on acceleration
295  inline double computeNewVelocity(double vg, double vi, double a_max, double dt){
296  if(vg >= 0)
297  return std::min(vg, vi + a_max * dt);
298  return std::max(vg, vi - a_max * dt);
299  }
300 
301  double lineCost(int x0, int x1, int y0, int y1);
302  double pointCost(int x, int y);
303 // double headingDiff(int cell_x, int cell_y, double x, double y, double heading);
304  };
305 };
306 
307 #endif
void getLineCells(int x0, int x1, int y0, int y1, std::vector< base_local_planner::Position2DInt > &pts)
Use Bresenham&#39;s algorithm to trace a line between two points in a grid.
~SafeTrajectoryPlanner()
Destructs a trajectory controller.
double sim_granularity_
The distance between simulation points.
base_local_planner::MapGrid map_
The local map grid where we propagate goal and path distance.
double computeNewYPosition(double yi, double vx, double vy, double theta, double dt)
Compute y position based on velocity.
double occdist_scale_
Scaling factors for the controller&#39;s cost function.
base_local_planner::Trajectory traj_two
Used for scoring trajectories.
TFSIMD_FORCE_INLINE const tfScalar & y() const
void getFillCells(std::vector< base_local_planner::Position2DInt > &footprint)
Fill the outline of a polygon, in this case the robot footprint, in a grid.
double acc_lim_theta_
The acceleration limits of the robot.
Computes control velocities for a robot given a costmap, a plan, and the robot&#39;s position in the worl...
base_local_planner::Trajectory createTrajectories(double x, double y, double theta, double vx, double vy, double vtheta, double acc_x, double acc_y, double acc_theta, double dx, double dy, double dtheta)
Create the trajectories we wish to explore, score them, and return the best option.
double min_vel_th_
Velocity limits for the controller.
SafeTrajectoryPlanner(base_local_planner::WorldModel &world_model, const costmap_2d::Costmap2D &costmap, std::vector< geometry_msgs::Point > footprint_spec, double inscribed_radius, double circumscribed_radius, double acc_lim_x=1.0, double acc_lim_y=1.0, double acc_lim_theta=1.0, double sim_time=1.0, double sim_granularity=0.025, int vx_samples=10, int vy_samples=10, int vtheta_samples=10, double userdist_scale=0.8, double occdist_scale=0.2, double max_vel_x=0.5, double min_vel_x=0.1, double max_vel_y=0.2, double min_vel_y=-0.2, double max_vel_th=1.0, double min_vel_th=-1.0, bool holonomic_robot=true, bool dwa=false)
Constructs a trajectory controller.
double sim_time_
The number of seconds each trajectory is "rolled-out".
base_local_planner::Trajectory findPath(tf::Stamped< tf::Pose > global_pose, tf::Stamped< tf::Pose > global_vel, tf::Stamped< tf::Pose > user_vel)
Given the current position, orientation, and velocity of the robot, return a trajectory to follow...
base_local_planner::Trajectory traj_one
double computeNewThetaPosition(double thetai, double vth, double dt)
Compute orientation based on velocity.
std::vector< geometry_msgs::Point > footprint_spec_
The footprint specification of the robot.
TFSIMD_FORCE_INLINE const tfScalar & x() const
double computeNewVelocity(double vg, double vi, double a_max, double dt)
Compute velocity based on acceleration.
double circumscribed_radius_
The inscribed and circumscribed radii of the robot.
std::vector< base_local_planner::Position2DInt > getFootprintCells(double x_i, double y_i, double theta_i, bool fill)
Used to get the cells that make up the footprint of the robot.
double computeNewXPosition(double xi, double vx, double vy, double theta, double dt)
Compute x position based on velocity.
base_local_planner::WorldModel & world_model_
The world model that the controller uses for collision detection.
double lineCost(int x0, int x1, int y0, int y1)
double footprintCost(double x_i, double y_i, double theta_i)
Checks the legality of the robot footprint at a position and orientation using the world model...
base_local_planner::Trajectory findBestPath(tf::Stamped< tf::Pose > global_pose, tf::Stamped< tf::Pose > global_vel, tf::Stamped< tf::Pose > user_vel, tf::Stamped< tf::Pose > &drive_velocities)
Given the current position, orientation, and velocity of the robot, return a trajectory to follow...
const costmap_2d::Costmap2D & costmap_
Provides access to cost map information.
void generateTrajectory(double x, double y, double theta, double vx, double vy, double vtheta, double vx_samp, double vy_samp, double vtheta_samp, double acc_x, double acc_y, double acc_theta, double impossible_cost, double dx, double dy, double dtheta, base_local_planner::Trajectory &traj)
Generate and score a single trajectory.


safe_teleop_base
Author(s):
autogenerated on Fri Dec 20 2019 04:00:23