controller.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2020, Christoph Rösmann, All rights reserved.
6  *
7  * This program is free software: you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License as published by
9  * the Free Software Foundation, either version 3 of the License, or
10  * (at your option) any later version.
11  *
12  * This program is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with this program. If not, see <https://www.gnu.org/licenses/>.
19  *
20  * Authors: Christoph Rösmann
21  *********************************************************************/
22 
24 
44 
45 #include <mpc_local_planner_msgs/OptimalControlResult.h>
46 #include <mpc_local_planner_msgs/StateFeedback.h>
47 
48 #include <corbo-communication/utilities.h>
49 #include <corbo-core/console.h>
50 
51 #include <tf2/utils.h>
52 
53 #include <memory>
54 #include <mutex>
55 
56 namespace mpc_local_planner {
57 
59  teb_local_planner::RobotFootprintModelPtr robot_model, const std::vector<teb_local_planner::PoseSE2>& via_points)
60 {
62  if (!_dynamics) return false; // we may need state and control dimensions to check other parameters
63 
64  _grid = configureGrid(nh);
66 
67  _structured_ocp = configureOcp(nh, obstacles, robot_model, via_points);
68  _ocp = _structured_ocp; // copy pointer also to parent member
69 
70  int outer_ocp_iterations = 1;
71  nh.param("controller/outer_ocp_iterations", outer_ocp_iterations, outer_ocp_iterations);
72  setNumOcpIterations(outer_ocp_iterations);
73 
74  // further goal opions
75  nh.param("controller/force_reinit_new_goal_dist", _force_reinit_new_goal_dist, _force_reinit_new_goal_dist);
76  nh.param("controller/force_reinit_new_goal_angular", _force_reinit_new_goal_angular, _force_reinit_new_goal_angular);
77 
78  nh.param("controller/allow_init_with_backward_motion", _guess_backwards_motion, _guess_backwards_motion);
79  nh.param("controller/force_reinit_num_steps", _force_reinit_num_steps, _force_reinit_num_steps);
80 
81  // custom feedback:
82  nh.param("controller/prefer_x_feedback", _prefer_x_feedback, _prefer_x_feedback);
83  _x_feedback_sub = nh.subscribe("state_feedback", 1, &Controller::stateFeedbackCallback, this);
84 
85  // result publisher:
86  _ocp_result_pub = nh.advertise<mpc_local_planner_msgs::OptimalControlResult>("ocp_result", 100);
87  nh.param("controller/publish_ocp_results", _publish_ocp_results, _publish_ocp_results);
88  nh.param("controller/print_cpu_time", _print_cpu_time, _print_cpu_time);
89 
90  setAutoUpdatePreviousControl(false); // we want to update the previous control value manually
91 
92  if (_ocp->initialize())
93  ROS_INFO("OCP initialized.");
94  else
95  {
96  ROS_ERROR("OCP initialization failed");
97  return false;
98  }
99  return _grid && _dynamics && _solver && _structured_ocp;
100 }
101 
102 bool Controller::step(const Controller::PoseSE2& start, const Controller::PoseSE2& goal, const geometry_msgs::Twist& vel, double dt, ros::Time t,
104 {
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);
109 }
110 
111 bool Controller::step(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist& vel, double dt, ros::Time t,
113 {
114  if (!_dynamics || !_grid || !_structured_ocp)
115  {
116  ROS_ERROR("Controller must be configured before invoking step().");
117  return false;
118  }
119  if (initial_plan.size() < 2)
120  {
121  ROS_ERROR("Controller::step(): initial plan must contain at least two poses.");
122  return false;
123  }
124 
125  PoseSE2 start(initial_plan.front().pose);
126  PoseSE2 goal(initial_plan.back().pose);
127 
128  Eigen::VectorXd xf(_dynamics->getStateDimension());
129  _dynamics->getSteadyStateFromPoseSE2(goal, xf);
130 
131  // retrieve or estimate current state
132  Eigen::VectorXd x(_dynamics->getStateDimension());
133  // check for new measurements
134  bool new_x = false;
135  {
136  std::lock_guard<std::mutex> lock(_x_feedback_mutex);
137  new_x = _recent_x_feedback.size() > 0 && (t - _recent_x_time).toSec() < 2.0 * dt;
138  if (new_x) x = _recent_x_feedback;
139  }
140  if (!new_x && (!_x_ts || _x_ts->isEmpty() || !_x_ts->getValuesInterpolate(dt, x))) // predict with previous state sequence
141  {
142  _dynamics->getSteadyStateFromPoseSE2(start, x); // otherwise initialize steady state
143  }
144  if (!new_x || !_prefer_x_feedback)
145  {
146  // Merge state feedback with odometry feedback if desired.
147  // Note, some models like unicycle overwrite the full state by odom feedback unless _prefer_x_measurement is set to true.
148  _dynamics->mergeStateFeedbackAndOdomFeedback(start, vel, x);
149  }
150 
151  // now check goal
153  if (!_grid->isEmpty() && ((goal.position() - _last_goal.position()).norm() > _force_reinit_new_goal_dist ||
154  std::abs(normalize_theta(goal.theta() - _last_goal.theta())) > _force_reinit_new_goal_angular))
155  {
156  // goal pose diverges a lot from the previous one, so force reinit
157  _grid->clear();
158  }
159  if (_grid->isEmpty())
160  {
161  // generate custom initialization based on initial_plan
162  // check if the goal is behind the start pose (w.r.t. start orientation)
163  bool backward = _guess_backwards_motion && (goal.position() - start.position()).dot(start.orientationUnitVec()) < 0;
164  generateInitialStateTrajectory(x, xf, initial_plan, backward);
165  }
166  corbo::Time time(t.toSec());
168 
169  corbo::StaticReference xref(xf); // currently, we only support point-to-point transitions in ros
170  corbo::ZeroReference uref(_dynamics->getInputDimension());
171 
172  _ocp_successful = PredictiveController::step(x, xref, uref, corbo::Duration(dt), time, u_seq, x_seq, nullptr, nullptr, &_x_seq_init);
173  // publish results if desired
174  if (_publish_ocp_results) publishOptimalControlResult(); // TODO(roesmann): we could also pass time t from above
175  ROS_INFO_STREAM_COND(_print_cpu_time, "Cpu time: " << _statistics.step_time.toSec() * 1000.0 << " ms.");
176  ++_ocp_seq;
177  _last_goal = goal;
178  return _ocp_successful;
179 }
180 
181 void Controller::stateFeedbackCallback(const mpc_local_planner_msgs::StateFeedback::ConstPtr& msg)
182 {
183  if (!_dynamics) return;
184 
185  if ((int)msg->state.size() != _dynamics->getStateDimension())
186  {
187  ROS_ERROR_STREAM("stateFeedbackCallback(): state feedback dimension does not match robot state dimension: "
188  << msg->state.size() << " != " << _dynamics->getStateDimension());
189  return;
190  }
191 
192  std::lock_guard<std::mutex> lock(_x_feedback_mutex);
193  _recent_x_time = msg->header.stamp;
194  _recent_x_feedback = Eigen::Map<const Eigen::VectorXd>(msg->state.data(), (int)msg->state.size());
195 }
196 
198 {
199  if (!_dynamics) return;
200  mpc_local_planner_msgs::OptimalControlResult msg;
201  msg.header.stamp = ros::Time::now();
202  msg.header.seq = static_cast<unsigned int>(_ocp_seq);
203  msg.dim_states = _dynamics->getStateDimension();
204  msg.dim_controls = _dynamics->getInputDimension();
205  msg.optimal_solution_found = _ocp_successful;
206  msg.cpu_time = _statistics.step_time.toSec();
207 
208  if (_x_ts && !_x_ts->isEmpty())
209  {
210  msg.time_states = _x_ts->getTime();
211  msg.states = _x_ts->getValues();
212  }
213 
214  if (_u_ts && !_u_ts->isEmpty())
215  {
216  msg.time_controls = _u_ts->getTime();
217  msg.controls = _u_ts->getValues();
218  }
219 
221 }
222 
223 void Controller::reset() { PredictiveController::reset(); }
224 
226 {
227  if (!_dynamics) return {};
228 
229  std::string grid_type = "fd_grid";
230  nh.param("grid/type", grid_type, grid_type);
231 
232  if (grid_type == "fd_grid")
233  {
235 
236  bool variable_grid = true;
237  nh.param("grid/variable_grid/enable", variable_grid, variable_grid);
238  if (variable_grid)
239  {
240  FiniteDifferencesVariableGridSE2::Ptr var_grid = std::make_shared<FiniteDifferencesVariableGridSE2>();
241 
242  double min_dt = 0.0;
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);
247 
248  bool grid_adaptation = true;
249  nh.param("grid/variable_grid/grid_adaptation/enable", grid_adaptation, grid_adaptation);
250 
251  if (grid_adaptation)
252  {
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);
258 
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);
262  }
263  else
264  {
265  var_grid->disableGridAdaptation();
266  }
267  grid = var_grid;
268  }
269  else
270  {
271  grid = std::make_shared<FiniteDifferencesGridSE2>();
272  }
273  // common grid parameters
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);
277 
278  double dt_ref = 0.3;
279  nh.param("grid/dt_ref", dt_ref, dt_ref);
280  grid->setDtRef(dt_ref);
281 
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())
285  {
286  ROS_ERROR_STREAM("Array size of `xf_fixed` does not match robot state dimension(): " << xf_fixed.size()
287  << " != " << _dynamics->getStateDimension());
288  return {};
289  }
290  Eigen::Matrix<bool, -1, 1> xf_fixed_eigen(xf_fixed.size()); // we cannot use Eigen::Map as vector<bool> does not provide raw access
291  for (int i = 0; i < (int)xf_fixed.size(); ++i) xf_fixed_eigen[i] = xf_fixed[i];
292  grid->setXfFixed(xf_fixed_eigen);
293 
294  bool warm_start = true;
295  nh.param("grid/warm_start", warm_start, warm_start);
296  grid->setWarmStart(warm_start);
297 
298  std::string collocation_method = "forward_differences";
299  nh.param("grid/collocation_method", collocation_method, collocation_method);
300 
301  if (collocation_method == "forward_differences")
302  {
303  grid->setFiniteDifferencesCollocationMethod(std::make_shared<ForwardDiffCollocationSE2>());
304  }
305  else if (collocation_method == "midpoint_differences")
306  {
307  grid->setFiniteDifferencesCollocationMethod(std::make_shared<MidpointDiffCollocationSE2>());
308  }
309  else if (collocation_method == "crank_nicolson_differences")
310  {
311  grid->setFiniteDifferencesCollocationMethod(std::make_shared<CrankNicolsonDiffCollocationSE2>());
312  }
313  else
314  {
315  ROS_ERROR_STREAM("Unknown collocation method '" << collocation_method << "' specified. Falling back to default...");
316  }
317 
318  std::string cost_integration_method = "left_sum";
319  nh.param("grid/cost_integration_method", cost_integration_method, cost_integration_method);
320 
321  if (cost_integration_method == "left_sum")
322  {
324  }
325  else if (cost_integration_method == "trapezoidal_rule")
326  {
328  }
329  else
330  {
331  ROS_ERROR_STREAM("Unknown cost integration method '" << cost_integration_method << "' specified. Falling back to default...");
332  }
333 
334  return std::move(grid);
335  }
336  else
337  {
338  ROS_ERROR_STREAM("Unknown grid type '" << grid_type << "' specified.");
339  }
340 
341  return {};
342 }
343 
345 {
346  _robot_type = "unicycle";
347  nh.param("robot/type", _robot_type, _robot_type);
348 
349  if (_robot_type == "unicycle")
350  {
351  return std::make_shared<UnicycleModel>();
352  }
353  else if (_robot_type == "simple_car")
354  {
355  double wheelbase = 0.5;
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);
361  else
362  return std::make_shared<SimpleCarModel>(wheelbase);
363  }
364  else if (_robot_type == "kinematic_bicycle_vel_input")
365  {
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);
371  }
372  else
373  {
374  ROS_ERROR_STREAM("Unknown robot type '" << _robot_type << "' specified.");
375  }
376 
377  return {};
378 }
379 
381 {
382 
383  std::string solver_type = "ipopt";
384  nh.param("solver/type", solver_type, solver_type);
385 
386  if (solver_type == "ipopt")
387  {
388  corbo::SolverIpopt::Ptr solver = std::make_shared<corbo::SolverIpopt>();
389  solver->initialize(); // requried for setting parameters afterward
390 
391  int iterations = 100;
392  nh.param("solver/ipopt/iterations", iterations, iterations);
393  solver->setIterations(iterations);
394 
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);
398 
399  // now check for additional ipopt options
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)
403  {
404  if (!solver->setIpoptOptionNumeric(item.first, item.second)) ROS_WARN_STREAM("Ipopt option " << item.first << " could not be set.");
405  }
406 
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)
410  {
411  if (!solver->setIpoptOptionString(item.first, item.second)) ROS_WARN_STREAM("Ipopt option " << item.first << " could not be set.");
412  }
413 
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)
417  {
418  if (!solver->setIpoptOptionInt(item.first, item.second)) ROS_WARN_STREAM("Ipopt option " << item.first << " could not be set.");
419  }
420 
421  return std::move(solver);
422  }
423  // else if (solver_type == "sqp")
424  // {
425  // corbo::SolverSQP::Ptr solver = std::make_shared<corbo::SolverSQP>();
426  // solver->setUseObjectiveHessian(true);
427  // // solver->setQpZeroWarmstart(false);
428  // solver->setVerbose(true);
429  // corbo::SolverOsqp::Ptr qp_solver = std::make_shared<corbo::SolverOsqp>();
430  // qp_solver->getOsqpSettings()->verbose = 1;
431  // solver->setQpSolver(qp_solver);
432  // corbo::LineSearchL1::Ptr ls = std::make_shared<corbo::LineSearchL1>();
433  // ls->setVerbose(true);
434  // ls->setEta(1e-6);
435  // solver->setLineSearchAlgorithm(ls);
436 
437  // return std::move(solver);
438  // }
439  else if (solver_type == "lsq_lm")
440  {
441  corbo::LevenbergMarquardtSparse::Ptr solver = std::make_shared<corbo::LevenbergMarquardtSparse>();
442 
443  int iterations = 10;
444  nh.param("solver/lsq_lm/iterations", iterations, iterations);
445  solver->setIterations(iterations);
446 
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);
453 
454  solver->setPenaltyWeights(weight_init_eq, weight_init_ineq, weight_init_bounds);
455 
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);
462 
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);
469 
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);
472 
473  return std::move(solver);
474  }
475  else
476  {
477  ROS_ERROR_STREAM("Unknown solver type '" << solver_type << "' specified.");
478  }
479 
480  return {};
481 }
482 
485  const std::vector<teb_local_planner::PoseSE2>& via_points)
486 {
487  corbo::BaseHyperGraphOptimizationProblem::Ptr hg = std::make_shared<corbo::HyperGraphOptimizationProblemEdgeBased>();
488 
489  corbo::StructuredOptimalControlProblem::Ptr ocp = std::make_shared<corbo::StructuredOptimalControlProblem>(_grid, _dynamics, hg, _solver);
490 
491  const int x_dim = _dynamics->getStateDimension();
492  const int u_dim = _dynamics->getInputDimension();
493 
494  if (_robot_type == "unicycle")
495  {
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)
501  {
502  ROS_WARN("max_vel_x_backwards must be >= 0");
503  max_vel_x_backwards *= -1;
504  }
505  double max_vel_theta = 0.3;
506  nh.param("robot/unicycle/max_vel_theta", max_vel_theta, max_vel_theta);
507 
508  // ocp->setBounds(Eigen::Vector3d(-corbo::CORBO_INF_DBL, -corbo::CORBO_INF_DBL, -corbo::CORBO_INF_DBL),
509  // Eigen::Vector3d(corbo::CORBO_INF_DBL, corbo::CORBO_INF_DBL, corbo::CORBO_INF_DBL),
510  // Eigen::Vector2d(-max_vel_x_backwards, -max_vel_theta), Eigen::Vector2d(max_vel_x, max_vel_theta));
511  ocp->setControlBounds(Eigen::Vector2d(-max_vel_x_backwards, -max_vel_theta), Eigen::Vector2d(max_vel_x, max_vel_theta));
512  }
513  else if (_robot_type == "simple_car")
514  {
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)
520  {
521  ROS_WARN("max_vel_x_backwards must be >= 0");
522  max_vel_x_backwards *= -1;
523  }
524  double max_steering_angle = 1.5;
525  nh.param("robot/simple_car/max_steering_angle", max_steering_angle, max_steering_angle);
526 
527  ocp->setControlBounds(Eigen::Vector2d(-max_vel_x_backwards, -max_steering_angle), Eigen::Vector2d(max_vel_x, max_steering_angle));
528  }
529  else if (_robot_type == "kinematic_bicycle_vel_input")
530  {
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)
536  {
537  ROS_WARN("max_vel_x_backwards must be >= 0");
538  max_vel_x_backwards *= -1;
539  }
540  double max_steering_angle = 1.5;
541  nh.param("robot/kinematic_bicycle_vel_input/max_steering_angle", max_steering_angle, max_steering_angle);
542 
543  ocp->setControlBounds(Eigen::Vector2d(-max_vel_x_backwards, -max_steering_angle), Eigen::Vector2d(max_vel_x, max_steering_angle));
544  }
545  else
546  {
547  ROS_ERROR_STREAM("Cannot configure OCP for unknown robot type " << _robot_type << ".");
548  return {};
549  }
550 
551  std::string objective_type = "minimum_time";
552  nh.param("planning/objective/type", objective_type, objective_type);
553  bool lsq_solver = _solver->isLsqSolver();
554 
555  if (objective_type == "minimum_time")
556  {
557  ocp->setStageCost(std::make_shared<corbo::MinimumTime>(lsq_solver));
558  }
559  else if (objective_type == "quadratic_form")
560  {
561  std::vector<double> state_weights;
562  nh.param("planning/objective/quadratic_form/state_weights", state_weights, state_weights);
563  Eigen::MatrixXd Q;
564  if (state_weights.size() == x_dim)
565  {
566  Q = Eigen::Map<Eigen::VectorXd>(state_weights.data(), x_dim).asDiagonal();
567  }
568  else if (state_weights.size() == x_dim * x_dim)
569  {
570  Q = Eigen::Map<Eigen::MatrixXd>(state_weights.data(), x_dim, x_dim); // Eigens default is column major
571  }
572  else
573  {
574  ROS_ERROR_STREAM("State weights dimension invalid. Must be either " << x_dim << " x 1 or " << x_dim << " x " << x_dim << ".");
575  return {};
576  }
577  std::vector<double> control_weights;
578  nh.param("planning/objective/quadratic_form/control_weights", control_weights, control_weights);
579  Eigen::MatrixXd R;
580  if (control_weights.size() == u_dim)
581  {
582  R = Eigen::Map<Eigen::VectorXd>(control_weights.data(), u_dim).asDiagonal();
583  }
584  else if (control_weights.size() == u_dim * u_dim)
585  {
586  R = Eigen::Map<Eigen::MatrixXd>(control_weights.data(), u_dim, u_dim); // Eigens default is column major
587  }
588  else
589  {
590  ROS_ERROR_STREAM("Control weights dimension invalid. Must be either " << u_dim << " x 1 or " << u_dim << " x " << u_dim << ".");
591  return {};
592  }
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);
597 
598  bool q_zero = Q.isZero();
599  bool r_zero = R.isZero();
600  if (!q_zero && !r_zero)
601  {
602  PRINT_ERROR_COND(hybrid_cost_minimum_time,
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));
606  }
607  else if (!q_zero && r_zero)
608  {
609  PRINT_ERROR_COND(hybrid_cost_minimum_time,
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));
613  }
614  else if (q_zero && !r_zero)
615  {
616  if (hybrid_cost_minimum_time)
617  {
618  ocp->setStageCost(std::make_shared<corbo::MinTimeQuadraticControls>(R, integral_form, lsq_solver));
619  }
620  else
621  {
622  ocp->setStageCost(std::make_shared<corbo::QuadraticControlCost>(R, integral_form, lsq_solver));
623  }
624  }
625  }
626  else if (objective_type == "minimum_time_via_points")
627  {
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));
635  // TODO(roesmann): lsq version
636  }
637  else
638  {
639  ROS_ERROR_STREAM("Unknown objective type '" << objective_type << "' specified ('planning/objective/type').");
640  return {};
641  }
642 
643  std::string terminal_cost = "none";
644  nh.param("planning/terminal_cost/type", terminal_cost, terminal_cost);
645 
646  if (terminal_cost == "none")
647  {
648  ocp->setFinalStageCost({});
649  }
650  else if (terminal_cost == "quadratic")
651  {
652  std::vector<double> state_weights;
653  nh.param("planning/terminal_cost/quadratic/final_state_weights", state_weights, state_weights);
654  Eigen::MatrixXd Qf;
655  if (state_weights.size() == x_dim)
656  {
657  Qf = Eigen::Map<Eigen::VectorXd>(state_weights.data(), x_dim).asDiagonal();
658  }
659  else if (state_weights.size() == x_dim * x_dim)
660  {
661  Qf = Eigen::Map<Eigen::MatrixXd>(state_weights.data(), x_dim, x_dim); // Eigens default is column major
662  }
663  else
664  {
665  ROS_ERROR_STREAM("Final state weights dimension invalid. Must be either " << x_dim << " x 1 or " << x_dim << " x " << x_dim << ".");
666  return {};
667  }
668  ocp->setFinalStageCost(std::make_shared<QuadraticFinalStateCostSE2>(Qf, lsq_solver));
669  }
670  else
671  {
672  ROS_ERROR_STREAM("Unknown terminal_cost type '" << terminal_cost << "' specified ('planning/terminal_cost/type').");
673  return {};
674  }
675 
676  std::string terminal_constraint = "none";
677  nh.param("planning/terminal_constraint/type", terminal_constraint, terminal_constraint);
678 
679  if (terminal_constraint == "none")
680  {
681  ocp->setFinalStageConstraint({});
682  }
683  else if (terminal_constraint == "l2_ball")
684  {
685  std::vector<double> weight_matrix;
686  nh.param("planning/terminal_constraint/l2_ball/weight_matrix", weight_matrix, weight_matrix);
687  Eigen::MatrixXd S;
688  if (weight_matrix.size() == x_dim)
689  {
690  S = Eigen::Map<Eigen::VectorXd>(weight_matrix.data(), x_dim).asDiagonal();
691  }
692  else if (weight_matrix.size() == x_dim * x_dim)
693  {
694  S = Eigen::Map<Eigen::MatrixXd>(weight_matrix.data(), x_dim, x_dim); // Eigens default is column major
695  }
696  else
697  {
698  ROS_ERROR_STREAM("l2-ball weight_matrix dimensions invalid. Must be either " << x_dim << " x 1 or " << x_dim << " x " << x_dim << ".");
699  return {};
700  }
701  double radius = 1.0;
702  nh.param("planning/terminal_constraint/l2_ball/radius", radius, radius);
703  ocp->setFinalStageConstraint(std::make_shared<TerminalBallSE2>(S, radius));
704  }
705  else
706  {
707  ROS_ERROR_STREAM("Unknown terminal_constraint type '" << terminal_constraint << "' specified ('planning/terminal_constraint/type').");
708  return {};
709  }
710 
711  _inequality_constraint = std::make_shared<StageInequalitySE2>();
712  _inequality_constraint->setObstacleVector(obstacles);
713  _inequality_constraint->setRobotFootprintModel(robot_model);
714 
715  // configure collision avoidance
716 
717  double min_obstacle_dist = 0.5;
718  nh.param("collision_avoidance/min_obstacle_dist", min_obstacle_dist, min_obstacle_dist);
719  _inequality_constraint->setMinimumDistance(min_obstacle_dist);
720 
721  bool enable_dynamic_obstacles = false;
722  nh.param("collision_avoidance/enable_dynamic_obstacles", enable_dynamic_obstacles, enable_dynamic_obstacles);
723  _inequality_constraint->setEnableDynamicObstacles(enable_dynamic_obstacles);
724 
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);
729  _inequality_constraint->setObstacleFilterParameters(force_inclusion_dist, cutoff_dist);
730 
731  // configure control deviation bounds
732 
733  if (_robot_type == "unicycle")
734  {
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);
739  if (dec_lim_x < 0)
740  {
741  ROS_WARN("dec_lim_x must be >= 0");
742  dec_lim_x *= -1;
743  }
744  double acc_lim_theta = 0.0;
745  nh.param("robot/unicycle/acc_lim_theta", acc_lim_theta, acc_lim_theta);
746 
747  if (acc_lim_x <= 0) acc_lim_x = corbo::CORBO_INF_DBL;
748  if (dec_lim_x <= 0) dec_lim_x = corbo::CORBO_INF_DBL;
749  if (acc_lim_theta <= 0) acc_lim_theta = corbo::CORBO_INF_DBL;
750  Eigen::Vector2d ud_lb(-dec_lim_x, -acc_lim_theta);
751  Eigen::Vector2d ud_ub(acc_lim_x, acc_lim_theta);
752  _inequality_constraint->setControlDeviationBounds(ud_lb, ud_ub);
753  }
754  else if (_robot_type == "simple_car")
755  {
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);
760  if (dec_lim_x < 0)
761  {
762  ROS_WARN("dec_lim_x must be >= 0");
763  dec_lim_x *= -1;
764  }
765  double max_steering_rate = 0.0;
766  nh.param("robot/simple_car/max_steering_rate", max_steering_rate, max_steering_rate);
767 
768  if (acc_lim_x <= 0) acc_lim_x = corbo::CORBO_INF_DBL;
769  if (dec_lim_x <= 0) dec_lim_x = corbo::CORBO_INF_DBL;
770  if (max_steering_rate <= 0) max_steering_rate = corbo::CORBO_INF_DBL;
771  Eigen::Vector2d ud_lb(-dec_lim_x, -max_steering_rate);
772  Eigen::Vector2d ud_ub(acc_lim_x, max_steering_rate);
773  _inequality_constraint->setControlDeviationBounds(ud_lb, ud_ub);
774  }
775  else if (_robot_type == "kinematic_bicycle_vel_input")
776  {
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);
781  if (dec_lim_x < 0)
782  {
783  ROS_WARN("dec_lim_x must be >= 0");
784  dec_lim_x *= -1;
785  }
786  double max_steering_rate = 0.0;
787  nh.param("robot/kinematic_bicycle_vel_input/max_steering_rate", max_steering_rate, max_steering_rate);
788 
789  if (acc_lim_x <= 0) acc_lim_x = corbo::CORBO_INF_DBL;
790  if (dec_lim_x <= 0) dec_lim_x = corbo::CORBO_INF_DBL;
791  if (max_steering_rate <= 0) max_steering_rate = corbo::CORBO_INF_DBL;
792  Eigen::Vector2d ud_lb(-dec_lim_x, -max_steering_rate);
793  Eigen::Vector2d ud_ub(acc_lim_x, max_steering_rate);
794  _inequality_constraint->setControlDeviationBounds(ud_lb, ud_ub);
795  }
796  else
797  {
798  ROS_ERROR_STREAM("Cannot configure control deviation bounds for unknown robot type " << _robot_type << ".");
799  return {};
800  }
801 
802  ocp->setStageInequalityConstraint(_inequality_constraint);
803 
804  return ocp;
805 }
806 
807 bool Controller::generateInitialStateTrajectory(const Eigen::VectorXd& x0, const Eigen::VectorXd& xf,
808  const std::vector<geometry_msgs::PoseStamped>& initial_plan, bool backward)
809 {
810  if (initial_plan.size() < 2 || !_dynamics) return false;
811 
812  TimeSeriesSE2::Ptr ts = std::make_shared<TimeSeriesSE2>();
813 
814  int n_init = (int)initial_plan.size();
815  int n_ref = _grid->getInitialN();
816  if (n_ref < 2)
817  {
818  ROS_ERROR("Controller::generateInitialStateTrajectory(): grid not properly initialized");
819  return false;
820  }
821  ts->add(0.0, x0);
822 
823  double dt_ref = _grid->getInitialDt();
824  double tf_ref = (double)(n_ref - 1) * dt_ref;
825 
826  Eigen::VectorXd x(_dynamics->getStateDimension());
827 
828  // we initialize by assuming equally distributed poses
829  double dt_init = tf_ref / double(n_init - 1);
830 
831  double t = dt_init;
832  for (int i = 1; i < n_init - 1; ++i)
833  {
834  // get yaw from the orientation of the distance vector between pose_{i+1} and pose_{i}
835  double yaw;
837  {
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);
841  if (backward) normalize_theta(yaw + M_PI);
842  }
843  else
844  {
845  yaw = tf2::getYaw(initial_plan[i].pose.orientation);
846  }
847  PoseSE2 intermediate_pose(initial_plan[i].pose.position.x, initial_plan[i].pose.position.y, yaw);
848  _dynamics->getSteadyStateFromPoseSE2(intermediate_pose, x);
849  ts->add(t, x);
850  t += dt_init;
851  }
852 
853  ts->add(tf_ref, xf);
854 
856  return true;
857 }
858 
859 bool Controller::isPoseTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector<geometry_msgs::Point>& footprint_spec,
860  double inscribed_radius, double circumscribed_radius, double min_resolution_collision_check_angular,
861  int look_ahead_idx)
862 {
863  if (!_grid)
864  {
865  ROS_ERROR("Controller must be configured before invoking step().");
866  return false;
867  }
868  if (_grid->getN() < 2) return false;
869 
870  // we currently require a full discretization grid as we want to have fast access to
871  // individual states without requiring any new simulation.
872  // Alternatively, other grids could be used in combination with method getStateAndControlTimeSeries()
873  const FullDiscretizationGridBaseSE2* fd_grid = dynamic_cast<const FullDiscretizationGridBaseSE2*>(_grid.get());
874  if (!fd_grid)
875  {
876  ROS_ERROR("isPoseTrajectoriyFeasible is currently only implemented for fd grids");
877  return true;
878  }
879 
880  if (look_ahead_idx < 0 || look_ahead_idx >= _grid->getN()) look_ahead_idx = _grid->getN() - 1;
881 
882  for (int i = 0; i <= look_ahead_idx; ++i)
883  {
884  if (costmap_model->footprintCost(fd_grid->getState(i)[0], fd_grid->getState(i)[1], fd_grid->getState(i)[2], footprint_spec, inscribed_radius,
885  circumscribed_radius) == -1)
886  {
887  return false;
888  }
889  // Checks if the distance between two poses is higher than the robot radius or the orientation diff is bigger than the specified threshold
890  // and interpolates in that case.
891  // (if obstacles are pushing two consecutive poses away, the center between two consecutive poses might coincide with the obstacle ;-)!
892  if (i < look_ahead_idx)
893  {
894  double delta_rot = normalize_theta(fd_grid->getState(i + 1)[2] - fd_grid->getState(i)[2]);
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)
897  {
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)) -
900  1;
901 
902  PoseSE2 intermediate_pose(fd_grid->getState(i)[0], fd_grid->getState(i)[1], fd_grid->getState(i)[2]);
903  for (int step = 0; step < n_additional_samples; ++step)
904  {
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)
909  {
910  return false;
911  }
912  }
913  }
914  }
915  }
916  return true;
917 }
918 
919 } // namespace mpc_local_planner
Scalar * x
#define PRINT_ERROR_COND(cond, msg)
teb_local_planner::PoseSE2 _last_goal
Definition: controller.h:136
Eigen::VectorXd _recent_x_feedback
Definition: controller.h:134
ROSCPP_DECL void start()
corbo::DiscretizationGridInterface::Ptr _grid
Definition: controller.h:118
return int(ret)+1
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)
Definition: controller.cpp:102
wheelbase
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
Definition: controller.h:122
ControllerStatistics _statistics
bool generateInitialStateTrajectory(const Eigen::VectorXd &x0, const Eigen::VectorXd &xf, const std::vector< geometry_msgs::PoseStamped > &initial_plan, bool backward)
Definition: controller.cpp:807
#define ROS_WARN(...)
geometry_msgs::TransformStamped t
OptimalControlProblemInterface::Ptr _ocp
std::shared_ptr< RobotDynamicsInterface > Ptr
corbo::NlpSolverInterface::Ptr configureSolver(const ros::NodeHandle &nh)
Definition: controller.cpp:380
RobotDynamicsInterface::Ptr _dynamics
Definition: controller.h:119
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)
Definition: controller.cpp:483
bool param(const std::string &param_name, T &param_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)
Definition: controller.cpp:181
#define ROS_INFO(...)
std::shared_ptr< FiniteDifferencesGridSE2 > Ptr
std::vector< ObstaclePtr > ObstContainer
corbo::DiscretizationGridInterface::Ptr configureGrid(const ros::NodeHandle &nh)
Definition: controller.cpp:225
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)
RobotDynamicsInterface::Ptr configureRobotDynamics(const ros::NodeHandle &nh)
Definition: controller.cpp:344
ros::Subscriber _x_feedback_sub
Definition: controller.h:131
#define ROS_WARN_STREAM(args)
void setAutoUpdatePreviousControl(bool enable)
double getYaw(const A &a)
StageInequalitySE2::Ptr _inequality_constraint
Definition: controller.h:121
double toSec() const
std::shared_ptr< DiscretizationGridInterface > Ptr
std::shared_ptr< FiniteDifferencesVariableGridSE2 > Ptr
Full discretization grid specialization for SE2.
double normalize_theta(double theta)
normalize angle to interval [-pi, pi)
Definition: math_utils.h:81
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
Definition: controller.h:124
static Time now()
void setNumOcpIterations(int ocp_iter)
std::shared_ptr< SolverIpopt > Ptr
std::shared_ptr< TimeSeries > Ptr
#define ROS_ERROR_STREAM(args)
#define ROS_ERROR(...)
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)
Definition: controller.cpp:58
std::shared_ptr< LevenbergMarquardtSparse > Ptr
corbo::DiscreteTimeReferenceTrajectory _x_seq_init
Definition: controller.h:139
corbo::NlpSolverInterface::Ptr _solver
Definition: controller.h:120
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.
Definition: controller.cpp:859
std::shared_ptr< TimeSeriesSE2 > Ptr


mpc_local_planner
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:53:18