69 initialize(cfg, obstacles, robot_model, visual, via_points);
139 g2o::Factory* factory = g2o::Factory::instance();
140 factory->registerType(
"VERTEX_POSE",
new g2o::HyperGraphElementCreator<VertexPose>);
141 factory->registerType(
"VERTEX_TIMEDIFF",
new g2o::HyperGraphElementCreator<VertexTimeDiff>);
143 factory->registerType(
"EDGE_TIME_OPTIMAL",
new g2o::HyperGraphElementCreator<EdgeTimeOptimal>);
144 factory->registerType(
"EDGE_SHORTEST_PATH",
new g2o::HyperGraphElementCreator<EdgeShortestPath>);
145 factory->registerType(
"EDGE_VELOCITY",
new g2o::HyperGraphElementCreator<EdgeVelocity>);
146 factory->registerType(
"EDGE_VELOCITY_HOLONOMIC",
new g2o::HyperGraphElementCreator<EdgeVelocityHolonomic>);
147 factory->registerType(
"EDGE_ACCELERATION",
new g2o::HyperGraphElementCreator<EdgeAcceleration>);
148 factory->registerType(
"EDGE_ACCELERATION_START",
new g2o::HyperGraphElementCreator<EdgeAccelerationStart>);
149 factory->registerType(
"EDGE_ACCELERATION_GOAL",
new g2o::HyperGraphElementCreator<EdgeAccelerationGoal>);
150 factory->registerType(
"EDGE_ACCELERATION_HOLONOMIC",
new g2o::HyperGraphElementCreator<EdgeAccelerationHolonomic>);
151 factory->registerType(
"EDGE_ACCELERATION_HOLONOMIC_START",
new g2o::HyperGraphElementCreator<EdgeAccelerationHolonomicStart>);
152 factory->registerType(
"EDGE_ACCELERATION_HOLONOMIC_GOAL",
new g2o::HyperGraphElementCreator<EdgeAccelerationHolonomicGoal>);
153 factory->registerType(
"EDGE_KINEMATICS_DIFF_DRIVE",
new g2o::HyperGraphElementCreator<EdgeKinematicsDiffDrive>);
154 factory->registerType(
"EDGE_KINEMATICS_CARLIKE",
new g2o::HyperGraphElementCreator<EdgeKinematicsCarlike>);
155 factory->registerType(
"EDGE_OBSTACLE",
new g2o::HyperGraphElementCreator<EdgeObstacle>);
156 factory->registerType(
"EDGE_INFLATED_OBSTACLE",
new g2o::HyperGraphElementCreator<EdgeInflatedObstacle>);
157 factory->registerType(
"EDGE_DYNAMIC_OBSTACLE",
new g2o::HyperGraphElementCreator<EdgeDynamicObstacle>);
158 factory->registerType(
"EDGE_VIA_POINT",
new g2o::HyperGraphElementCreator<EdgeViaPoint>);
159 factory->registerType(
"EDGE_PREFER_ROTDIR",
new g2o::HyperGraphElementCreator<EdgePreferRotDir>);
170 static boost::once_flag flag = BOOST_ONCE_INIT;
176 linear_solver->setBlockOrdering(
true);
177 std::unique_ptr<TEBBlockSolver> block_solver(
new TEBBlockSolver(std::move(linear_solver)));
178 g2o::OptimizationAlgorithmLevenberg* solver =
new g2o::OptimizationAlgorithmLevenberg(std::move(block_solver));
180 optimizer->setAlgorithm(solver);
182 optimizer->initMultiThreading();
189 double obst_cost_scale,
double viapoint_cost_scale,
bool alternative_time_cost)
194 bool success =
false;
197 double weight_multiplier = 1.0;
205 for(
int i=0; i<iterations_outerloop; ++i)
228 if (compute_cost_afterwards && i==iterations_outerloop-1)
242 vel_start_.second.linear.x = vel_start.linear.x;
243 vel_start_.second.linear.y = vel_start.linear.y;
244 vel_start_.second.angular.z = vel_start.angular.z;
263 PoseSE2 start_(initial_plan.front().pose);
264 PoseSE2 goal_(initial_plan.back().pose);
271 ROS_DEBUG(
"New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
293 return plan(start_, goal_, start_vel);
312 ROS_DEBUG(
"New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
333 ROS_WARN(
"Cannot build graph, because it is not empty. Call graphClear()!");
378 ROS_WARN(
"optimizeGraph(): Robot Max Velocity is smaller than 0.01m/s. Optimizing aborted...");
385 ROS_WARN(
"optimizeGraph(): TEB is empty or has too less elements. Skipping optimization.");
393 int iter =
optimizer_->optimize(no_iterations);
401 ROS_ERROR(
"optimizeGraph(): Optimization failed! iter=%i", iter);
419 v.second->edges().clear();
432 unsigned int id_counter = 0;
444 iter_obstacle->clear();
445 (iter_obstacle++)->reserve(
obstacles_->size());
458 Eigen::Matrix<double,1,1> information;
461 Eigen::Matrix<double,2,2> information_inflated;
464 information_inflated(0,1) = information_inflated(1,0) = 0;
468 auto create_edge = [inflated, &information, &information_inflated,
this] (
int index,
const Obstacle* obstacle) {
473 dist_bandpt_obst->setInformation(information_inflated);
481 dist_bandpt_obst->setInformation(information);
491 double left_min_dist = std::numeric_limits<double>::max();
492 double right_min_dist = std::numeric_limits<double>::max();
511 iter_obstacle->push_back(obst);
519 if (
cross2d(pose_orient, obst->getCentroid()) > 0)
521 if (dist < left_min_dist)
523 left_min_dist = dist;
524 left_obstacle = obst;
529 if (dist < right_min_dist)
531 right_min_dist = dist;
532 right_obstacle = obst;
538 iter_obstacle->push_back(left_obstacle);
540 iter_obstacle->push_back(right_obstacle);
551 create_edge(i, obst.get());
562 Eigen::Matrix<double,1,1> information;
565 Eigen::Matrix<double,2,2> information_inflated;
568 information_inflated(0,1) = information_inflated(1,0) = 0;
572 for (ObstContainer::const_iterator obst =
obstacles_->begin(); obst !=
obstacles_->end(); ++obst)
593 dist_bandpt_obst->setInformation(information_inflated);
601 dist_bandpt_obst->setInformation(information);
613 dist_bandpt_obst_n_r->setVertex(0,
teb_.
PoseVertex(index+neighbourIdx));
614 dist_bandpt_obst_n_r->setInformation(information_inflated);
621 dist_bandpt_obst_n_r->setVertex(0,
teb_.
PoseVertex(index+neighbourIdx));
622 dist_bandpt_obst_n_r->setInformation(information);
627 if ( index - neighbourIdx >= 0)
632 dist_bandpt_obst_n_l->setVertex(0,
teb_.
PoseVertex(index-neighbourIdx));
633 dist_bandpt_obst_n_l->setInformation(information_inflated);
640 dist_bandpt_obst_n_l->setVertex(0,
teb_.
PoseVertex(index-neighbourIdx));
641 dist_bandpt_obst_n_l->setInformation(information);
657 Eigen::Matrix<double,2,2> information;
660 information(0,1) = information(1,0) = 0;
662 for (ObstContainer::const_iterator obst =
obstacles_->begin(); obst !=
obstacles_->end(); ++obst)
664 if (!(*obst)->isDynamic())
673 dynobst_edge->setInformation(information);
686 int start_pose_idx = 0;
692 for (ViaPointContainer::const_iterator vp_it =
via_points_->begin(); vp_it !=
via_points_->end(); ++vp_it)
697 start_pose_idx = index+2;
711 ROS_DEBUG(
"TebOptimalPlanner::AddEdgesViaPoints(): skipping a via-point that is close or behind the current robot pose.");
715 Eigen::Matrix<double,1,1> information;
720 edge_viapoint->setInformation(information);
734 Eigen::Matrix<double,2,2> information;
737 information(0,1) = 0.0;
738 information(1,0) = 0.0;
740 for (
int i=0; i < n - 1; ++i)
746 velocity_edge->setInformation(information);
757 Eigen::Matrix<double,3,3> information;
763 for (
int i=0; i < n - 1; ++i)
769 velocity_edge->setInformation(information);
786 Eigen::Matrix<double,2,2> information;
799 acceleration_edge->setInformation(information);
805 for (
int i=0; i < n - 2; ++i)
813 acceleration_edge->setInformation(information);
826 acceleration_edge->setInformation(information);
833 Eigen::Matrix<double,3,3> information;
847 acceleration_edge->setInformation(information);
853 for (
int i=0; i < n - 2; ++i)
861 acceleration_edge->setInformation(information);
874 acceleration_edge->setInformation(information);
888 Eigen::Matrix<double,1,1> information;
895 timeoptimal_edge->setInformation(information);
906 Eigen::Matrix<double,1,1> information;
914 shortest_path_edge->setInformation(information);
928 Eigen::Matrix<double,2,2> information_kinematics;
929 information_kinematics.fill(0.0);
938 kinematics_edge->setInformation(information_kinematics);
950 Eigen::Matrix<double,2,2> information_kinematics;
951 information_kinematics.fill(0.0);
960 kinematics_edge->setInformation(information_kinematics);
981 ROS_WARN(
"TebOptimalPlanner::AddEdgesPreferRotDir(): unsupported RotType selected. Skipping edge creation.");
986 Eigen::Matrix<double,1,1> information_rotdir;
994 rotdir_edge->setInformation(information_rotdir);
1007 Eigen::Matrix<double,2,2> information;
1010 information(0,1) = information(1,0) = 0;
1016 for (
const ObstaclePtr obstacle : (*iter_obstacle++))
1022 edge->setInformation(information);
1035 auto stats_vector =
optimizer_->batchStatistics();
1038 if (stats_vector.empty())
1042 const auto last_iter_stats = stats_vector.back();
1050 bool graph_exist_flag(
false);
1060 graph_exist_flag =
true;
1067 if (alternative_time_cost)
1076 for (std::vector<g2o::OptimizableGraph::Edge*>::const_iterator it =
optimizer_->activeEdges().begin(); it!=
optimizer_->activeEdges().end(); it++)
1078 double cur_cost = (*it)->chi2();
1080 if (dynamic_cast<EdgeObstacle*>(*it) !=
nullptr 1081 || dynamic_cast<EdgeInflatedObstacle*>(*it) !=
nullptr 1082 || dynamic_cast<EdgeDynamicObstacle*>(*it) !=
nullptr)
1084 cur_cost *= obst_cost_scale;
1086 else if (dynamic_cast<EdgeViaPoint*>(*it) !=
nullptr)
1088 cur_cost *= viapoint_cost_scale;
1090 else if (dynamic_cast<EdgeTimeOptimal*>(*it) !=
nullptr && alternative_time_cost)
1098 if (!graph_exist_flag)
1119 double dir = deltaS.dot(conf1dir);
1120 vx = (double)
g2o::sign(dir) * deltaS.norm()/dt;
1128 double cos_theta1 = std::cos(pose1.
theta());
1129 double sin_theta1 = std::sin(pose1.
theta());
1130 double p1_dx = cos_theta1*deltaS.x() + sin_theta1*deltaS.y();
1131 double p1_dy = -sin_theta1*deltaS.x() + cos_theta1*deltaS.y();
1137 double orientdiff = g2o::normalize_theta(pose2.
theta() - pose1.
theta());
1138 omega = orientdiff/dt;
1145 ROS_ERROR(
"TebOptimalPlanner::getVelocityCommand(): The trajectory contains less than 2 poses. Make sure to init and optimize/plan the trajectory fist.");
1153 for(
int counter = 0; counter < look_ahead_poses; ++counter)
1158 look_ahead_poses = counter + 1;
1164 ROS_ERROR(
"TebOptimalPlanner::getVelocityCommand() - timediff<=0 is invalid!");
1179 velocity_profile.resize( n+1 );
1182 velocity_profile.front().linear.z = 0;
1183 velocity_profile.front().angular.x = velocity_profile.front().angular.y = 0;
1184 velocity_profile.front().linear.x =
vel_start_.second.linear.x;
1185 velocity_profile.front().linear.y =
vel_start_.second.linear.y;
1186 velocity_profile.front().angular.z =
vel_start_.second.angular.z;
1188 for (
int i=1; i<n; ++i)
1190 velocity_profile[i].linear.z = 0;
1191 velocity_profile[i].angular.x = velocity_profile[i].angular.y = 0;
1196 velocity_profile.back().linear.z = 0;
1197 velocity_profile.back().angular.x = velocity_profile.back().angular.y = 0;
1198 velocity_profile.back().linear.x =
vel_goal_.second.linear.x;
1199 velocity_profile.back().linear.y =
vel_goal_.second.linear.y;
1200 velocity_profile.back().angular.z =
vel_goal_.second.angular.z;
1207 trajectory.resize(n);
1212 double curr_time = 0;
1215 TrajectoryPointMsg&
start = trajectory.front();
1217 start.velocity.linear.z = 0;
1218 start.velocity.angular.x = start.velocity.angular.y = 0;
1219 start.velocity.linear.x =
vel_start_.second.linear.x;
1220 start.velocity.linear.y =
vel_start_.second.linear.y;
1221 start.velocity.angular.z =
vel_start_.second.angular.z;
1222 start.time_from_start.fromSec(curr_time);
1227 for (
int i=1; i < n-1; ++i)
1229 TrajectoryPointMsg&
point = trajectory[i];
1231 point.velocity.linear.z = 0;
1232 point.velocity.angular.x = point.velocity.angular.y = 0;
1233 double vel1_x, vel1_y, vel2_x, vel2_y, omega1, omega2;
1236 point.velocity.linear.x = 0.5*(vel1_x+vel2_x);
1237 point.velocity.linear.y = 0.5*(vel1_y+vel2_y);
1238 point.velocity.angular.z = 0.5*(omega1+omega2);
1239 point.time_from_start.fromSec(curr_time);
1245 TrajectoryPointMsg& goal = trajectory.back();
1247 goal.velocity.linear.z = 0;
1248 goal.velocity.angular.x = goal.velocity.angular.y = 0;
1249 goal.velocity.linear.x =
vel_goal_.second.linear.x;
1250 goal.velocity.linear.y =
vel_goal_.second.linear.y;
1251 goal.velocity.angular.z =
vel_goal_.second.angular.z;
1252 goal.time_from_start.fromSec(curr_time);
1257 double inscribed_radius,
double circumscribed_radius,
int look_ahead_idx)
1259 if (look_ahead_idx < 0 || look_ahead_idx >=
teb().sizePoses())
1262 for (
int i=0; i <= look_ahead_idx; ++i)
1275 if (i<look_ahead_idx)
1277 double delta_rot = g2o::normalize_theta(g2o::normalize_theta(
teb().
Pose(i+1).theta()) -
1278 g2o::normalize_theta(
teb().
Pose(i).theta()));
1283 std::ceil(delta_dist.norm() / inscribed_radius)) - 1;
1287 intermediate_pose.
position() = intermediate_pose.
position() + delta_dist / (n_additional_samples + 1.0);
1288 intermediate_pose.
theta() = g2o::normalize_theta(intermediate_pose.
theta() +
1289 delta_rot / (n_additional_samples + 1.0));
1290 if ( costmap_model->
footprintCost(intermediate_pose.
x(), intermediate_pose.
y(), intermediate_pose.
theta(),
1291 footprint_spec, inscribed_radius, circumscribed_radius) == -1 )
static void registerG2OTypes()
Register the vertices and edges defined for the TEB to the g2o::Factory.
Edge defining the cost function for limiting the translational and rotational acceleration at the end...
void setVelocityStart(const geometry_msgs::Twist &vel_start)
Set the initial velocity at the trajectory's start pose (e.g. the robot's velocity) [twist overload]...
bool optimizeGraph(int no_iterations, bool clear_after=true)
Optimize the previously constructed hyper-graph to deform / optimize the TEB.
void setVelocityGoalFree()
Set the desired final velocity at the trajectory's goal pose to be the maximum velocity limit...
Edge defining the cost function for keeping a distance from dynamic (moving) obstacles.
std::pair< bool, geometry_msgs::Twist > vel_start_
Store the initial velocity at the start pose.
double max_vel_y
Maximum strafing velocity of the robot (should be zero for non-holonomic robots!) ...
double weight_velocity_obstacle_ratio
Optimization weight for satisfying a maximum allowed velocity with respect to the distance to a stati...
TimedElasticBand & teb()
Access the internal TimedElasticBand trajectory.
int max_samples
Maximum number of samples; Warning: if too small the discretization/resolution might not be sufficien...
void clearGraph()
Clear an existing internal hyper-graph.
void getFullTrajectory(std::vector< TrajectoryPointMsg > &trajectory) const
Return the complete trajectory including poses, velocity profiles and temporal information.
virtual bool isTrajectoryFeasible(base_local_planner::CostmapModel *costmap_model, const std::vector< geometry_msgs::Point > &footprint_spec, double inscribed_radius=0.0, double circumscribed_radius=0.0, int look_ahead_idx=-1)
Check whether the planned trajectory is feasible or not.
double weight_adapt_factor
Some special weights (currently 'weight_obstacle') are repeatedly scaled by this factor in each outer...
bool allow_init_with_backwards_motion
If true, the underlying trajectories might be initialized with backwards motions in case the goal is ...
Edge defining the cost function for minimizing the Euclidean distance between two consectuive poses...
Eigen::Vector2d orientationUnitVec() const
Return the unit vector of the current orientation.
void setVisualization(TebVisualizationPtr visualization)
Register a TebVisualization class to enable visiualization routines (e.g. publish the local plan and ...
std::pair< bool, geometry_msgs::Twist > vel_goal_
Store the final velocity at the goal pose.
void AddEdgesShortestPath()
Add all edges (local cost functions) for minimizing the path length.
double min_obstacle_dist
Minimum desired separation from obstacles.
virtual void visualize()
Publish the local plan and pose sequence via ros topics (e.g. subscribe with rviz).
double weight_prefer_rotdir
Optimization weight for preferring a specific turning direction (-> currently only activated if an os...
Edge defining the cost function for limiting the translational and rotational acceleration at the end...
Edge defining the cost function for penalzing a specified turning direction, in particular left resp...
Eigen::Vector2d & position()
Access the 2D position part.
double cross2d(const V1 &v1, const V2 &v2)
Calculate the 2d cross product (returns length of the resulting vector along the z-axis in 3d) ...
double force_reinit_new_goal_angular
Reinitialize the trajectory if a previous goal is updated with an angular difference of more than the...
void setTebConfig(const TebConfig &cfg)
Assign the TebConfig class for parameters.
Edge defining the cost function for minimizing transition time of the trajectory. ...
void AddEdgesTimeOptimal()
Add all edges (local cost functions) for minimizing the transition time (resp. minimize time differen...
double dt_hysteresis
Hysteresis for automatic resizing depending on the current temporal resolution (dt): usually 10% of d...
Config class for the teb_local_planner and its components.
void AddEdgesAcceleration()
Add all edges (local cost functions) for limiting the translational and angular acceleration.
void setParameters(const TebConfig &cfg, const BaseRobotFootprintModel *robot_model, const Obstacle *obstacle)
Set all parameters at once.
double weight_max_vel_theta
Optimization weight for satisfying the maximum allowed angular velocity.
boost::shared_ptr< g2o::SparseOptimizer > optimizer()
Access the internal g2o optimizer.
void setInitialVelocity(const geometry_msgs::Twist &vel_start)
Set the initial velocity that is taken into account for calculating the acceleration.
Edge defining the cost function for limiting the translational and rotational acceleration.
Edge defining the cost function for limiting the translational and rotational acceleration at the beg...
bool initTrajectoryToGoal(const PoseSE2 &start, const PoseSE2 &goal, double diststep=0, double max_vel_x=0.5, int min_samples=3, bool guess_backwards_motion=false)
Initialize a trajectory between a given start and goal pose.
void setVelocityGoal(const geometry_msgs::Twist &vel_goal)
Set the desired final velocity at the trajectory's goal pose.
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
void setTebConfig(const TebConfig &cfg)
Assign the TebConfig class for parameters.
double min_turning_radius
Minimum turning radius of a carlike robot (diff-drive robot: zero);.
double & x()
Access the x-coordinate the pose.
Edge defining the cost function for limiting the translational and rotational velocity.
Edge defining the cost function for keeping a minimum distance from obstacles.
void setParameters(const TebConfig &cfg, const BaseRobotFootprintModel *robot_model, const Obstacle *obstacle)
Set all parameters at once.
struct teb_local_planner::TebConfig::Trajectory trajectory
Trajectory related parameters.
PoseSE2 & BackPose()
Access the last PoseSE2 in the pose sequence.
TebVisualizationPtr visual
double weight_max_vel_y
Optimization weight for satisfying the maximum allowed strafing velocity (in use only for holonomic r...
void AddEdgesVelocity()
Add all edges (local cost functions) for limiting the translational and angular velocity.
virtual bool getVelocityCommand(double &vx, double &vy, double &omega, int look_ahead_poses) const
Get the velocity command from a previously optimized plan to control the robot at the current samplin...
double weight_kinematics_turning_radius
Optimization weight for enforcing a minimum turning radius (carlike robots)
bool hasDiverged() const override
Returns true if the planner has diverged.
bool legacy_obstacle_association
If true, the old association strategy is used (for each obstacle, find the nearest TEB pose)...
double weight_acc_lim_x
Optimization weight for satisfying the maximum allowed translational acceleration.
void computeCurrentCost(double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false)
Compute the cost vector of a given optimization problen (hyper-graph must exist). ...
void setInitialVelocity(const geometry_msgs::Twist &vel_start)
Set the initial velocity that is taken into account for calculating the acceleration.
Edge defining the cost function for limiting the translational and rotational acceleration.
void AddEdgesPreferRotDir()
Add all edges (local cost functions) for prefering a specifiy turning direction (by penalizing the ot...
double weight_acc_lim_y
Optimization weight for satisfying the maximum allowed strafing acceleration (in use only for holonom...
virtual ~TebOptimalPlanner()
Destruct the optimal planner.
bool optimization_activate
Activate the optimization.
void toPoseMsg(geometry_msgs::Pose &pose) const
Convert PoseSE2 to a geometry_msgs::Pose.
void updateRobotModel(RobotFootprintModelPtr robot_model)
virtual bool plan(const std::vector< geometry_msgs::PoseStamped > &initial_plan, const geometry_msgs::Twist *start_vel=NULL, bool free_goal_vel=false)
Plan a trajectory based on an initial reference plan.
bool buildGraph(double weight_multiplier=1.0)
Build the hyper-graph representing the TEB optimization problem.
void updateAndPruneTEB(boost::optional< const PoseSE2 &> new_start, boost::optional< const PoseSE2 &> new_goal, int min_samples=3)
Hot-Start from an existing trajectory with updated start and goal poses.
void AddTEBVertices()
Add all relevant vertices to the hyper-graph as optimizable variables.
ObstContainer * obstacles_
Store obstacles that are relevant for planning.
TebVisualizationPtr visualization_
Instance of the visualization class.
g2o::BlockSolver< g2o::BlockSolverTraits<-1, -1 > > TEBBlockSolver
Typedef for the block solver utilized for optimization.
double teb_autosize
Enable automatic resizing of the trajectory w.r.t to the temporal resolution (recommended) ...
Edge defining the cost function for keeping a minimum distance from obstacles.
bool via_points_ordered
If true, the planner adheres to the order of via-points in the storage container. ...
double obstacle_association_force_inclusion_factor
The non-legacy obstacle association technique tries to connect only relevant obstacles with the discr...
double weight_max_vel_x
Optimization weight for satisfying the maximum allowed translational velocity.
double force_reinit_new_goal_dist
Reinitialize the trajectory if a previous goal is updated with a seperation of more than the specifie...
double dt_ref
Desired temporal resolution of the trajectory (should be in the magniture of the underlying control r...
void setTebConfig(const TebConfig &cfg)
Assign the TebConfig class for parameters.
void setGoalVelocity(const geometry_msgs::Twist &vel_goal)
Set the goal / final velocity that is taken into account for calculating the acceleration.
Edge defining the cost function for limiting the translational and rotational velocity according to x...
RotType
Symbols for left/none/right rotations.
void AddEdgesVelocityObstacleRatio()
Add all edges (local cost function) for reducing the velocity of a vertex due to its associated obsta...
void AddEdgesViaPoints()
Add all edges (local cost functions) related to minimizing the distance to via-points.
double min_resolution_collision_check_angular
Edge defining the cost function for keeping a minimum distance from inflated obstacles.
bool initialized_
Keeps track about the correct initialization of this class.
void AddEdgesDynamicObstacles(double weight_multiplier=1.0)
Add all edges (local cost functions) related to keeping a distance from dynamic (moving) obstacles...
#define ROS_ASSERT_MSG(cond,...)
double weight_inflation
Optimization weight for the inflation penalty (should be small)
double & TimeDiff(int index)
Access the time difference at pos index of the time sequence.
std::vector< ObstaclePtr > ObstContainer
Abbrev. for containers storing multiple obstacles.
int divergence_detection_max_chi_squared
Maximum acceptable Mahalanobis distance above which it is assumed that the optimization diverged...
double weight_obstacle
Optimization weight for satisfying a minimum separation from obstacles.
bool optimized_
This variable is true as long as the last optimization has been completed successful.
void setParameters(const TebConfig &cfg, const BaseRobotFootprintModel *robot_model, const Obstacle *obstacle)
Set all parameters at once.
double max_vel_theta
Maximum angular velocity of the robot.
TebOptimalPlanner()
Default constructor.
Edge defining the cost function for limiting the translational and rotational acceleration at the beg...
void clearTimedElasticBand()
clear all poses and timediffs from the trajectory. The pose and timediff sequences will be empty and ...
bool isInit() const
Check whether the trajectory is initialized (nonzero pose and timediff sequences) ...
int sizeTimeDiffs() const
Get the length of the internal timediff sequence.
PoseSE2 & Pose(int index)
Access the pose at pos index of the pose sequence.
VertexTimeDiff * TimeDiffVertex(int index)
Access the vertex of a time difference at pos index for optimization purposes.
RobotFootprintModelPtr robot_model_
Robot model.
#define ROS_DEBUG_COND(cond,...)
double & y()
Access the y-coordinate the pose.
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
double & theta()
Access the orientation part (yaw angle) of the pose.
double obstacle_association_cutoff_factor
See obstacle_association_force_inclusion_factor, but beyond a multiple of [value]*min_obstacle_dist a...
void initialize(const TebConfig &cfg, ObstContainer *obstacles=NULL, RobotFootprintModelPtr robot_model=boost::make_shared< PointRobotFootprint >(), TebVisualizationPtr visual=TebVisualizationPtr(), const ViaPointContainer *via_points=NULL)
Initializes the optimal planner.
int no_inner_iterations
Number of solver iterations called in each outerloop iteration.
double weight_acc_lim_theta
Optimization weight for satisfying the maximum allowed angular acceleration.
double weight_shortest_path
Optimization weight for contracting the trajectory w.r.t. path length.
double weight_dynamic_obstacle_inflation
Optimization weight for the inflation penalty of dynamic obstacles (should be small) ...
int prevent_look_ahead_poses_near_goal
Index of the pose used to extract the velocity command.
int obstacle_poses_affected
The obstacle position is attached to the closest pose on the trajectory to reduce computational effor...
void setParameters(const TebConfig &cfg, const Eigen::Vector2d *via_point)
Set all parameters at once.
double weight_dynamic_obstacle
Optimization weight for satisfying a minimum separation from dynamic obstacles.
int findClosestTrajectoryPose(const Eigen::Ref< const Eigen::Vector2d > &ref_point, double *distance=NULL, int begin_idx=0) const
Find the closest point on the trajectory w.r.t. to a provided reference point.
void setParameters(const TebConfig &cfg, const BaseRobotFootprintModel *robot_model, const Obstacle *obstacle)
Set all parameters at once.
void getVelocityProfile(std::vector< geometry_msgs::Twist > &velocity_profile) const
Compute the velocity profile of the trajectory.
double weight_optimaltime
Optimization weight for contracting the trajectory w.r.t. transition time.
void extractVelocity(const PoseSE2 &pose1, const PoseSE2 &pose2, double dt, double &vx, double &vy, double &omega) const
Extract the velocity from consecutive poses and a time difference (including strafing velocity for ho...
VertexPose * PoseVertex(int index)
Access the vertex of a pose at pos index for optimization purposes.
virtual double footprintCost(const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)
bool global_plan_overwrite_orientation
Overwrite orientation of local subgoals provided by the global planner.
double weight_kinematics_nh
Optimization weight for satisfying the non-holonomic kinematics.
void setGoalVelocity(const geometry_msgs::Twist &vel_goal)
Set the goal / final velocity that is taken into account for calculating the acceleration.
struct teb_local_planner::TebConfig::Recovery recovery
Parameters related to recovery and backup strategies.
Edge defining the cost function for satisfying the non-holonomic kinematics of a carlike mobile robot...
std::vector< ObstContainer > obstacles_per_vertex_
Store the obstacles associated with the n-1 initial vertices.
Edge defining the cost function for pushing a configuration towards a via point.
double cost_
Store cost value of the current hyper-graph.
bool include_dynamic_obstacles
Specify whether the movement of dynamic obstacles should be predicted by a constant velocity model (t...
void AddEdgesKinematicsCarlike()
Add all edges (local cost functions) for satisfying kinematic constraints of a carlike robot...
bool divergence_detection_enable
True to enable divergence detection.
double weight_viapoint
Optimization weight for minimizing the distance to via-points.
ViaPointContainer via_points
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
int no_outer_iterations
Each outerloop iteration automatically resizes the trajectory and invokes the internal optimizer with...
int sizePoses() const
Get the length of the internal pose sequence.
struct teb_local_planner::TebConfig::Optimization optim
Optimization related parameters.
const ViaPointContainer * via_points_
Store via points for planning.
TimedElasticBand teb_
Actual trajectory object.
void autoResize(double dt_ref, double dt_hysteresis, int min_samples=3, int max_samples=1000, bool fast_mode=false)
Resize the trajectory by removing or inserting a (pose,dt) pair depending on a reference temporal res...
bool publish_feedback
Publish planner feedback containing the full trajectory and a list of active obstacles (should be ena...
boost::shared_ptr< g2o::SparseOptimizer > initOptimizer()
Initialize and configure the g2o sparse optimizer.
double acc_lim_y
Maximum strafing acceleration of the robot.
g2o::LinearSolverCSparse< TEBBlockSolver::PoseMatrixType > TEBLinearSolver
Typedef for the linear solver utilized for optimization.
void AddEdgesObstacles(double weight_multiplier=1.0)
Add all edges (local cost functions) related to keeping a distance from static obstacles.
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
const TebConfig * cfg_
Config class that stores and manages all related parameters.
double inflation_dist
buffer zone around obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in ...
struct teb_local_planner::TebConfig::Obstacles obstacles
Obstacle related parameters.
double weight_kinematics_forward_drive
Optimization weight for forcing the robot to choose only forward directions (positive transl...
void AddEdgesKinematicsDiffDrive()
Add all edges (local cost functions) for satisfying kinematic constraints of a differential drive rob...
int min_samples
Minimum number of samples (should be always greater than 2)
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > ViaPointContainer
Typedef for a container storing via-points.
bool optimizeTEB(int iterations_innerloop, int iterations_outerloop, bool compute_cost_afterwards=false, double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false)
Optimize a previously initialized trajectory (actual TEB optimization loop).
Abstract class that defines the interface for modelling obstacles.
double max_vel_x
Maximum translational velocity of the robot.
bool optimization_verbose
Print verbose information.
boost::shared_ptr< g2o::SparseOptimizer > optimizer_
g2o optimizer for trajectory optimization
void AddEdgesObstaclesLegacy(double weight_multiplier=1.0)
Add all edges (local cost functions) related to keeping a distance from static obstacles (legacy asso...
RotType prefer_rotdir_
Store whether to prefer a specific initial rotation in optimization (might be activated in case the r...
Edge defining the cost function for satisfying the non-holonomic kinematics of a differential drive m...
double getSumOfAllTimeDiffs() const
Calculate the total transition time (sum over all time intervals of the timediff sequence) ...