37 #ifndef SAFE_TRAJECTORY_PLANNER_H_ 38 #define SAFE_TRAJECTORY_PLANNER_H_ 57 #include <geometry_msgs/PoseStamped.h> 58 #include <geometry_msgs/Point.h> 59 #include <base_local_planner/Position2DInt.h> 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);
161 double acc_x,
double acc_y,
double acc_theta,
double dx,
double dy,
double dtheta);
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,
195 double footprintCost(
double x_i,
double y_i,
double theta_i);
205 std::vector<base_local_planner::Position2DInt>
getFootprintCells(
double x_i,
double y_i,
double theta_i,
bool fill);
215 void getLineCells(
int x0,
int x1,
int y0,
int y1, std::vector<base_local_planner::Position2DInt>& pts);
221 void getFillCells(std::vector<base_local_planner::Position2DInt>& footprint);
259 return xi + (vx * cos(theta) + vy * cos(M_PI_2 + theta)) * dt;
272 return yi + (vx * sin(theta) + vy * sin(M_PI_2 + theta)) * dt;
283 return thetai + vth * dt;
297 return std::min(vg, vi + a_max * dt);
298 return std::max(vg, vi - a_max * dt);
301 double lineCost(
int x0,
int x1,
int y0,
int y1);
void getLineCells(int x0, int x1, int y0, int y1, std::vector< base_local_planner::Position2DInt > &pts)
Use Bresenham's algorithm to trace a line between two points in a grid.
friend class SafeTrajectoryPlannerTest
~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'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'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 pointCost(int x, int y)
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.