56 initialize(cfg, obstacles, robot_model, visual, via_points);
121 g2o::Factory* factory = g2o::Factory::instance();
122 factory->registerType(
"VERTEX_POSE",
new g2o::HyperGraphElementCreator<VertexPose>);
123 factory->registerType(
"VERTEX_TIMEDIFF",
new g2o::HyperGraphElementCreator<VertexTimeDiff>);
125 factory->registerType(
"EDGE_TIME_OPTIMAL",
new g2o::HyperGraphElementCreator<EdgeTimeOptimal>);
126 factory->registerType(
"EDGE_SHORTEST_PATH",
new g2o::HyperGraphElementCreator<EdgeShortestPath>);
127 factory->registerType(
"EDGE_VELOCITY",
new g2o::HyperGraphElementCreator<EdgeVelocity>);
128 factory->registerType(
"EDGE_VELOCITY_HOLONOMIC",
new g2o::HyperGraphElementCreator<EdgeVelocityHolonomic>);
129 factory->registerType(
"EDGE_ACCELERATION",
new g2o::HyperGraphElementCreator<EdgeAcceleration>);
130 factory->registerType(
"EDGE_ACCELERATION_START",
new g2o::HyperGraphElementCreator<EdgeAccelerationStart>);
131 factory->registerType(
"EDGE_ACCELERATION_GOAL",
new g2o::HyperGraphElementCreator<EdgeAccelerationGoal>);
132 factory->registerType(
"EDGE_ACCELERATION_HOLONOMIC",
new g2o::HyperGraphElementCreator<EdgeAccelerationHolonomic>);
133 factory->registerType(
"EDGE_ACCELERATION_HOLONOMIC_START",
new g2o::HyperGraphElementCreator<EdgeAccelerationHolonomicStart>);
134 factory->registerType(
"EDGE_ACCELERATION_HOLONOMIC_GOAL",
new g2o::HyperGraphElementCreator<EdgeAccelerationHolonomicGoal>);
135 factory->registerType(
"EDGE_KINEMATICS_DIFF_DRIVE",
new g2o::HyperGraphElementCreator<EdgeKinematicsDiffDrive>);
136 factory->registerType(
"EDGE_KINEMATICS_CARLIKE",
new g2o::HyperGraphElementCreator<EdgeKinematicsCarlike>);
137 factory->registerType(
"EDGE_OBSTACLE",
new g2o::HyperGraphElementCreator<EdgeObstacle>);
138 factory->registerType(
"EDGE_INFLATED_OBSTACLE",
new g2o::HyperGraphElementCreator<EdgeInflatedObstacle>);
139 factory->registerType(
"EDGE_DYNAMIC_OBSTACLE",
new g2o::HyperGraphElementCreator<EdgeDynamicObstacle>);
140 factory->registerType(
"EDGE_VIA_POINT",
new g2o::HyperGraphElementCreator<EdgeViaPoint>);
141 factory->registerType(
"EDGE_PREFER_ROTDIR",
new g2o::HyperGraphElementCreator<EdgePreferRotDir>);
152 static boost::once_flag flag = BOOST_ONCE_INIT;
158 linearSolver->setBlockOrdering(
true);
160 g2o::OptimizationAlgorithmLevenberg* solver =
new g2o::OptimizationAlgorithmLevenberg(blockSolver);
162 optimizer->setAlgorithm(solver);
164 optimizer->initMultiThreading();
171 double obst_cost_scale,
double viapoint_cost_scale,
bool alternative_time_cost)
176 bool success =
false;
179 double weight_multiplier = 1.0;
187 for(
int i=0; i<iterations_outerloop; ++i)
210 if (compute_cost_afterwards && i==iterations_outerloop-1)
224 vel_start_.second.linear.x = vel_start.linear.x;
225 vel_start_.second.linear.y = vel_start.linear.y;
226 vel_start_.second.angular.z = vel_start.angular.z;
245 PoseSE2 start_(initial_plan.front().pose);
246 PoseSE2 goal_(initial_plan.back().pose);
253 ROS_DEBUG(
"New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
274 return plan(start_, goal_, start_vel);
293 ROS_DEBUG(
"New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
314 ROS_WARN(
"Cannot build graph, because it is not empty. Call graphClear()!");
355 ROS_WARN(
"optimizeGraph(): Robot Max Velocity is smaller than 0.01m/s. Optimizing aborted...");
362 ROS_WARN(
"optimizeGraph(): TEB is empty or has too less elements. Skipping optimization.");
370 int iter =
optimizer_->optimize(no_iterations);
378 ROS_ERROR(
"optimizeGraph(): Optimization failed! iter=%i", iter);
404 unsigned int id_counter = 0;
426 Eigen::Matrix<double,1,1> information;
429 Eigen::Matrix<double,2,2> information_inflated;
432 information_inflated(0,1) = information_inflated(1,0) = 0;
437 double left_min_dist = std::numeric_limits<double>::max();
438 double right_min_dist = std::numeric_limits<double>::max();
442 std::vector<Obstacle*> relevant_obstacles;
459 relevant_obstacles.push_back(obst.get());
467 if (
cross2d(pose_orient, obst->getCentroid()) > 0)
469 if (dist < left_min_dist)
471 left_min_dist = dist;
472 left_obstacle = obst.get();
477 if (dist < right_min_dist)
479 right_min_dist = dist;
480 right_obstacle = obst.get();
492 dist_bandpt_obst->setInformation(information_inflated);
500 dist_bandpt_obst->setInformation(information);
512 dist_bandpt_obst->setInformation(information_inflated);
520 dist_bandpt_obst->setInformation(information);
526 for (
const Obstacle* obst : relevant_obstacles)
532 dist_bandpt_obst->setInformation(information_inflated);
540 dist_bandpt_obst->setInformation(information);
555 Eigen::Matrix<double,1,1> information;
558 Eigen::Matrix<double,2,2> information_inflated;
561 information_inflated(0,1) = information_inflated(1,0) = 0;
565 for (ObstContainer::const_iterator obst =
obstacles_->begin(); obst !=
obstacles_->end(); ++obst)
586 dist_bandpt_obst->setInformation(information_inflated);
594 dist_bandpt_obst->setInformation(information);
606 dist_bandpt_obst_n_r->setVertex(0,
teb_.
PoseVertex(index+neighbourIdx));
607 dist_bandpt_obst_n_r->setInformation(information_inflated);
614 dist_bandpt_obst_n_r->setVertex(0,
teb_.
PoseVertex(index+neighbourIdx));
615 dist_bandpt_obst_n_r->setInformation(information);
620 if ( index - neighbourIdx >= 0)
625 dist_bandpt_obst_n_l->setVertex(0,
teb_.
PoseVertex(index-neighbourIdx));
626 dist_bandpt_obst_n_l->setInformation(information_inflated);
633 dist_bandpt_obst_n_l->setVertex(0,
teb_.
PoseVertex(index-neighbourIdx));
634 dist_bandpt_obst_n_l->setInformation(information);
650 Eigen::Matrix<double,2,2> information;
653 information(0,1) = information(1,0) = 0;
655 for (ObstContainer::const_iterator obst =
obstacles_->begin(); obst !=
obstacles_->end(); ++obst)
657 if (!(*obst)->isDynamic())
666 dynobst_edge->setInformation(information);
679 int start_pose_idx = 0;
685 for (ViaPointContainer::const_iterator vp_it =
via_points_->begin(); vp_it !=
via_points_->end(); ++vp_it)
690 start_pose_idx = index+2;
704 ROS_DEBUG(
"TebOptimalPlanner::AddEdgesViaPoints(): skipping a via-point that is close or behind the current robot pose.");
708 Eigen::Matrix<double,1,1> information;
713 edge_viapoint->setInformation(information);
727 Eigen::Matrix<double,2,2> information;
730 information(0,1) = 0.0;
731 information(1,0) = 0.0;
733 for (
int i=0; i < n - 1; ++i)
739 velocity_edge->setInformation(information);
750 Eigen::Matrix<double,3,3> information;
756 for (
int i=0; i < n - 1; ++i)
762 velocity_edge->setInformation(information);
779 Eigen::Matrix<double,2,2> information;
792 acceleration_edge->setInformation(information);
798 for (
int i=0; i < n - 2; ++i)
806 acceleration_edge->setInformation(information);
819 acceleration_edge->setInformation(information);
826 Eigen::Matrix<double,3,3> information;
840 acceleration_edge->setInformation(information);
846 for (
int i=0; i < n - 2; ++i)
854 acceleration_edge->setInformation(information);
867 acceleration_edge->setInformation(information);
881 Eigen::Matrix<double,1,1> information;
888 timeoptimal_edge->setInformation(information);
899 Eigen::Matrix<double,1,1> information;
907 shortest_path_edge->setInformation(information);
921 Eigen::Matrix<double,2,2> information_kinematics;
922 information_kinematics.fill(0.0);
931 kinematics_edge->setInformation(information_kinematics);
943 Eigen::Matrix<double,2,2> information_kinematics;
944 information_kinematics.fill(0.0);
953 kinematics_edge->setInformation(information_kinematics);
974 ROS_WARN(
"TebOptimalPlanner::AddEdgesPreferRotDir(): unsupported RotType selected. Skipping edge creation.");
979 Eigen::Matrix<double,1,1> information_rotdir;
987 rotdir_edge->setInformation(information_rotdir);
1001 bool graph_exist_flag(
false);
1011 graph_exist_flag =
true;
1018 if (alternative_time_cost)
1027 for (std::vector<g2o::OptimizableGraph::Edge*>::const_iterator it =
optimizer_->activeEdges().begin(); it!=
optimizer_->activeEdges().end(); it++)
1029 double cur_cost = (*it)->chi2();
1031 if (dynamic_cast<EdgeObstacle*>(*it) !=
nullptr 1032 || dynamic_cast<EdgeInflatedObstacle*>(*it) !=
nullptr 1033 || dynamic_cast<EdgeDynamicObstacle*>(*it) !=
nullptr)
1035 cur_cost *= obst_cost_scale;
1037 else if (dynamic_cast<EdgeViaPoint*>(*it) !=
nullptr)
1039 cur_cost *= viapoint_cost_scale;
1041 else if (dynamic_cast<EdgeTimeOptimal*>(*it) !=
nullptr && alternative_time_cost)
1049 if (!graph_exist_flag)
1070 double dir = deltaS.dot(conf1dir);
1071 vx = (double)
g2o::sign(dir) * deltaS.norm()/dt;
1079 double cos_theta1 = std::cos(pose1.
theta());
1080 double sin_theta1 = std::sin(pose1.
theta());
1081 double p1_dx = cos_theta1*deltaS.x() + sin_theta1*deltaS.y();
1082 double p1_dy = -sin_theta1*deltaS.x() + cos_theta1*deltaS.y();
1088 double orientdiff = g2o::normalize_theta(pose2.
theta() - pose1.
theta());
1089 omega = orientdiff/dt;
1096 ROS_ERROR(
"TebOptimalPlanner::getVelocityCommand(): The trajectory contains less than 2 poses. Make sure to init and optimize/plan the trajectory fist.");
1102 look_ahead_poses = std::max(1, std::min(look_ahead_poses,
teb_.
sizePoses() - 1));
1104 for(
int counter = 0; counter < look_ahead_poses; ++counter)
1109 look_ahead_poses = counter + 1;
1115 ROS_ERROR(
"TebOptimalPlanner::getVelocityCommand() - timediff<=0 is invalid!");
1130 velocity_profile.resize( n+1 );
1133 velocity_profile.front().linear.z = 0;
1134 velocity_profile.front().angular.x = velocity_profile.front().angular.y = 0;
1135 velocity_profile.front().linear.x =
vel_start_.second.linear.x;
1136 velocity_profile.front().linear.y =
vel_start_.second.linear.y;
1137 velocity_profile.front().angular.z =
vel_start_.second.angular.z;
1139 for (
int i=1; i<n; ++i)
1141 velocity_profile[i].linear.z = 0;
1142 velocity_profile[i].angular.x = velocity_profile[i].angular.y = 0;
1147 velocity_profile.back().linear.z = 0;
1148 velocity_profile.back().angular.x = velocity_profile.back().angular.y = 0;
1149 velocity_profile.back().linear.x =
vel_goal_.second.linear.x;
1150 velocity_profile.back().linear.y =
vel_goal_.second.linear.y;
1151 velocity_profile.back().angular.z =
vel_goal_.second.angular.z;
1158 trajectory.resize(n);
1163 double curr_time = 0;
1166 TrajectoryPointMsg& start = trajectory.front();
1168 start.velocity.linear.z = 0;
1169 start.velocity.angular.x = start.velocity.angular.y = 0;
1170 start.velocity.linear.x =
vel_start_.second.linear.x;
1171 start.velocity.linear.y =
vel_start_.second.linear.y;
1172 start.velocity.angular.z =
vel_start_.second.angular.z;
1173 start.time_from_start.fromSec(curr_time);
1178 for (
int i=1; i < n-1; ++i)
1180 TrajectoryPointMsg&
point = trajectory[i];
1182 point.velocity.linear.z = 0;
1183 point.velocity.angular.x = point.velocity.angular.y = 0;
1184 double vel1_x, vel1_y, vel2_x, vel2_y, omega1, omega2;
1187 point.velocity.linear.x = 0.5*(vel1_x+vel2_x);
1188 point.velocity.linear.y = 0.5*(vel1_y+vel2_y);
1189 point.velocity.angular.z = 0.5*(omega1+omega2);
1190 point.time_from_start.fromSec(curr_time);
1196 TrajectoryPointMsg& goal = trajectory.back();
1198 goal.velocity.linear.z = 0;
1199 goal.velocity.angular.x = goal.velocity.angular.y = 0;
1200 goal.velocity.linear.x =
vel_goal_.second.linear.x;
1201 goal.velocity.linear.y =
vel_goal_.second.linear.y;
1202 goal.velocity.angular.z =
vel_goal_.second.angular.z;
1203 goal.time_from_start.fromSec(curr_time);
1208 double inscribed_radius,
double circumscribed_radius,
int look_ahead_idx)
1210 if (look_ahead_idx < 0 || look_ahead_idx >=
teb().sizePoses())
1213 for (
int i=0; i <= look_ahead_idx; ++i)
1226 if (i<look_ahead_idx)
1228 double delta_rot = g2o::normalize_theta(g2o::normalize_theta(
teb().
Pose(i+1).theta()) -
1229 g2o::normalize_theta(
teb().
Pose(i).theta()));
1234 std::ceil(delta_dist.norm() / inscribed_radius)) - 1;
1238 intermediate_pose.
position() = intermediate_pose.
position() + delta_dist / (n_additional_samples + 1.0);
1239 intermediate_pose.
theta() = g2o::normalize_theta(intermediate_pose.
theta() +
1240 delta_rot / (n_additional_samples + 1.0));
1241 if ( costmap_model->
footprintCost(intermediate_pose.
x(), intermediate_pose.
y(), intermediate_pose.
theta(),
1242 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!) ...
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.
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...
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. ...
double getSumOfAllTimeDiffs() const
Calculate the total transition time (sum over all time intervals of the timediff sequence) ...
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.
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.
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...
TFSIMD_FORCE_INLINE const tfScalar & y() const
void AddEdgesVelocity()
Add all edges (local cost functions) for limiting the translational and angular velocity.
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.
double weight_kinematics_turning_radius
Optimization weight for enforcing a minimum turning radius (carlike robots)
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). ...
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.
Eigen::Vector2d orientationUnitVec() const
Return the unit vector of the current orientation.
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.
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 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 AddEdgesViaPoints()
Add all edges (local cost functions) related to minimizing the distance to via-points.
double min_resolution_collision_check_angular
int sizeTimeDiffs() const
Get the length of the internal timediff sequence.
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.
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.
TFSIMD_FORCE_INLINE const tfScalar & x() const
void setParameters(const TebConfig &cfg, const BaseRobotFootprintModel *robot_model, const Obstacle *obstacle)
Set all parameters at once.
TebOptimalPlanner()
Default constructor.
void getFullTrajectory(std::vector< TrajectoryPointMsg > &trajectory) const
Return the complete trajectory including poses, velocity profiles and temporal information.
Edge defining the cost function for limiting the translational and rotational acceleration at the beg...
void toPoseMsg(geometry_msgs::Pose &pose) const
Convert PoseSE2 to a geometry_msgs::Pose.
void clearTimedElasticBand()
clear all poses and timediffs from the trajectory. The pose and timediff sequences will be empty and ...
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.
void getVelocityProfile(std::vector< geometry_msgs::Twist > &velocity_profile) const
Compute the velocity profile of the trajectory.
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 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.
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...
void setParameters(const TebConfig &cfg, const BaseRobotFootprintModel *robot_model, const Obstacle *obstacle)
Set all parameters at once.
double weight_optimaltime
Optimization weight for contracting the trajectory w.r.t. transition time.
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.
Edge defining the cost function for satisfying the non-holonomic kinematics of a carlike mobile robot...
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...
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...
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...
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...
int sizePoses() const
Get the length of the internal pose sequence.
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.
bool isInit() const
Check whether the trajectory is initialized (nonzero pose and timediff sequences) ...
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...