45 #include <mpc_local_planner_msgs/OptimalControlResult.h> 46 #include <mpc_local_planner_msgs/StateFeedback.h> 48 #include <corbo-communication/utilities.h> 70 int outer_ocp_iterations = 1;
71 nh.
param(
"controller/outer_ocp_iterations", outer_ocp_iterations, outer_ocp_iterations);
92 if (
_ocp->initialize())
105 std::vector<geometry_msgs::PoseStamped> initial_plan(2);
106 start.
toPoseMsg(initial_plan.front().pose);
107 goal.
toPoseMsg(initial_plan.back().pose);
108 return step(initial_plan, vel, dt, t, u_seq, x_seq);
111 bool Controller::step(
const std::vector<geometry_msgs::PoseStamped>& initial_plan,
const geometry_msgs::Twist& vel,
double dt,
ros::Time t,
116 ROS_ERROR(
"Controller must be configured before invoking step().");
119 if (initial_plan.size() < 2)
121 ROS_ERROR(
"Controller::step(): initial plan must contain at least two poses.");
126 PoseSE2 goal(initial_plan.back().pose);
128 Eigen::VectorXd xf(
_dynamics->getStateDimension());
129 _dynamics->getSteadyStateFromPoseSE2(goal, xf);
132 Eigen::VectorXd
x(
_dynamics->getStateDimension());
140 if (!new_x && (!
_x_ts ||
_x_ts->isEmpty() || !
_x_ts->getValuesInterpolate(dt,
x)))
159 if (
_grid->isEmpty())
185 if ((
int)msg->state.size() !=
_dynamics->getStateDimension())
187 ROS_ERROR_STREAM(
"stateFeedbackCallback(): state feedback dimension does not match robot state dimension: " 188 << msg->state.size() <<
" != " <<
_dynamics->getStateDimension());
200 mpc_local_planner_msgs::OptimalControlResult msg;
202 msg.header.seq =
static_cast<unsigned int>(
_ocp_seq);
203 msg.dim_states =
_dynamics->getStateDimension();
204 msg.dim_controls =
_dynamics->getInputDimension();
210 msg.time_states =
_x_ts->getTime();
211 msg.states =
_x_ts->getValues();
216 msg.time_controls =
_u_ts->getTime();
217 msg.controls =
_u_ts->getValues();
229 std::string grid_type =
"fd_grid";
230 nh.
param(
"grid/type", grid_type, grid_type);
232 if (grid_type ==
"fd_grid")
236 bool variable_grid =
true;
237 nh.
param(
"grid/variable_grid/enable", variable_grid, variable_grid);
243 nh.
param(
"grid/variable_grid/min_dt", min_dt, min_dt);
244 double max_dt = 10.0;
245 nh.
param(
"grid/variable_grid/max_dt", max_dt, max_dt);
246 var_grid->setDtBounds(min_dt, max_dt);
248 bool grid_adaptation =
true;
249 nh.
param(
"grid/variable_grid/grid_adaptation/enable", grid_adaptation, grid_adaptation);
253 int max_grid_size = 50;
254 nh.
param(
"grid/variable_grid/grid_adaptation/max_grid_size", max_grid_size, max_grid_size);
255 double dt_hyst_ratio = 0.1;
256 nh.
param(
"grid/variable_grid/grid_adaptation/dt_hyst_ratio", dt_hyst_ratio, dt_hyst_ratio);
257 var_grid->setGridAdaptTimeBasedSingleStep(max_grid_size, dt_hyst_ratio,
true);
259 int min_grid_size = 2;
260 nh.
param(
"grid/variable_grid/grid_adaptation/min_grid_size", min_grid_size, min_grid_size);
261 var_grid->setNmin(min_grid_size);
265 var_grid->disableGridAdaptation();
271 grid = std::make_shared<FiniteDifferencesGridSE2>();
274 int grid_size_ref = 20;
275 nh.
param(
"grid/grid_size_ref", grid_size_ref, grid_size_ref);
276 grid->setNRef(grid_size_ref);
279 nh.
param(
"grid/dt_ref", dt_ref, dt_ref);
280 grid->setDtRef(dt_ref);
282 std::vector<bool> xf_fixed = {
true,
true,
true};
283 nh.
param(
"grid/xf_fixed", xf_fixed, xf_fixed);
284 if ((
int)xf_fixed.size() !=
_dynamics->getStateDimension())
286 ROS_ERROR_STREAM(
"Array size of `xf_fixed` does not match robot state dimension(): " << xf_fixed.size()
287 <<
" != " <<
_dynamics->getStateDimension());
291 for (
int i = 0; i < (
int)xf_fixed.size(); ++i) xf_fixed_eigen[i] = xf_fixed[i];
292 grid->setXfFixed(xf_fixed_eigen);
294 bool warm_start =
true;
295 nh.
param(
"grid/warm_start", warm_start, warm_start);
296 grid->setWarmStart(warm_start);
298 std::string collocation_method =
"forward_differences";
299 nh.
param(
"grid/collocation_method", collocation_method, collocation_method);
301 if (collocation_method ==
"forward_differences")
303 grid->setFiniteDifferencesCollocationMethod(std::make_shared<ForwardDiffCollocationSE2>());
305 else if (collocation_method ==
"midpoint_differences")
307 grid->setFiniteDifferencesCollocationMethod(std::make_shared<MidpointDiffCollocationSE2>());
309 else if (collocation_method ==
"crank_nicolson_differences")
311 grid->setFiniteDifferencesCollocationMethod(std::make_shared<CrankNicolsonDiffCollocationSE2>());
315 ROS_ERROR_STREAM(
"Unknown collocation method '" << collocation_method <<
"' specified. Falling back to default...");
318 std::string cost_integration_method =
"left_sum";
319 nh.
param(
"grid/cost_integration_method", cost_integration_method, cost_integration_method);
321 if (cost_integration_method ==
"left_sum")
325 else if (cost_integration_method ==
"trapezoidal_rule")
331 ROS_ERROR_STREAM(
"Unknown cost integration method '" << cost_integration_method <<
"' specified. Falling back to default...");
334 return std::move(grid);
351 return std::make_shared<UnicycleModel>();
356 nh.
param(
"robot/simple_car/wheelbase", wheelbase, wheelbase);
357 bool front_wheel_driving =
false;
358 nh.
param(
"robot/simple_car/front_wheel_driving", front_wheel_driving, front_wheel_driving);
359 if (front_wheel_driving)
360 return std::make_shared<SimpleCarFrontWheelDrivingModel>(wheelbase);
362 return std::make_shared<SimpleCarModel>(wheelbase);
364 else if (
_robot_type ==
"kinematic_bicycle_vel_input")
366 double length_rear = 1.0;
367 nh.
param(
"robot/kinematic_bicycle_vel_input/length_rear", length_rear, length_rear);
368 double length_front = 1.0;
369 nh.
param(
"robot/kinematic_bicycle_vel_input/length_front", length_front, length_front);
370 return std::make_shared<KinematicBicycleModelVelocityInput>(length_rear, length_front);
383 std::string solver_type =
"ipopt";
384 nh.
param(
"solver/type", solver_type, solver_type);
386 if (solver_type ==
"ipopt")
389 solver->initialize();
391 int iterations = 100;
392 nh.
param(
"solver/ipopt/iterations", iterations, iterations);
393 solver->setIterations(iterations);
395 double max_cpu_time = -1.0;
396 nh.
param(
"solver/ipopt/max_cpu_time", max_cpu_time, max_cpu_time);
397 solver->setMaxCpuTime(max_cpu_time);
400 std::map<std::string, double> numeric_options;
401 nh.
param(
"solver/ipopt/ipopt_numeric_options", numeric_options, numeric_options);
402 for (
const auto& item : numeric_options)
404 if (!solver->setIpoptOptionNumeric(item.first, item.second))
ROS_WARN_STREAM(
"Ipopt option " << item.first <<
" could not be set.");
407 std::map<std::string, std::string> string_options;
408 nh.
param(
"solver/ipopt/ipopt_string_options", string_options, string_options);
409 for (
const auto& item : string_options)
411 if (!solver->setIpoptOptionString(item.first, item.second))
ROS_WARN_STREAM(
"Ipopt option " << item.first <<
" could not be set.");
414 std::map<std::string, int> integer_options;
415 nh.
param(
"solver/ipopt/ipopt_integer_options", integer_options, integer_options);
416 for (
const auto& item : integer_options)
418 if (!solver->setIpoptOptionInt(item.first, item.second))
ROS_WARN_STREAM(
"Ipopt option " << item.first <<
" could not be set.");
421 return std::move(solver);
439 else if (solver_type ==
"lsq_lm")
444 nh.
param(
"solver/lsq_lm/iterations", iterations, iterations);
445 solver->setIterations(iterations);
447 double weight_init_eq = 2;
448 nh.
param(
"solver/lsq_lm/weight_init_eq", weight_init_eq, weight_init_eq);
449 double weight_init_ineq = 2;
450 nh.
param(
"solver/lsq_lm/weight_init_ineq", weight_init_ineq, weight_init_ineq);
451 double weight_init_bounds = 2;
452 nh.
param(
"solver/lsq_lm/weight_init_bounds", weight_init_bounds, weight_init_bounds);
454 solver->setPenaltyWeights(weight_init_eq, weight_init_ineq, weight_init_bounds);
456 double weight_adapt_factor_eq = 1;
457 nh.
param(
"solver/lsq_lm/weight_adapt_factor_eq", weight_adapt_factor_eq, weight_adapt_factor_eq);
458 double weight_adapt_factor_ineq = 1;
459 nh.
param(
"solver/lsq_lm/weight_adapt_factor_ineq", weight_adapt_factor_ineq, weight_adapt_factor_ineq);
460 double weight_adapt_factor_bounds = 1;
461 nh.
param(
"solver/lsq_lm/weight_adapt_factor_bounds", weight_adapt_factor_bounds, weight_adapt_factor_bounds);
463 double weight_adapt_max_eq = 500;
464 nh.
param(
"solver/lsq_lm/weight_adapt_max_eq", weight_adapt_max_eq, weight_adapt_max_eq);
465 double weight_adapt_max_ineq = 500;
466 nh.
param(
"solver/lsq_lm/weight_init_eq", weight_adapt_max_ineq, weight_adapt_max_ineq);
467 double weight_adapt_max_bounds = 500;
468 nh.
param(
"solver/lsq_lm/weight_adapt_max_bounds", weight_adapt_max_bounds, weight_adapt_max_bounds);
470 solver->setWeightAdapation(weight_adapt_factor_eq, weight_adapt_factor_ineq, weight_adapt_factor_bounds, weight_adapt_max_eq,
471 weight_adapt_max_ineq, weight_adapt_max_bounds);
473 return std::move(solver);
485 const std::vector<teb_local_planner::PoseSE2>& via_points)
491 const int x_dim = _dynamics->getStateDimension();
492 const int u_dim = _dynamics->getInputDimension();
496 double max_vel_x = 0.4;
497 nh.
param(
"robot/unicycle/max_vel_x", max_vel_x, max_vel_x);
498 double max_vel_x_backwards = 0.2;
499 nh.
param(
"robot/unicycle/max_vel_x_backwards", max_vel_x_backwards, max_vel_x_backwards);
500 if (max_vel_x_backwards < 0)
502 ROS_WARN(
"max_vel_x_backwards must be >= 0");
503 max_vel_x_backwards *= -1;
505 double max_vel_theta = 0.3;
506 nh.
param(
"robot/unicycle/max_vel_theta", max_vel_theta, max_vel_theta);
511 ocp->setControlBounds(Eigen::Vector2d(-max_vel_x_backwards, -max_vel_theta), Eigen::Vector2d(max_vel_x, max_vel_theta));
515 double max_vel_x = 0.4;
516 nh.
param(
"robot/simple_car/max_vel_x", max_vel_x, max_vel_x);
517 double max_vel_x_backwards = 0.2;
518 nh.
param(
"robot/simple_car/max_vel_x_backwards", max_vel_x_backwards, max_vel_x_backwards);
519 if (max_vel_x_backwards < 0)
521 ROS_WARN(
"max_vel_x_backwards must be >= 0");
522 max_vel_x_backwards *= -1;
524 double max_steering_angle = 1.5;
525 nh.
param(
"robot/simple_car/max_steering_angle", max_steering_angle, max_steering_angle);
527 ocp->setControlBounds(Eigen::Vector2d(-max_vel_x_backwards, -max_steering_angle), Eigen::Vector2d(max_vel_x, max_steering_angle));
529 else if (
_robot_type ==
"kinematic_bicycle_vel_input")
531 double max_vel_x = 0.4;
532 nh.
param(
"robot/kinematic_bicycle_vel_input/max_vel_x", max_vel_x, max_vel_x);
533 double max_vel_x_backwards = 0.2;
534 nh.
param(
"robot/kinematic_bicycle_vel_input/max_vel_x_backwards", max_vel_x_backwards, max_vel_x_backwards);
535 if (max_vel_x_backwards < 0)
537 ROS_WARN(
"max_vel_x_backwards must be >= 0");
538 max_vel_x_backwards *= -1;
540 double max_steering_angle = 1.5;
541 nh.
param(
"robot/kinematic_bicycle_vel_input/max_steering_angle", max_steering_angle, max_steering_angle);
543 ocp->setControlBounds(Eigen::Vector2d(-max_vel_x_backwards, -max_steering_angle), Eigen::Vector2d(max_vel_x, max_steering_angle));
551 std::string objective_type =
"minimum_time";
552 nh.
param(
"planning/objective/type", objective_type, objective_type);
553 bool lsq_solver =
_solver->isLsqSolver();
555 if (objective_type ==
"minimum_time")
557 ocp->setStageCost(std::make_shared<corbo::MinimumTime>(lsq_solver));
559 else if (objective_type ==
"quadratic_form")
561 std::vector<double> state_weights;
562 nh.
param(
"planning/objective/quadratic_form/state_weights", state_weights, state_weights);
564 if (state_weights.size() == x_dim)
568 else if (state_weights.size() == x_dim * x_dim)
574 ROS_ERROR_STREAM(
"State weights dimension invalid. Must be either " << x_dim <<
" x 1 or " << x_dim <<
" x " << x_dim <<
".");
577 std::vector<double> control_weights;
578 nh.
param(
"planning/objective/quadratic_form/control_weights", control_weights, control_weights);
580 if (control_weights.size() == u_dim)
584 else if (control_weights.size() == u_dim * u_dim)
590 ROS_ERROR_STREAM(
"Control weights dimension invalid. Must be either " << u_dim <<
" x 1 or " << u_dim <<
" x " << u_dim <<
".");
593 bool integral_form =
false;
594 nh.
param(
"planning/objective/quadratic_form/integral_form", integral_form, integral_form);
595 bool hybrid_cost_minimum_time =
false;
596 nh.
param(
"planning/objective/quadratic_form/hybrid_cost_minimum_time", hybrid_cost_minimum_time, hybrid_cost_minimum_time);
598 bool q_zero = Q.isZero();
599 bool r_zero = R.isZero();
600 if (!q_zero && !r_zero)
603 "Hybrid minimum time and quadratic form cost is currently only supported for non-zero control weights only. Falling " 604 "back to quadratic form.");
605 ocp->setStageCost(std::make_shared<QuadraticFormCostSE2>(Q, R, integral_form, lsq_solver));
607 else if (!q_zero && r_zero)
610 "Hybrid minimum time and quadratic form cost is currently only supported for non-zero control weights only. Falling " 611 "back to only quadratic state cost.");
612 ocp->setStageCost(std::make_shared<QuadraticStateCostSE2>(Q, integral_form, lsq_solver));
614 else if (q_zero && !r_zero)
616 if (hybrid_cost_minimum_time)
618 ocp->setStageCost(std::make_shared<corbo::MinTimeQuadraticControls>(R, integral_form, lsq_solver));
622 ocp->setStageCost(std::make_shared<corbo::QuadraticControlCost>(R, integral_form, lsq_solver));
626 else if (objective_type ==
"minimum_time_via_points")
628 bool via_points_ordered =
false;
629 nh.
param(
"planning/objective/minimum_time_via_points/via_points_ordered", via_points_ordered, via_points_ordered);
630 double position_weight = 1.0;
631 nh.
param(
"planning/objective/minimum_time_via_points/position_weight", position_weight, position_weight);
632 double orientation_weight = 0.0;
633 nh.
param(
"planning/objective/minimum_time_via_points/orientation_weight", orientation_weight, orientation_weight);
634 ocp->setStageCost(std::make_shared<MinTimeViaPointsCost>(via_points, position_weight, orientation_weight, via_points_ordered));
639 ROS_ERROR_STREAM(
"Unknown objective type '" << objective_type <<
"' specified ('planning/objective/type').");
643 std::string terminal_cost =
"none";
644 nh.
param(
"planning/terminal_cost/type", terminal_cost, terminal_cost);
646 if (terminal_cost ==
"none")
648 ocp->setFinalStageCost({});
650 else if (terminal_cost ==
"quadratic")
652 std::vector<double> state_weights;
653 nh.
param(
"planning/terminal_cost/quadratic/final_state_weights", state_weights, state_weights);
655 if (state_weights.size() == x_dim)
659 else if (state_weights.size() == x_dim * x_dim)
665 ROS_ERROR_STREAM(
"Final state weights dimension invalid. Must be either " << x_dim <<
" x 1 or " << x_dim <<
" x " << x_dim <<
".");
668 ocp->setFinalStageCost(std::make_shared<QuadraticFinalStateCostSE2>(Qf, lsq_solver));
672 ROS_ERROR_STREAM(
"Unknown terminal_cost type '" << terminal_cost <<
"' specified ('planning/terminal_cost/type').");
676 std::string terminal_constraint =
"none";
677 nh.
param(
"planning/terminal_constraint/type", terminal_constraint, terminal_constraint);
679 if (terminal_constraint ==
"none")
681 ocp->setFinalStageConstraint({});
683 else if (terminal_constraint ==
"l2_ball")
685 std::vector<double> weight_matrix;
686 nh.
param(
"planning/terminal_constraint/l2_ball/weight_matrix", weight_matrix, weight_matrix);
688 if (weight_matrix.size() == x_dim)
692 else if (weight_matrix.size() == x_dim * x_dim)
698 ROS_ERROR_STREAM(
"l2-ball weight_matrix dimensions invalid. Must be either " << x_dim <<
" x 1 or " << x_dim <<
" x " << x_dim <<
".");
702 nh.
param(
"planning/terminal_constraint/l2_ball/radius", radius, radius);
703 ocp->setFinalStageConstraint(std::make_shared<TerminalBallSE2>(S, radius));
707 ROS_ERROR_STREAM(
"Unknown terminal_constraint type '" << terminal_constraint <<
"' specified ('planning/terminal_constraint/type').");
717 double min_obstacle_dist = 0.5;
718 nh.
param(
"collision_avoidance/min_obstacle_dist", min_obstacle_dist, min_obstacle_dist);
721 bool enable_dynamic_obstacles =
false;
722 nh.
param(
"collision_avoidance/enable_dynamic_obstacles", enable_dynamic_obstacles, enable_dynamic_obstacles);
725 double force_inclusion_dist = 0.5;
726 nh.
param(
"collision_avoidance/force_inclusion_dist", force_inclusion_dist, force_inclusion_dist);
727 double cutoff_dist = 2;
728 nh.
param(
"collision_avoidance/cutoff_dist", cutoff_dist, cutoff_dist);
735 double acc_lim_x = 0.0;
736 nh.
param(
"robot/unicycle/acc_lim_x", acc_lim_x, acc_lim_x);
737 double dec_lim_x = 0.0;
738 nh.
param(
"robot/unicycle/dec_lim_x", dec_lim_x, dec_lim_x);
744 double acc_lim_theta = 0.0;
745 nh.
param(
"robot/unicycle/acc_lim_theta", acc_lim_theta, acc_lim_theta);
750 Eigen::Vector2d ud_lb(-dec_lim_x, -acc_lim_theta);
751 Eigen::Vector2d ud_ub(acc_lim_x, acc_lim_theta);
756 double acc_lim_x = 0.0;
757 nh.
param(
"robot/simple_car/acc_lim_x", acc_lim_x, acc_lim_x);
758 double dec_lim_x = 0.0;
759 nh.
param(
"robot/simple_car/dec_lim_x", dec_lim_x, dec_lim_x);
765 double max_steering_rate = 0.0;
766 nh.
param(
"robot/simple_car/max_steering_rate", max_steering_rate, max_steering_rate);
771 Eigen::Vector2d ud_lb(-dec_lim_x, -max_steering_rate);
772 Eigen::Vector2d ud_ub(acc_lim_x, max_steering_rate);
775 else if (
_robot_type ==
"kinematic_bicycle_vel_input")
777 double acc_lim_x = 0.0;
778 nh.
param(
"robot/kinematic_bicycle_vel_input/acc_lim_x", acc_lim_x, acc_lim_x);
779 double dec_lim_x = 0.0;
780 nh.
param(
"robot/kinematic_bicycle_vel_input/dec_lim_x", dec_lim_x, dec_lim_x);
786 double max_steering_rate = 0.0;
787 nh.
param(
"robot/kinematic_bicycle_vel_input/max_steering_rate", max_steering_rate, max_steering_rate);
792 Eigen::Vector2d ud_lb(-dec_lim_x, -max_steering_rate);
793 Eigen::Vector2d ud_ub(acc_lim_x, max_steering_rate);
808 const std::vector<geometry_msgs::PoseStamped>& initial_plan,
bool backward)
810 if (initial_plan.size() < 2 || !
_dynamics)
return false;
814 int n_init = (
int)initial_plan.size();
815 int n_ref =
_grid->getInitialN();
818 ROS_ERROR(
"Controller::generateInitialStateTrajectory(): grid not properly initialized");
823 double dt_ref =
_grid->getInitialDt();
824 double tf_ref = (double)(n_ref - 1) * dt_ref;
826 Eigen::VectorXd
x(
_dynamics->getStateDimension());
829 double dt_init = tf_ref / double(n_init - 1);
832 for (
int i = 1; i < n_init - 1; ++i)
838 double dx = initial_plan[i + 1].pose.position.x - initial_plan[i].pose.position.x;
839 double dy = initial_plan[i + 1].pose.position.y - initial_plan[i].pose.position.y;
840 yaw = std::atan2(dy, dx);
845 yaw =
tf2::getYaw(initial_plan[i].pose.orientation);
847 PoseSE2 intermediate_pose(initial_plan[i].pose.position.x, initial_plan[i].pose.position.y, yaw);
848 _dynamics->getSteadyStateFromPoseSE2(intermediate_pose,
x);
860 double inscribed_radius,
double circumscribed_radius,
double min_resolution_collision_check_angular,
865 ROS_ERROR(
"Controller must be configured before invoking step().");
868 if (
_grid->getN() < 2)
return false;
876 ROS_ERROR(
"isPoseTrajectoriyFeasible is currently only implemented for fd grids");
880 if (look_ahead_idx < 0 || look_ahead_idx >=
_grid->getN()) look_ahead_idx =
_grid->getN() - 1;
882 for (
int i = 0; i <= look_ahead_idx; ++i)
885 circumscribed_radius) == -1)
892 if (i < look_ahead_idx)
895 Eigen::Vector2d delta_dist = fd_grid->
getState(i + 1).head(2) - fd_grid->
getState(i).head(2);
896 if (std::abs(delta_rot) > min_resolution_collision_check_angular || delta_dist.norm() > inscribed_radius)
898 int n_additional_samples = std::max(std::ceil(std::abs(delta_rot) / min_resolution_collision_check_angular),
899 std::ceil(delta_dist.norm() / inscribed_radius)) -
905 intermediate_pose.
position() = intermediate_pose.position() + delta_dist / (n_additional_samples + 1.0);
906 intermediate_pose.theta() =
g2o::normalize_theta(intermediate_pose.theta() + delta_rot / (n_additional_samples + 1.0));
907 if (costmap_model->
footprintCost(intermediate_pose.x(), intermediate_pose.y(), intermediate_pose.theta(), footprint_spec,
908 inscribed_radius, circumscribed_radius) == -1)
bool _guess_backwards_motion
#define PRINT_ERROR_COND(cond, msg)
teb_local_planner::PoseSE2 _last_goal
Eigen::VectorXd _recent_x_feedback
bool _initial_plan_estimate_orientation
corbo::DiscretizationGridInterface::Ptr _grid
bool step(const PoseSE2 &start, const PoseSE2 &goal, const geometry_msgs::Twist &vel, double dt, ros::Time t, corbo::TimeSeries::Ptr u_seq, corbo::TimeSeries::Ptr x_seq)
void publishOptimalControlResult()
void setTrajectory(TimeSeries::Ptr trajectory, TimeSeries::Interpolation interpolation)
Eigen::Vector2d & position()
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::shared_ptr< BaseHyperGraphOptimizationProblem > Ptr
corbo::StructuredOptimalControlProblem::Ptr _structured_ocp
ControllerStatistics _statistics
bool generateInitialStateTrajectory(const Eigen::VectorXd &x0, const Eigen::VectorXd &xf, const std::vector< geometry_msgs::PoseStamped > &initial_plan, bool backward)
geometry_msgs::TransformStamped t
OptimalControlProblemInterface::Ptr _ocp
std::shared_ptr< RobotDynamicsInterface > Ptr
double _force_reinit_new_goal_dist
corbo::NlpSolverInterface::Ptr configureSolver(const ros::NodeHandle &nh)
RobotDynamicsInterface::Ptr _dynamics
void toPoseMsg(geometry_msgs::Pose &pose) const
Scalar EIGEN_BLAS_FUNC() dot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
corbo::StructuredOptimalControlProblem::Ptr configureOcp(const ros::NodeHandle &nh, const teb_local_planner::ObstContainer &obstacles, teb_local_planner::RobotFootprintModelPtr robot_model, const std::vector< teb_local_planner::PoseSE2 > &via_points)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
void stateFeedbackCallback(const mpc_local_planner_msgs::StateFeedback::ConstPtr &msg)
std::shared_ptr< FiniteDifferencesGridSE2 > Ptr
std::vector< ObstaclePtr > ObstContainer
corbo::DiscretizationGridInterface::Ptr configureGrid(const ros::NodeHandle &nh)
void setTimeFromStart(const Time &time_from_start)
constexpr const double CORBO_INF_DBL
#define ROS_INFO_STREAM_COND(cond, args)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::mutex _x_feedback_mutex
double _force_reinit_new_goal_angular
RobotDynamicsInterface::Ptr configureRobotDynamics(const ros::NodeHandle &nh)
ros::Subscriber _x_feedback_sub
#define ROS_WARN_STREAM(args)
void setAutoUpdatePreviousControl(bool enable)
double getYaw(const A &a)
StageInequalitySE2::Ptr _inequality_constraint
std::shared_ptr< DiscretizationGridInterface > Ptr
std::shared_ptr< FiniteDifferencesVariableGridSE2 > Ptr
Full discretization grid specialization for SE2.
int _force_reinit_num_steps
bool _publish_ocp_results
double normalize_theta(double theta)
normalize angle to interval [-pi, pi)
std::shared_ptr< NlpSolverInterface > Ptr
virtual double footprintCost(const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)
const Eigen::VectorXd & getState(int k) const
Return state at time stamp k.
ros::Publisher _ocp_result_pub
void setNumOcpIterations(int ocp_iter)
std::shared_ptr< SolverIpopt > Ptr
std::shared_ptr< TimeSeries > Ptr
#define ROS_ERROR_STREAM(args)
bool configure(ros::NodeHandle &nh, const teb_local_planner::ObstContainer &obstacles, teb_local_planner::RobotFootprintModelPtr robot_model, const std::vector< teb_local_planner::PoseSE2 > &via_points)
std::shared_ptr< LevenbergMarquardtSparse > Ptr
corbo::DiscreteTimeReferenceTrajectory _x_seq_init
corbo::NlpSolverInterface::Ptr _solver
std::shared_ptr< StructuredOptimalControlProblem > Ptr
virtual bool isPoseTrajectoryFeasible(base_local_planner::CostmapModel *costmap_model, const std::vector< geometry_msgs::Point > &footprint_spec, double inscribed_radius=0.0, double circumscribed_radius=0.0, double min_resolution_collision_check_angular=M_PI, int look_ahead_idx=-1)
Check whether the planned trajectory is feasible or not.
std::shared_ptr< TimeSeriesSE2 > Ptr