47 #include <boost/algorithm/string.hpp> 59 void TrajectoryPlanner::reconfigure(BaseLocalPlannerConfig &cfg)
61 BaseLocalPlannerConfig config(cfg);
63 boost::mutex::scoped_lock l(configuration_mutex_);
65 acc_lim_x_ = config.acc_lim_x;
66 acc_lim_y_ = config.acc_lim_y;
67 acc_lim_theta_ = config.acc_lim_theta;
69 max_vel_x_ = config.max_vel_x;
70 min_vel_x_ = config.min_vel_x;
72 max_vel_th_ = config.max_vel_theta;
73 min_vel_th_ = config.min_vel_theta;
74 min_in_place_vel_th_ = config.min_in_place_vel_theta;
76 sim_time_ = config.sim_time;
77 sim_granularity_ = config.sim_granularity;
78 angular_sim_granularity_ = config.angular_sim_granularity;
80 pdist_scale_ = config.pdist_scale;
81 gdist_scale_ = config.gdist_scale;
82 occdist_scale_ = config.occdist_scale;
86 double resolution = costmap_.getResolution();
87 gdist_scale_ *= resolution;
88 pdist_scale_ *= resolution;
89 occdist_scale_ *= resolution;
92 oscillation_reset_dist_ = config.oscillation_reset_dist;
93 escape_reset_dist_ = config.escape_reset_dist;
94 escape_reset_theta_ = config.escape_reset_theta;
96 vx_samples_ = config.vx_samples;
97 vtheta_samples_ = config.vtheta_samples;
99 if (vx_samples_ <= 0) {
100 config.vx_samples = 1;
101 vx_samples_ = config.vx_samples;
102 ROS_WARN(
"You've specified that you don't want any samples in the x dimension. We'll at least assume that you want to sample one value... so we're going to set vx_samples to 1 instead");
104 if(vtheta_samples_ <= 0) {
105 config.vtheta_samples = 1;
106 vtheta_samples_ = config.vtheta_samples;
107 ROS_WARN(
"You've specified that you don't want any samples in the theta dimension. We'll at least assume that you want to sample one value... so we're going to set vtheta_samples to 1 instead");
110 heading_lookahead_ = config.heading_lookahead;
112 holonomic_robot_ = config.holonomic_robot;
114 backup_vel_ = config.escape_vel;
118 heading_scoring_ = config.heading_scoring;
119 heading_scoring_timestep_ = config.heading_scoring_timestep;
121 simple_attractor_ = config.simple_attractor;
124 string y_string = config.y_vels;
125 vector<string> y_strs;
126 boost::split(y_strs, y_string, boost::is_any_of(
", "), boost::token_compress_on);
128 vector<double>y_vels;
129 for(vector<string>::iterator it=y_strs.begin(); it != y_strs.end(); ++it) {
130 istringstream iss(*it);
133 y_vels.push_back(temp);
141 TrajectoryPlanner::TrajectoryPlanner(
WorldModel& world_model,
143 std::vector<geometry_msgs::Point> footprint_spec,
144 double acc_lim_x,
double acc_lim_y,
double acc_lim_theta,
145 double sim_time,
double sim_granularity,
146 int vx_samples,
int vtheta_samples,
147 double pdist_scale,
double gdist_scale,
double occdist_scale,
148 double heading_lookahead,
double oscillation_reset_dist,
149 double escape_reset_dist,
double escape_reset_theta,
150 bool holonomic_robot,
151 double max_vel_x,
double min_vel_x,
152 double max_vel_th,
double min_vel_th,
double min_in_place_vel_th,
154 bool dwa,
bool heading_scoring,
double heading_scoring_timestep,
bool meter_scoring,
bool simple_attractor,
155 vector<double> y_vels,
double stop_time_buffer,
double sim_period,
double angular_sim_granularity)
156 : path_map_(costmap.getSizeInCellsX(), costmap.getSizeInCellsY()),
157 goal_map_(costmap.getSizeInCellsX(), costmap.getSizeInCellsY()),
159 world_model_(world_model), footprint_spec_(footprint_spec),
160 sim_time_(sim_time), sim_granularity_(sim_granularity), angular_sim_granularity_(angular_sim_granularity),
161 vx_samples_(vx_samples), vtheta_samples_(vtheta_samples),
162 pdist_scale_(pdist_scale), gdist_scale_(gdist_scale), occdist_scale_(occdist_scale),
163 acc_lim_x_(acc_lim_x), acc_lim_y_(acc_lim_y), acc_lim_theta_(acc_lim_theta),
164 prev_x_(0), prev_y_(0), escape_x_(0), escape_y_(0), escape_theta_(0), heading_lookahead_(heading_lookahead),
165 oscillation_reset_dist_(oscillation_reset_dist), escape_reset_dist_(escape_reset_dist),
166 escape_reset_theta_(escape_reset_theta), holonomic_robot_(holonomic_robot),
167 max_vel_x_(max_vel_x), min_vel_x_(min_vel_x),
168 max_vel_th_(max_vel_th), min_vel_th_(min_vel_th), min_in_place_vel_th_(min_in_place_vel_th),
169 backup_vel_(backup_vel),
170 dwa_(dwa), heading_scoring_(heading_scoring), heading_scoring_timestep_(heading_scoring_timestep),
171 simple_attractor_(simple_attractor), y_vels_(y_vels), stop_time_buffer_(stop_time_buffer), sim_period_(sim_period)
214 double x,
double y,
double theta,
215 double vx,
double vy,
double vtheta,
216 double vx_samp,
double vy_samp,
double vtheta_samp,
217 double acc_x,
double acc_y,
double acc_theta,
218 double impossible_cost,
226 double theta_i = theta;
228 double vx_i, vy_i, vtheta_i;
235 double vmag = hypot(vx_samp, vy_samp);
261 double path_dist = 0.0;
262 double goal_dist = 0.0;
263 double occ_cost = 0.0;
264 double heading_diff = 0.0;
266 for(
int i = 0; i < num_steps; ++i){
268 unsigned int cell_x, cell_y;
280 if(footprint_cost < 0){
306 occ_cost = std::max(std::max(occ_cost, footprint_cost),
double(
costmap_.
getCost(cell_x, cell_y)));
316 bool update_path_and_goal_distances =
true;
322 heading_diff =
headingDiff(cell_x, cell_y, x_i, y_i, theta_i);
324 update_path_and_goal_distances =
false;
328 if (update_path_and_goal_distances) {
330 path_dist =
path_map_(cell_x, cell_y).target_dist;
331 goal_dist =
goal_map_(cell_x, cell_y).target_dist;
334 if(impossible_cost <= goal_dist || impossible_cost <= path_dist){
372 unsigned int goal_cell_x, goal_cell_y;
377 if (
lineCost(cell_x, goal_cell_x, cell_y, goal_cell_y) >= 0) {
391 int deltax = abs(x1 - x0);
392 int deltay = abs(y1 - y0);
396 int xinc1, xinc2, yinc1, yinc2;
397 int den, num, numadd, numpixels;
399 double line_cost = 0.0;
400 double point_cost = -1.0;
424 if (deltax >= deltay)
441 for (
int curpixel = 0; curpixel <= numpixels; curpixel++) {
444 if (point_cost < 0) {
448 if (line_cost < point_cost) {
449 line_cost = point_cost;
468 if(cost == LETHAL_OBSTACLE || cost == INSCRIBED_INFLATED_OBSTACLE || cost == NO_INFORMATION){
477 for(
unsigned int i = 0; i < new_plan.size(); ++i){
498 ROS_DEBUG(
"Path/Goal distance computed");
503 double vtheta,
double vx_samp,
double vy_samp,
double vtheta_samp){
506 double cost =
scoreTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp);
512 ROS_WARN(
"Invalid Trajectory %f, %f, %f, cost: %f", vx_samp, vy_samp, vtheta_samp, cost);
519 double vtheta,
double vx_samp,
double vy_samp,
double vtheta_samp) {
524 vx_samp, vy_samp, vtheta_samp,
529 return double( t.
cost_ );
536 double vx,
double vy,
double vtheta,
537 double acc_x,
double acc_y,
double acc_theta) {
540 double min_vel_x, min_vel_theta;
544 max_vel_x =
min( max_vel_x, final_goal_dist /
sim_time_ );
550 min_vel_x = max(
min_vel_x_, vx - acc_x * sim_period_);
552 max_vel_theta =
min(
max_vel_th_, vtheta + acc_theta * sim_period_);
553 min_vel_theta = max(
min_vel_th_, vtheta - acc_theta * sim_period_);
556 min_vel_x = max(
min_vel_x_, vx - acc_x * sim_time_);
559 min_vel_theta = max(
min_vel_th_, vtheta - acc_theta * sim_time_);
564 double dvx = (max_vel_x - min_vel_x) / (
vx_samples_ - 1);
565 double dvtheta = (max_vel_theta - min_vel_theta) / (
vtheta_samples_ - 1);
567 double vx_samp = min_vel_x;
568 double vtheta_samp = min_vel_theta;
569 double vy_samp = 0.0;
573 best_traj->
cost_ = -1.0;
576 comp_traj->
cost_ = -1.0;
590 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
595 best_traj = comp_traj;
599 vtheta_samp = min_vel_theta;
603 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
608 best_traj = comp_traj;
611 vtheta_samp += dvtheta;
623 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
628 best_traj = comp_traj;
636 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
641 best_traj = comp_traj;
648 vtheta_samp = min_vel_theta;
660 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp_limited,
661 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
665 if(comp_traj->
cost_ >= 0
666 && (comp_traj->
cost_ <= best_traj->
cost_ || best_traj->
cost_ < 0 || best_traj->
yv_ != 0.0)
667 && (vtheta_samp > dvtheta || vtheta_samp < -1 * dvtheta)){
668 double x_r, y_r, th_r;
672 unsigned int cell_x, cell_y;
676 double ahead_gdist =
goal_map_(cell_x, cell_y).target_dist;
677 if (ahead_gdist < heading_dist) {
681 best_traj = comp_traj;
683 heading_dist = ahead_gdist;
688 best_traj = comp_traj;
690 heading_dist = ahead_gdist;
696 vtheta_samp += dvtheta;
700 if (best_traj->
cost_ >= 0) {
702 if ( ! (best_traj->
xv_ > 0)) {
708 }
else if (best_traj->
thetav_ > 0) {
713 }
else if(best_traj->
yv_ > 0) {
718 }
else if(best_traj->
yv_ < 0){
754 vtheta_samp = min_vel_theta;
758 for(
unsigned int i = 0; i <
y_vels_.size(); ++i){
763 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
767 double x_r, y_r, th_r;
771 unsigned int cell_x, cell_y;
775 double ahead_gdist =
goal_map_(cell_x, cell_y).target_dist;
776 if (ahead_gdist < heading_dist) {
780 best_traj = comp_traj;
782 heading_dist = ahead_gdist;
787 best_traj = comp_traj;
789 heading_dist = ahead_gdist;
798 if (best_traj->
cost_ >= 0) {
799 if (!(best_traj->
xv_ > 0)) {
805 }
else if(best_traj->
thetav_ > 0) {
810 }
else if(best_traj->
yv_ > 0) {
815 }
else if(best_traj->
yv_ < 0) {
853 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
866 best_traj = comp_traj;
898 if(best_traj->
cost_ == -1.0)
899 best_traj->
cost_ = 1.0;
909 Eigen::Vector3f pos(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(),
tf::getYaw(global_pose.getRotation()));
910 Eigen::Vector3f vel(global_vel.getOrigin().getX(), global_vel.getOrigin().getY(),
tf::getYaw(global_vel.getRotation()));
917 std::vector<base_local_planner::Position2DInt> footprint_list =
925 for (
unsigned int i = 0; i < footprint_list.size(); ++i) {
926 path_map_(footprint_list[i].
x, footprint_list[i].
y).within_robot =
true;
932 ROS_DEBUG(
"Path/Goal distance computed");
936 vel[0], vel[1], vel[2],
966 drive_velocities.setIdentity();
970 drive_velocities.setOrigin(start);
973 drive_velocities.setBasis(matrix);
double unreachableCellCosts()
int vx_samples_
The number of samples we'll take in the x dimenstion of the control space.
double angular_sim_granularity_
The distance between angular simulation points.
virtual double footprintCost(const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)=0
Subclass will implement this method to check a footprint at a given position and orientation for lega...
double computeNewYPosition(double yi, double vx, double vy, double theta, double dt)
Compute y position based on velocity.
double heading_scoring_timestep_
How far to look ahead in time when we score a heading.
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.
int vtheta_samples_
The number of samples we'll take in the theta dimension of the control space.
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
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.
void setTargetCells(const costmap_2d::Costmap2D &costmap, const std::vector< geometry_msgs::PoseStamped > &global_plan)
Update what cells are considered path based on the global plan.
base_local_planner::FootprintHelper footprint_helper_
double computeNewXPosition(double xi, double vx, double vy, double theta, double dt)
Compute x position based on velocity.
double oscillation_reset_dist_
The distance the robot must travel before it can explore rotational velocities that were unsuccessful...
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...
bool stuck_right
Booleans to keep the robot from oscillating during rotation.
bool within_robot
Mark for cells within the robot footprint.
const costmap_2d::Costmap2D & costmap_
Provides access to cost map information.
double heading_lookahead_
How far the robot should look ahead of itself when differentiating between different rotational veloc...
static double getYaw(const Quaternion &bt_q)
double goal_y_
The goal distance was last computed from.
~TrajectoryPlanner()
Destructs a trajectory controller.
bool holonomic_robot_
Is the robot holonomic or not?
double min_in_place_vel_th_
Velocity limits for the controller.
double computeNewThetaPosition(double thetai, double vth, double dt)
Compute orientation based on velocity.
double lineCost(int x0, int x1, int y0, int y1)
MapGrid path_map_
The local map grid where we propagate path distance.
double prev_y_
Used to calculate the distance the robot has traveled before reseting oscillation booleans...
bool dwa_
Should we use the dynamic window approach?
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 sim_time_
The number of seconds each trajectory is "rolled-out".
double cost_
The cost/score of the trajectory.
double backup_vel_
The velocity to use while backing up.
TFSIMD_FORCE_INLINE const tfScalar & y() const
double sim_period_
The number of seconds to use to compute max/min vels for dwa.
bool simple_attractor_
Enables simple attraction to a goal point.
void setRotation(const Quaternion &q)
std::vector< double > y_vels_
Y velocities to explore.
double escape_reset_theta_
The distance the robot must travel before it can leave escape mode.
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.
void resetPoints()
Clear the trajectory's points.
unsigned char getCost(unsigned int mx, unsigned int my) const
double escape_theta_
Used to calculate the distance the robot has traveled before reseting escape booleans.
WorldModel & world_model_
The world model that the controller uses for collision detection.
std::vector< geometry_msgs::PoseStamped > global_plan_
The global path for the robot to follow.
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
boost::mutex configuration_mutex_
static Quaternion createQuaternionFromYaw(double yaw)
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 occdist_scale_
Scaling factors for the controller's cost function.
MapGrid goal_map_
The local map grid where we propagate goal distance.
bool escaping_
Boolean to keep track of whether we're in escape mode.
double headingDiff(int cell_x, int cell_y, double x, double y, double heading)
double thetav_
The x, y, and theta velocities of the trajectory.
TFSIMD_FORCE_INLINE const tfScalar & x() const
double sim_granularity_
The distance between simulation points.
double acc_lim_theta_
The acceleration limits of the robot.
double circumscribed_radius_
double pointCost(int x, int y)
double escape_reset_dist_
void addPoint(double x, double y, double th)
Add a point to the end of a trajectory.
Trajectory traj_two
Used for scoring trajectories.
void updatePlan(const std::vector< geometry_msgs::PoseStamped > &new_plan, bool compute_dists=false)
Update the plan that the controller is following.
void getEndpoint(double &x, double &y, double &th) const
Get the last point of the trajectory.
double target_dist
Distance to planner's path.
An interface the trajectory controller uses to interact with the world regardless of the underlying w...
double final_goal_y_
The end position of the plan.
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.
bool heading_scoring_
Should we score based on the rollout approach or the heading approach.
bool stuck_right_strafe
Booleans to keep the robot from oscillating during strafing.
std::vector< geometry_msgs::Point > footprint_spec_
The footprint specification of the robot.
Trajectory findBestPath(tf::Stamped< tf::Pose > global_pose, tf::Stamped< tf::Pose > global_vel, tf::Stamped< tf::Pose > &drive_velocities)
Given the current position, orientation, and velocity of the robot, return a trajectory to follow...
Stores path distance and goal distance information used for scoring trajectories. ...
double computeNewVelocity(double vg, double vi, double a_max, double dt)
Compute velocity based on acceleration.
void getLocalGoal(double &x, double &y)
Accessor for the goal the robot is currently pursuing in world corrdinates.
bool strafe_left
Booleans to keep track of strafe direction for the robot.
void setLocalGoal(const costmap_2d::Costmap2D &costmap, const std::vector< geometry_msgs::PoseStamped > &global_plan)
Update what cell is considered the next local goal.
void resetPathDist()
reset path distance fields for all cells
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
bool rotating_right
Booleans to keep track of the direction of rotation for the robot.
def shortest_angular_distance(from_angle, to_angle)
Holds a trajectory generated by considering an x, y, and theta velocity.
void calculateMinAndMaxDistances(const std::vector< geometry_msgs::Point > &footprint, double &min_dist, double &max_dist)