63 initialized_(false), optimized_(false)
133 g2o::Factory* factory = g2o::Factory::instance();
134 factory->registerType(
"VERTEX_POSE",
new g2o::HyperGraphElementCreator<VertexPose>);
135 factory->registerType(
"VERTEX_TIMEDIFF",
new g2o::HyperGraphElementCreator<VertexTimeDiff>);
137 factory->registerType(
"EDGE_TIME_OPTIMAL",
new g2o::HyperGraphElementCreator<EdgeTimeOptimal>);
138 factory->registerType(
"EDGE_SHORTEST_PATH",
new g2o::HyperGraphElementCreator<EdgeShortestPath>);
139 factory->registerType(
"EDGE_VELOCITY",
new g2o::HyperGraphElementCreator<EdgeVelocity>);
140 factory->registerType(
"EDGE_VELOCITY_HOLONOMIC",
new g2o::HyperGraphElementCreator<EdgeVelocityHolonomic>);
141 factory->registerType(
"EDGE_ACCELERATION",
new g2o::HyperGraphElementCreator<EdgeAcceleration>);
142 factory->registerType(
"EDGE_ACCELERATION_START",
new g2o::HyperGraphElementCreator<EdgeAccelerationStart>);
143 factory->registerType(
"EDGE_ACCELERATION_GOAL",
new g2o::HyperGraphElementCreator<EdgeAccelerationGoal>);
144 factory->registerType(
"EDGE_ACCELERATION_HOLONOMIC",
new g2o::HyperGraphElementCreator<EdgeAccelerationHolonomic>);
145 factory->registerType(
"EDGE_ACCELERATION_HOLONOMIC_START",
new g2o::HyperGraphElementCreator<EdgeAccelerationHolonomicStart>);
146 factory->registerType(
"EDGE_ACCELERATION_HOLONOMIC_GOAL",
new g2o::HyperGraphElementCreator<EdgeAccelerationHolonomicGoal>);
147 factory->registerType(
"EDGE_KINEMATICS_DIFF_DRIVE",
new g2o::HyperGraphElementCreator<EdgeKinematicsDiffDrive>);
148 factory->registerType(
"EDGE_KINEMATICS_CARLIKE",
new g2o::HyperGraphElementCreator<EdgeKinematicsCarlike>);
149 factory->registerType(
"EDGE_OBSTACLE",
new g2o::HyperGraphElementCreator<EdgeObstacle>);
150 factory->registerType(
"EDGE_INFLATED_OBSTACLE",
new g2o::HyperGraphElementCreator<EdgeInflatedObstacle>);
151 factory->registerType(
"EDGE_DYNAMIC_OBSTACLE",
new g2o::HyperGraphElementCreator<EdgeDynamicObstacle>);
152 factory->registerType(
"EDGE_VIA_POINT",
new g2o::HyperGraphElementCreator<EdgeViaPoint>);
153 factory->registerType(
"EDGE_PREFER_ROTDIR",
new g2o::HyperGraphElementCreator<EdgePreferRotDir>);
164 static boost::once_flag flag = BOOST_ONCE_INIT;
170 linear_solver->setBlockOrdering(
true);
171 std::unique_ptr<TEBBlockSolver> block_solver(
new TEBBlockSolver(std::move(linear_solver)));
172 g2o::OptimizationAlgorithmLevenberg* solver =
new g2o::OptimizationAlgorithmLevenberg(std::move(block_solver));
183 double obst_cost_scale,
double viapoint_cost_scale,
bool alternative_time_cost)
188 bool success =
false;
191 double weight_multiplier = 1.0;
199 for(
int i=0; i<iterations_outerloop; ++i)
222 if (compute_cost_afterwards && i==iterations_outerloop-1)
236 vel_start_.second.linear.x = vel_start.linear.x;
237 vel_start_.second.linear.y = vel_start.linear.y;
238 vel_start_.second.angular.z = vel_start.angular.z;
257 PoseSE2 start_(initial_plan.front().pose);
258 PoseSE2 goal_(initial_plan.back().pose);
265 ROS_DEBUG(
"New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
287 return plan(start_, goal_, start_vel);
306 ROS_DEBUG(
"New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
327 ROS_WARN(
"Cannot build graph, because it is not empty. Call graphClear()!");
372 ROS_WARN(
"optimizeGraph(): Robot Max Velocity is smaller than 0.01m/s. Optimizing aborted...");
379 ROS_WARN(
"optimizeGraph(): TEB is empty or has too less elements. Skipping optimization.");
387 int iter =
optimizer_->optimize(no_iterations);
395 ROS_ERROR(
"optimizeGraph(): Optimization failed! iter=%i", iter);
413 v.second->edges().clear();
426 unsigned int id_counter = 0;
438 iter_obstacle->clear();
439 (iter_obstacle++)->reserve(
obstacles_->size());
452 Eigen::Matrix<double,1,1> information;
455 Eigen::Matrix<double,2,2> information_inflated;
458 information_inflated(0,1) = information_inflated(1,0) = 0;
462 auto create_edge = [inflated, &information, &information_inflated,
this] (
int index,
const Obstacle* obstacle) {
467 dist_bandpt_obst->setInformation(information_inflated);
475 dist_bandpt_obst->setInformation(information);
485 double left_min_dist = std::numeric_limits<double>::max();
486 double right_min_dist = std::numeric_limits<double>::max();
505 iter_obstacle->push_back(obst);
515 if (dist < left_min_dist)
517 left_min_dist = dist;
518 left_obstacle = obst;
523 if (dist < right_min_dist)
525 right_min_dist = dist;
526 right_obstacle = obst;
532 iter_obstacle->push_back(left_obstacle);
534 iter_obstacle->push_back(right_obstacle);
545 create_edge(i, obst.get());
556 Eigen::Matrix<double,1,1> information;
559 Eigen::Matrix<double,2,2> information_inflated;
562 information_inflated(0,1) = information_inflated(1,0) = 0;
566 for (ObstContainer::const_iterator obst =
obstacles_->begin(); obst !=
obstacles_->end(); ++obst)
585 EdgeInflatedObstacle* dist_bandpt_obst =
new EdgeInflatedObstacle;
587 dist_bandpt_obst->setInformation(information_inflated);
588 dist_bandpt_obst->setParameters(*
cfg_, obst->get());
595 dist_bandpt_obst->setInformation(information);
606 EdgeInflatedObstacle* dist_bandpt_obst_n_r =
new EdgeInflatedObstacle;
607 dist_bandpt_obst_n_r->setVertex(0,
teb_.
PoseVertex(index+neighbourIdx));
608 dist_bandpt_obst_n_r->setInformation(information_inflated);
609 dist_bandpt_obst_n_r->setParameters(*
cfg_, obst->get());
614 EdgeObstacle* dist_bandpt_obst_n_r =
new EdgeObstacle;
615 dist_bandpt_obst_n_r->setVertex(0,
teb_.
PoseVertex(index+neighbourIdx));
616 dist_bandpt_obst_n_r->setInformation(information);
617 dist_bandpt_obst_n_r->setParameters(*
cfg_, obst->get());
621 if ( index - neighbourIdx >= 0)
625 EdgeInflatedObstacle* dist_bandpt_obst_n_l =
new EdgeInflatedObstacle;
626 dist_bandpt_obst_n_l->setVertex(0,
teb_.
PoseVertex(index-neighbourIdx));
627 dist_bandpt_obst_n_l->setInformation(information_inflated);
628 dist_bandpt_obst_n_l->setParameters(*
cfg_, obst->get());
633 EdgeObstacle* dist_bandpt_obst_n_l =
new EdgeObstacle;
634 dist_bandpt_obst_n_l->setVertex(0,
teb_.
PoseVertex(index-neighbourIdx));
635 dist_bandpt_obst_n_l->setInformation(information);
636 dist_bandpt_obst_n_l->setParameters(*
cfg_, obst->get());
651 Eigen::Matrix<double,2,2> information;
654 information(0,1) = information(1,0) = 0;
656 for (ObstContainer::const_iterator obst =
obstacles_->begin(); obst !=
obstacles_->end(); ++obst)
658 if (!(*obst)->isDynamic())
665 EdgeDynamicObstacle* dynobst_edge =
new EdgeDynamicObstacle(time);
667 dynobst_edge->setInformation(information);
668 dynobst_edge->setParameters(*
cfg_, obst->get());
680 int start_pose_idx = 0;
686 for (ViaPointContainer::const_iterator vp_it =
via_points_->begin(); vp_it !=
via_points_->end(); ++vp_it)
691 start_pose_idx = index+2;
705 ROS_DEBUG(
"TebOptimalPlanner::AddEdgesViaPoints(): skipping a via-point that is close or behind the current robot pose.");
709 Eigen::Matrix<double,1,1> information;
714 edge_viapoint->setInformation(information);
728 Eigen::Matrix<double,2,2> information;
731 information(0,1) = 0.0;
732 information(1,0) = 0.0;
734 for (
int i=0; i < n - 1; ++i)
736 EdgeVelocity* velocity_edge =
new EdgeVelocity;
740 velocity_edge->setInformation(information);
741 velocity_edge->setTebConfig(*
cfg_);
751 Eigen::Matrix<double,3,3> information;
757 for (
int i=0; i < n - 1; ++i)
763 velocity_edge->setInformation(information);
780 Eigen::Matrix<double,2,2> information;
788 EdgeAccelerationStart* acceleration_edge =
new EdgeAccelerationStart;
792 acceleration_edge->setInitialVelocity(
vel_start_.second);
793 acceleration_edge->setInformation(information);
794 acceleration_edge->setTebConfig(*
cfg_);
799 for (
int i=0; i < n - 2; ++i)
801 EdgeAcceleration* acceleration_edge =
new EdgeAcceleration;
807 acceleration_edge->setInformation(information);
808 acceleration_edge->setTebConfig(*
cfg_);
820 acceleration_edge->setInformation(information);
827 Eigen::Matrix<double,3,3> information;
836 EdgeAccelerationHolonomicStart* acceleration_edge =
new EdgeAccelerationHolonomicStart;
840 acceleration_edge->setInitialVelocity(
vel_start_.second);
841 acceleration_edge->setInformation(information);
842 acceleration_edge->setTebConfig(*
cfg_);
847 for (
int i=0; i < n - 2; ++i)
849 EdgeAccelerationHolonomic* acceleration_edge =
new EdgeAccelerationHolonomic;
855 acceleration_edge->setInformation(information);
856 acceleration_edge->setTebConfig(*
cfg_);
863 EdgeAccelerationHolonomicGoal* acceleration_edge =
new EdgeAccelerationHolonomicGoal;
867 acceleration_edge->setGoalVelocity(
vel_goal_.second);
868 acceleration_edge->setInformation(information);
869 acceleration_edge->setTebConfig(*
cfg_);
882 Eigen::Matrix<double,1,1> information;
887 EdgeTimeOptimal* timeoptimal_edge =
new EdgeTimeOptimal;
889 timeoptimal_edge->setInformation(information);
890 timeoptimal_edge->setTebConfig(*
cfg_);
900 Eigen::Matrix<double,1,1> information;
905 EdgeShortestPath* shortest_path_edge =
new EdgeShortestPath;
908 shortest_path_edge->setInformation(information);
909 shortest_path_edge->setTebConfig(*
cfg_);
922 Eigen::Matrix<double,2,2> information_kinematics;
923 information_kinematics.fill(0.0);
932 kinematics_edge->setInformation(information_kinematics);
944 Eigen::Matrix<double,2,2> information_kinematics;
945 information_kinematics.fill(0.0);
951 EdgeKinematicsCarlike* kinematics_edge =
new EdgeKinematicsCarlike;
954 kinematics_edge->setInformation(information_kinematics);
975 ROS_WARN(
"TebOptimalPlanner::AddEdgesPreferRotDir(): unsupported RotType selected. Skipping edge creation.");
980 Eigen::Matrix<double,1,1> information_rotdir;
988 rotdir_edge->setInformation(information_rotdir);
1001 Eigen::Matrix<double,2,2> information;
1004 information(0,1) = information(1,0) = 0;
1010 for (
const ObstaclePtr obstacle : (*iter_obstacle++))
1016 edge->setInformation(information);
1029 auto stats_vector =
optimizer_->batchStatistics();
1032 if (stats_vector.empty())
1036 const auto last_iter_stats = stats_vector.back();
1044 bool graph_exist_flag(
false);
1054 graph_exist_flag =
true;
1061 if (alternative_time_cost)
1070 for (std::vector<g2o::OptimizableGraph::Edge*>::const_iterator it =
optimizer_->activeEdges().begin(); it!=
optimizer_->activeEdges().end(); it++)
1072 double cur_cost = (*it)->chi2();
1078 cur_cost *= obst_cost_scale;
1082 cur_cost *= viapoint_cost_scale;
1084 else if (
dynamic_cast<EdgeTimeOptimal*
>(*it) !=
nullptr && alternative_time_cost)
1092 if (!graph_exist_flag)
1107 Eigen::Vector2d deltaS = pose2.position() - pose1.position();
1111 Eigen::Vector2d conf1dir( cos(pose1.theta()), sin(pose1.theta()) );
1113 double dir = deltaS.dot(conf1dir);
1114 vx = (double) g2o::sign(dir) * deltaS.norm()/dt;
1122 double cos_theta1 = std::cos(pose1.theta());
1123 double sin_theta1 = std::sin(pose1.theta());
1124 double p1_dx = cos_theta1*deltaS.x() + sin_theta1*deltaS.y();
1125 double p1_dy = -sin_theta1*deltaS.x() + cos_theta1*deltaS.y();
1131 double orientdiff = g2o::normalize_theta(pose2.theta() - pose1.theta());
1132 omega = orientdiff/dt;
1139 ROS_ERROR(
"TebOptimalPlanner::getVelocityCommand(): The trajectory contains less than 2 poses. Make sure to init and optimize/plan the trajectory fist.");
1147 for(
int counter = 0; counter < look_ahead_poses; ++counter)
1152 look_ahead_poses = counter + 1;
1158 ROS_ERROR(
"TebOptimalPlanner::getVelocityCommand() - timediff<=0 is invalid!");
1173 velocity_profile.resize( n+1 );
1176 velocity_profile.front().linear.z = 0;
1177 velocity_profile.front().angular.x = velocity_profile.front().angular.y = 0;
1178 velocity_profile.front().linear.x =
vel_start_.second.linear.x;
1179 velocity_profile.front().linear.y =
vel_start_.second.linear.y;
1180 velocity_profile.front().angular.z =
vel_start_.second.angular.z;
1182 for (
int i=1; i<n; ++i)
1184 velocity_profile[i].linear.z = 0;
1185 velocity_profile[i].angular.x = velocity_profile[i].angular.y = 0;
1190 velocity_profile.back().linear.z = 0;
1191 velocity_profile.back().angular.x = velocity_profile.back().angular.y = 0;
1192 velocity_profile.back().linear.x =
vel_goal_.second.linear.x;
1193 velocity_profile.back().linear.y =
vel_goal_.second.linear.y;
1194 velocity_profile.back().angular.z =
vel_goal_.second.angular.z;
1206 double curr_time = 0;
1211 start.velocity.linear.z = 0;
1212 start.velocity.angular.x =
start.velocity.angular.y = 0;
1216 start.time_from_start.fromSec(curr_time);
1221 for (
int i=1; i < n-1; ++i)
1225 point.velocity.linear.z = 0;
1226 point.velocity.angular.x =
point.velocity.angular.y = 0;
1227 double vel1_x, vel1_y, vel2_x, vel2_y, omega1, omega2;
1230 point.velocity.linear.x = 0.5*(vel1_x+vel2_x);
1231 point.velocity.linear.y = 0.5*(vel1_y+vel2_y);
1232 point.velocity.angular.z = 0.5*(omega1+omega2);
1233 point.time_from_start.fromSec(curr_time);
1239 TrajectoryPointMsg& goal =
trajectory.back();
1241 goal.velocity.linear.z = 0;
1242 goal.velocity.angular.x = goal.velocity.angular.y = 0;
1243 goal.velocity.linear.x =
vel_goal_.second.linear.x;
1244 goal.velocity.linear.y =
vel_goal_.second.linear.y;
1245 goal.velocity.angular.z =
vel_goal_.second.angular.z;
1246 goal.time_from_start.fromSec(curr_time);
1251 double inscribed_radius,
double circumscribed_radius,
int look_ahead_idx,
double feasibility_check_lookahead_distance)
1253 if (look_ahead_idx < 0 || look_ahead_idx >=
teb().sizePoses())
1256 if (feasibility_check_lookahead_distance > 0){
1259 if(pose_distance > feasibility_check_lookahead_distance){
1260 look_ahead_idx = i - 1;
1266 for (
int i=0; i <= look_ahead_idx; ++i)
1279 if (i<look_ahead_idx)
1281 double delta_rot = g2o::normalize_theta(g2o::normalize_theta(
teb().
Pose(i+1).theta()) -
1282 g2o::normalize_theta(
teb().
Pose(i).theta()));
1287 std::ceil(delta_dist.norm() / inscribed_radius)) - 1;
1289 for(
int step = 0;
step < n_additional_samples; ++
step)
1291 intermediate_pose.
position() = intermediate_pose.
position() + delta_dist / (n_additional_samples + 1.0);
1292 intermediate_pose.
theta() = g2o::normalize_theta(intermediate_pose.
theta() +
1293 delta_rot / (n_additional_samples + 1.0));
1294 if ( costmap_model->
footprintCost(intermediate_pose.
x(), intermediate_pose.
y(), intermediate_pose.
theta(),
1295 footprint_spec, inscribed_radius, circumscribed_radius) == -1 )