Go to the documentation of this file.
37 #ifndef TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_H_
38 #define TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_H_
50 #include <base_local_planner/Position2DInt.h>
51 #include <base_local_planner/BaseLocalPlannerConfig.h>
54 #include <geometry_msgs/PoseStamped.h>
55 #include <geometry_msgs/Point.h>
66 class TrajectoryPlanner{
107 std::vector<geometry_msgs::Point> footprint_spec,
108 double acc_lim_x = 1.0,
double acc_lim_y = 1.0,
double acc_lim_theta = 1.0,
109 double sim_time = 1.0,
double sim_granularity = 0.025,
110 int vx_samples = 20,
int vtheta_samples = 20,
111 double path_distance_bias = 0.6,
double goal_distance_bias = 0.8,
double occdist_scale = 0.2,
112 double heading_lookahead = 0.325,
double oscillation_reset_dist = 0.05,
113 double escape_reset_dist = 0.10,
double escape_reset_theta = M_PI_2,
114 bool holonomic_robot =
true,
115 double max_vel_x = 0.5,
double min_vel_x = 0.1,
116 double max_vel_th = 1.0,
double min_vel_th = -1.0,
double min_in_place_vel_th = 0.4,
117 double backup_vel = -0.1,
118 bool dwa =
false,
bool heading_scoring =
false,
double heading_scoring_timestep = 0.1,
119 bool meter_scoring =
true,
120 bool simple_attractor =
false,
121 std::vector<double> y_vels = std::vector<double>(0),
122 double stop_time_buffer = 0.2,
123 double sim_period = 0.1,
double angular_sim_granularity = 0.025);
142 Trajectory
findBestPath(
const geometry_msgs::PoseStamped& global_pose,
143 geometry_msgs::PoseStamped& global_vel, geometry_msgs::PoseStamped& drive_velocities);
150 void updatePlan(
const std::vector<geometry_msgs::PoseStamped>& new_plan,
bool compute_dists =
false);
172 bool checkTrajectory(
double x,
double y,
double theta,
double vx,
double vy,
173 double vtheta,
double vx_samp,
double vy_samp,
double vtheta_samp);
188 double scoreTrajectory(
double x,
double y,
double theta,
double vx,
double vy,
189 double vtheta,
double vx_samp,
double vy_samp,
double vtheta_samp);
201 bool getCellCosts(
int cx,
int cy,
float &path_cost,
float &goal_cost,
float &occ_cost,
float &total_cost);
224 Trajectory
createTrajectories(
double x,
double y,
double theta,
double vx,
double vy,
double vtheta,
225 double acc_x,
double acc_y,
double acc_theta);
245 double vtheta,
double vx_samp,
double vy_samp,
double vtheta_samp,
double acc_x,
double acc_y,
246 double acc_theta,
double impossible_cost, Trajectory& traj);
255 double footprintCost(
double x_i,
double y_i,
double theta_i);
329 inline double computeNewXPosition(
double xi,
double vx,
double vy,
double theta,
double dt){
330 return xi + (vx * cos(theta) + vy * cos(M_PI_2 + theta)) * dt;
343 return yi + (vx * sin(theta) + vy * sin(M_PI_2 + theta)) * dt;
354 return thetai + vth * dt;
368 return std::min(vg, vi + a_max * dt);
370 return std::max(vg, vi - a_max * dt);
379 double lineCost(
int x0,
int x1,
int y0,
int y1);
381 double headingDiff(
int cell_x,
int cell_y,
double x,
double y,
double heading);
bool checkTrajectory(double x, double y, double theta, double vx, double vy, double vtheta, double vx_samp, double vy_samp, double vtheta_samp)
Generate and score a single trajectory.
double occdist_scale_
Scaling factors for the controller's cost function.
std::vector< geometry_msgs::Point > getFootprint() const
double stop_time_buffer_
How long before hitting something we're going to enforce that the robot stop.
~TrajectoryPlanner()
Destructs a trajectory controller.
double min_in_place_vel_th_
Velocity limits for the controller.
double computeNewVelocity(double vg, double vi, double a_max, double dt)
Compute velocity based on acceleration.
int vtheta_samples_
The number of samples we'll take in the theta dimension of the control space.
Trajectory createTrajectories(double x, double y, double theta, double vx, double vy, double vtheta, double acc_x, double acc_y, double acc_theta)
Create the trajectories we wish to explore, score them, and return the best option.
bool strafe_left
Booleans to keep track of strafe direction for the robot.
bool getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost)
Compute the components and total cost for a map grid cell.
double path_distance_bias_
MapGrid goal_map_
The local map grid where we propagate goal distance.
double escape_reset_dist_
double computeNewThetaPosition(double thetai, double vth, double dt)
Compute orientation based on velocity.
double oscillation_reset_dist_
The distance the robot must travel before it can explore rotational velocities that were unsuccessful...
bool escaping_
Boolean to keep track of whether we're in escape mode.
bool stuck_right_strafe
Booleans to keep the robot from oscillating during strafing.
double pointCost(int x, int y)
double computeNewXPosition(double xi, double vx, double vy, double theta, double dt)
Compute x position based on velocity.
double final_goal_y_
The end position of the plan.
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.
double headingDiff(int cell_x, int cell_y, double x, double y, double heading)
base_local_planner::FootprintHelper footprint_helper_
double sim_period_
The number of seconds to use to compute max/min vels for dwa.
double goal_distance_bias_
double prev_y_
Used to calculate the distance the robot has traveled before reseting oscillation booleans.
void getLocalGoal(double &x, double &y)
Accessor for the goal the robot is currently pursuing in world corrdinates.
const costmap_2d::Costmap2D & costmap_
Provides access to cost map information.
double computeNewYPosition(double yi, double vx, double vy, double theta, double dt)
Compute y position based on velocity.
double escape_theta_
Used to calculate the distance the robot has traveled before reseting escape booleans.
void updatePlan(const std::vector< geometry_msgs::PoseStamped > &new_plan, bool compute_dists=false)
Update the plan that the controller is following.
MapGrid path_map_
The local map grid where we propagate path distance.
double angular_sim_granularity_
The distance between angular simulation points.
void setFootprint(std::vector< geometry_msgs::Point > footprint)
Set the footprint specification of the robot.
double acc_lim_theta_
The acceleration limits of the robot.
double heading_lookahead_
How far the robot should look ahead of itself when differentiating between different rotational veloc...
WorldModel & world_model_
The world model that the controller uses for collision detection.
double scoreTrajectory(double x, double y, double theta, double vx, double vy, double vtheta, double vx_samp, double vy_samp, double vtheta_samp)
Generate and score a single trajectory.
double circumscribed_radius_
double goal_y_
Storage for the local goal the robot is pursuing.
double sim_granularity_
The distance between simulation points.
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, Trajectory &traj)
Generate and score a single trajectory.
void getMaxSpeedToStopInTime(double time, double &vx, double &vy, double &vth)
bool final_goal_position_valid_
True if final_goal_x_ and final_goal_y_ have valid data. Only false if an empty path is sent.
int vx_samples_
The number of samples we'll take in the x dimenstion of the control space.
bool holonomic_robot_
Is the robot holonomic or not?
Trajectory findBestPath(const geometry_msgs::PoseStamped &global_pose, geometry_msgs::PoseStamped &global_vel, geometry_msgs::PoseStamped &drive_velocities)
Given the current position, orientation, and velocity of the robot, return a trajectory to follow.
geometry_msgs::Polygon getFootprintPolygon() const
Return the footprint specification of the robot.
TrajectoryPlanner(WorldModel &world_model, const costmap_2d::Costmap2D &costmap, std::vector< geometry_msgs::Point > footprint_spec, 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=20, int vtheta_samples=20, double path_distance_bias=0.6, double goal_distance_bias=0.8, double occdist_scale=0.2, double heading_lookahead=0.325, double oscillation_reset_dist=0.05, double escape_reset_dist=0.10, double escape_reset_theta=M_PI_2, bool holonomic_robot=true, double max_vel_x=0.5, double min_vel_x=0.1, double max_vel_th=1.0, double min_vel_th=-1.0, double min_in_place_vel_th=0.4, double backup_vel=-0.1, bool dwa=false, bool heading_scoring=false, double heading_scoring_timestep=0.1, bool meter_scoring=true, bool simple_attractor=false, std::vector< double > y_vels=std::vector< double >(0), double stop_time_buffer=0.2, double sim_period=0.1, double angular_sim_granularity=0.025)
Constructs a trajectory controller.
bool heading_scoring_
Should we score based on the rollout approach or the heading approach.
bool dwa_
Should we use the dynamic window approach?
void reconfigure(BaseLocalPlannerConfig &cfg)
Reconfigures the trajectory planner.
Holds a trajectory generated by considering an x, y, and theta velocity.
Trajectory traj_two
Used for scoring trajectories.
std::vector< double > y_vels_
Y velocities to explore.
bool simple_attractor_
Enables simple attraction to a goal point.
double escape_reset_theta_
The distance the robot must travel before it can leave escape mode.
double backup_vel_
The velocity to use while backing up.
bool rotating_right
Booleans to keep track of the direction of rotation for the robot.
double lineCost(int x0, int x1, int y0, int y1)
double sim_time_
The number of seconds each trajectory is "rolled-out".
double heading_scoring_timestep_
How far to look ahead in time when we score a heading.
std::vector< geometry_msgs::PoseStamped > global_plan_
The global path for the robot to follow.
boost::mutex configuration_mutex_
friend class TrajectoryPlannerTest
std::vector< geometry_msgs::Point > footprint_spec_
The footprint specification of the robot.
geometry_msgs::Polygon toPolygon(std::vector< geometry_msgs::Point > pts)
bool stuck_right
Booleans to keep the robot from oscillating during rotation.
base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:24