16 #include "nav2_mppi_controller/optimizer.hpp"
26 #include "nav2_core/controller_exceptions.hpp"
27 #include "nav2_costmap_2d/costmap_filters/filter_values.hpp"
33 rclcpp_lifecycle::LifecycleNode::WeakPtr parent,
const std::string & name,
34 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros,
39 costmap_ros_ = costmap_ros;
40 costmap_ = costmap_ros_->getCostmap();
41 parameters_handler_ = param_handler;
43 auto node = parent_.lock();
48 critic_manager_.
on_configure(parent_, name_, costmap_ros_, parameters_handler_);
61 std::string motion_model_name;
66 getParam(s.model_dt,
"model_dt", 0.05f);
67 getParam(s.time_steps,
"time_steps", 56);
68 getParam(s.batch_size,
"batch_size", 1000);
69 getParam(s.iteration_count,
"iteration_count", 1);
70 getParam(s.temperature,
"temperature", 0.3f);
71 getParam(s.gamma,
"gamma", 0.015f);
72 getParam(s.base_constraints.vx_max,
"vx_max", 0.5f);
73 getParam(s.base_constraints.vx_min,
"vx_min", -0.35f);
74 getParam(s.base_constraints.vy,
"vy_max", 0.5f);
75 getParam(s.base_constraints.wz,
"wz_max", 1.9f);
76 getParam(s.base_constraints.ax_max,
"ax_max", 3.0f);
77 getParam(s.base_constraints.ax_min,
"ax_min", -3.0f);
78 getParam(s.base_constraints.ay_max,
"ay_max", 3.0f);
79 getParam(s.base_constraints.ay_min,
"ay_min", -3.0f);
80 getParam(s.base_constraints.az_max,
"az_max", 3.5f);
81 getParam(s.sampling_std.vx,
"vx_std", 0.2f);
82 getParam(s.sampling_std.vy,
"vy_std", 0.2f);
83 getParam(s.sampling_std.wz,
"wz_std", 0.4f);
84 getParam(s.retry_attempt_limit,
"retry_attempt_limit", 1);
86 s.base_constraints.ax_max = fabs(s.base_constraints.ax_max);
87 if (s.base_constraints.ax_min > 0.0) {
88 s.base_constraints.ax_min = -1.0 * s.base_constraints.ax_min;
91 "Sign of the parameter ax_min is incorrect, consider setting it negative.");
94 if (s.base_constraints.ay_min > 0.0) {
95 s.base_constraints.ay_min = -1.0 * s.base_constraints.ay_min;
98 "Sign of the parameter ay_min is incorrect, consider setting it negative.");
102 getParam(motion_model_name,
"motion_model", std::string(
"DiffDrive"));
104 s.constraints = s.base_constraints;
109 double controller_frequency;
110 getParentParam(controller_frequency,
"controller_frequency", 0.0, ParameterType::Static);
116 const double controller_period = 1.0 / controller_frequency;
117 constexpr
double eps = 1e-6;
119 if ((controller_period + eps) < settings_.model_dt) {
122 "Controller period is less then model dt, consider setting it equal");
123 }
else if (abs(controller_period - settings_.model_dt) < eps) {
126 "Controller period is equal to model dt. Control sequence "
128 settings_.shift_control_sequence =
true;
131 "Controller period more then model dt, set it equal to model dt");
137 state_.
reset(settings_.batch_size, settings_.time_steps);
138 control_sequence_.reset(settings_.time_steps);
139 control_history_[0] = {0.0f, 0.0f, 0.0f};
140 control_history_[1] = {0.0f, 0.0f, 0.0f};
141 control_history_[2] = {0.0f, 0.0f, 0.0f};
142 control_history_[3] = {0.0f, 0.0f, 0.0f};
144 if (reset_dynamic_speed_limits) {
145 settings_.constraints = settings_.base_constraints;
148 costs_.setZero(settings_.batch_size);
149 generated_trajectories_.
reset(settings_.batch_size, settings_.time_steps);
152 motion_model_->initialize(settings_.constraints, settings_.model_dt);
154 RCLCPP_INFO(
logger_,
"Optimizer reset");
159 return motion_model_->isHolonomic();
163 const geometry_msgs::msg::PoseStamped & robot_pose,
164 const geometry_msgs::msg::Twist & robot_speed,
165 const nav_msgs::msg::Path & plan,
166 const geometry_msgs::msg::Pose & goal,
169 prepare(robot_pose, robot_speed, plan, goal, goal_checker);
173 }
while (
fallback(critics_data_.fail_flag));
175 utils::savitskyGolayFilter(control_sequence_, control_history_, settings_);
178 if (settings_.shift_control_sequence) {
187 for (
size_t i = 0; i < settings_.iteration_count; ++i) {
196 static size_t counter = 0;
205 if (++counter > settings_.retry_attempt_limit) {
214 const geometry_msgs::msg::PoseStamped & robot_pose,
215 const geometry_msgs::msg::Twist & robot_speed,
216 const nav_msgs::msg::Path & plan,
217 const geometry_msgs::msg::Pose & goal,
220 state_.pose = robot_pose;
221 state_.speed = robot_speed;
222 path_ = utils::toTensor(plan);
226 critics_data_.fail_flag =
false;
227 critics_data_.goal_checker = goal_checker;
228 critics_data_.motion_model = motion_model_;
229 critics_data_.furthest_reached_path_point.reset();
230 critics_data_.path_pts_valid.reset();
235 auto size = control_sequence_.vx.size();
236 utils::shiftColumnsByOnePlace(control_sequence_.vx, -1);
237 utils::shiftColumnsByOnePlace(control_sequence_.wz, -1);
238 control_sequence_.vx(size - 1) = control_sequence_.vx(size - 2);
239 control_sequence_.wz(size - 1) = control_sequence_.wz(size - 2);
242 utils::shiftColumnsByOnePlace(control_sequence_.vy, -1);
243 control_sequence_.vy(size - 1) = control_sequence_.vy(size - 2);
257 auto & s = settings_;
259 float max_delta_vx = s.model_dt * s.constraints.ax_max;
260 float min_delta_vx = s.model_dt * s.constraints.ax_min;
261 float max_delta_vy = s.model_dt * s.constraints.ay_max;
262 float min_delta_vy = s.model_dt * s.constraints.ay_min;
263 float max_delta_wz = s.model_dt * s.constraints.az_max;
264 float vx_last = utils::clamp(s.constraints.vx_min, s.constraints.vx_max, control_sequence_.vx(0));
265 float wz_last = utils::clamp(-s.constraints.wz, s.constraints.wz, control_sequence_.wz(0));
266 control_sequence_.vx(0) = vx_last;
267 control_sequence_.wz(0) = wz_last;
270 vy_last = utils::clamp(-s.constraints.vy, s.constraints.vy, control_sequence_.vy(0));
271 control_sequence_.vy(0) = vy_last;
274 for (
unsigned int i = 1; i != control_sequence_.vx.size(); i++) {
275 float & vx_curr = control_sequence_.vx(i);
276 vx_curr = utils::clamp(s.constraints.vx_min, s.constraints.vx_max, vx_curr);
278 vx_curr = utils::clamp(vx_last + min_delta_vx, vx_last + max_delta_vx, vx_curr);
280 vx_curr = utils::clamp(vx_last - max_delta_vx, vx_last - min_delta_vx, vx_curr);
284 float & wz_curr = control_sequence_.wz(i);
285 wz_curr = utils::clamp(-s.constraints.wz, s.constraints.wz, wz_curr);
286 wz_curr = utils::clamp(wz_last - max_delta_wz, wz_last + max_delta_wz, wz_curr);
290 float & vy_curr = control_sequence_.vy(i);
291 vy_curr = utils::clamp(-s.constraints.vy, s.constraints.vy, vy_curr);
293 vy_curr = utils::clamp(vy_last + min_delta_vy, vy_last + max_delta_vy, vy_curr);
295 vy_curr = utils::clamp(vy_last - max_delta_vy, vy_last - min_delta_vy, vy_curr);
301 motion_model_->applyConstraints(control_sequence_);
314 state.vx.col(0) =
static_cast<float>(state.speed.linear.x);
315 state.wz.col(0) =
static_cast<float>(state.speed.angular.z);
318 state.vy.col(0) =
static_cast<float>(state.speed.linear.y);
325 motion_model_->predict(state);
329 Eigen::Array<float, Eigen::Dynamic, 3> & trajectory,
330 const Eigen::ArrayXXf & sequence)
const
332 float initial_yaw =
static_cast<float>(tf2::getYaw(state_.pose.pose.orientation));
334 const auto vx = sequence.col(0);
335 const auto wz = sequence.col(1);
337 auto traj_x = trajectory.col(0);
338 auto traj_y = trajectory.col(1);
339 auto traj_yaws = trajectory.col(2);
341 const size_t n_size = traj_yaws.size();
343 float last_yaw = initial_yaw;
344 for(
size_t i = 0; i != n_size; i++) {
345 last_yaw += wz(i) * settings_.model_dt;
346 traj_yaws(i) = last_yaw;
349 Eigen::ArrayXf yaw_cos = traj_yaws.cos();
350 Eigen::ArrayXf yaw_sin = traj_yaws.sin();
351 utils::shiftColumnsByOnePlace(yaw_cos, 1);
352 utils::shiftColumnsByOnePlace(yaw_sin, 1);
353 yaw_cos(0) = cosf(initial_yaw);
354 yaw_sin(0) = sinf(initial_yaw);
356 auto dx = (vx * yaw_cos).eval();
357 auto dy = (vx * yaw_sin).eval();
360 auto vy = sequence.col(2);
361 dx = (dx - vy * yaw_sin).eval();
362 dy = (dy + vy * yaw_cos).eval();
365 float last_x = state_.pose.pose.position.x;
366 float last_y = state_.pose.pose.position.y;
367 for(
size_t i = 0; i != n_size; i++) {
368 last_x += dx(i) * settings_.model_dt;
369 last_y += dy(i) * settings_.model_dt;
379 auto initial_yaw =
static_cast<float>(tf2::getYaw(state.pose.pose.orientation));
380 const size_t n_cols = trajectories.yaws.cols();
382 Eigen::ArrayXf last_yaws = Eigen::ArrayXf::Constant(trajectories.yaws.rows(), initial_yaw);
383 for (
size_t i = 0; i != n_cols; i++) {
384 last_yaws += state.wz.col(i) * settings_.model_dt;
385 trajectories.yaws.col(i) = last_yaws;
388 Eigen::ArrayXXf yaw_cos = trajectories.yaws.cos();
389 Eigen::ArrayXXf yaw_sin = trajectories.yaws.sin();
390 utils::shiftColumnsByOnePlace(yaw_cos, 1);
391 utils::shiftColumnsByOnePlace(yaw_sin, 1);
392 yaw_cos.col(0) = cosf(initial_yaw);
393 yaw_sin.col(0) = sinf(initial_yaw);
395 auto dx = (state.vx * yaw_cos).eval();
396 auto dy = (state.vx * yaw_sin).eval();
399 dx -= state.vy * yaw_sin;
400 dy += state.vy * yaw_cos;
403 Eigen::ArrayXf last_x = Eigen::ArrayXf::Constant(trajectories.x.rows(),
404 state.pose.pose.position.x);
405 Eigen::ArrayXf last_y = Eigen::ArrayXf::Constant(trajectories.y.rows(),
406 state.pose.pose.position.y);
408 for (
size_t i = 0; i != n_cols; i++) {
409 last_x += dx.col(i) * settings_.model_dt;
410 last_y += dy.col(i) * settings_.model_dt;
411 trajectories.x.col(i) = last_x;
412 trajectories.y.col(i) = last_y;
419 Eigen::ArrayXXf sequence = Eigen::ArrayXXf(settings_.time_steps, is_holo ? 3 : 2);
420 Eigen::Array<float, Eigen::Dynamic, 3> trajectories =
421 Eigen::Array<float, Eigen::Dynamic, 3>(settings_.time_steps, 3);
423 sequence.col(0) = control_sequence_.vx;
424 sequence.col(1) = control_sequence_.wz;
427 sequence.col(2) = control_sequence_.vy;
436 return control_sequence_;
442 auto & s = settings_;
444 auto vx_T = control_sequence_.vx.transpose();
445 auto bounded_noises_vx = state_.cvx.rowwise() - vx_T;
446 const float gamma_vx = s.gamma / (s.sampling_std.vx * s.sampling_std.vx);
447 costs_ += (gamma_vx * (bounded_noises_vx.rowwise() * vx_T).rowwise().sum()).eval();
449 if (s.sampling_std.wz > 0.0f) {
450 auto wz_T = control_sequence_.wz.transpose();
451 auto bounded_noises_wz = state_.cwz.rowwise() - wz_T;
452 const float gamma_wz = s.gamma / (s.sampling_std.wz * s.sampling_std.wz);
453 costs_ += (gamma_wz * (bounded_noises_wz.rowwise() * wz_T).rowwise().sum()).eval();
457 auto vy_T = control_sequence_.vy.transpose();
458 auto bounded_noises_vy = state_.cvy.rowwise() - vy_T;
459 const float gamma_vy = s.gamma / (s.sampling_std.vy * s.sampling_std.vy);
460 costs_ += (gamma_vy * (bounded_noises_vy.rowwise() * vy_T).rowwise().sum()).eval();
463 auto costs_normalized = costs_ - costs_.minCoeff();
464 const float inv_temp = 1.0f / s.temperature;
465 auto softmaxes = (-inv_temp * costs_normalized).exp().eval();
466 softmaxes /= softmaxes.sum();
468 auto softmax_mat = softmaxes.matrix();
469 control_sequence_.vx = state_.cvx.transpose().matrix() * softmax_mat;
470 control_sequence_.wz = state_.cwz.transpose().matrix() * softmax_mat;
473 control_sequence_.vy = state_.cvy.transpose().matrix() * softmax_mat;
480 const builtin_interfaces::msg::Time & stamp)
482 unsigned int offset = settings_.shift_control_sequence ? 1 : 0;
484 auto vx = control_sequence_.vx(offset);
485 auto wz = control_sequence_.wz(offset);
488 auto vy = control_sequence_.vy(offset);
489 return utils::toTwistStamped(vx, vy, wz, stamp, costmap_ros_->getBaseFrameID());
492 return utils::toTwistStamped(vx, wz, stamp, costmap_ros_->getBaseFrameID());
497 if (model ==
"DiffDrive") {
498 motion_model_ = std::make_shared<DiffDriveMotionModel>();
499 }
else if (model ==
"Omni") {
500 motion_model_ = std::make_shared<OmniMotionModel>();
501 }
else if (model ==
"Ackermann") {
502 motion_model_ = std::make_shared<AckermannMotionModel>(parameters_handler_, name_);
506 "Model " + model +
" is not valid! Valid options are DiffDrive, Omni, "
509 motion_model_->initialize(settings_.constraints, settings_.model_dt);
514 auto & s = settings_;
515 if (speed_limit == nav2_costmap_2d::NO_SPEED_LIMIT) {
516 s.constraints.vx_max = s.base_constraints.vx_max;
517 s.constraints.vx_min = s.base_constraints.vx_min;
518 s.constraints.vy = s.base_constraints.vy;
519 s.constraints.wz = s.base_constraints.wz;
523 double ratio = speed_limit / 100.0;
524 s.constraints.vx_max = s.base_constraints.vx_max * ratio;
525 s.constraints.vx_min = s.base_constraints.vx_min * ratio;
526 s.constraints.vy = s.base_constraints.vy * ratio;
527 s.constraints.wz = s.base_constraints.wz * ratio;
530 double ratio = speed_limit / s.base_constraints.vx_max;
531 s.constraints.vx_max = s.base_constraints.vx_max * ratio;
532 s.constraints.vx_min = s.base_constraints.vx_min * ratio;
533 s.constraints.vy = s.base_constraints.vy * ratio;
534 s.constraints.wz = s.base_constraints.wz * ratio;
541 return generated_trajectories_;
void on_configure(rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string &name, std::shared_ptr< nav2_costmap_2d::Costmap2DROS >, ParametersHandler *)
Configure critic manager on bringup and load plugins.
void evalTrajectoriesScores(CriticData &data) const
Score trajectories by the set of loaded critic functions.
void reset(mppi::models::OptimizerSettings &settings, bool is_holonomic)
Reset noise generator with settings and model types.
void initialize(mppi::models::OptimizerSettings &settings, bool is_holonomic, const std::string &name, ParametersHandler *param_handler)
Initialize noise generator with settings and model types.
void setNoisedControls(models::State &state, const models::ControlSequence &control_sequence)
set noised control_sequence to state controls
void shutdown()
Shutdown noise generator thread.
void generateNextNoises()
Signal to the noise thread the controller is ready to generate a new noised control for the next iter...
geometry_msgs::msg::TwistStamped evalControl(const geometry_msgs::msg::PoseStamped &robot_pose, const geometry_msgs::msg::Twist &robot_speed, const nav_msgs::msg::Path &plan, const geometry_msgs::msg::Pose &goal, nav2_core::GoalChecker *goal_checker)
Compute control using MPPI algorithm.
void updateStateVelocities(models::State &state) const
Update velocities in state.
const models::ControlSequence & getOptimalControlSequence()
Get the optimal control sequence for a cycle for visualization.
void setMotionModel(const std::string &model)
Set the motion model of the vehicle platform.
void setOffset(double controller_frequency)
Using control frequencies and time step size, determine if trajectory offset should be used to popula...
Eigen::ArrayXXf getOptimizedTrajectory()
Get the optimal trajectory for a cycle for visualization.
void reset(bool reset_dynamic_speed_limits=true)
Reset the optimization problem to initial conditions.
rclcpp::Logger logger_
Caution, keep references.
void prepare(const geometry_msgs::msg::PoseStamped &robot_pose, const geometry_msgs::msg::Twist &robot_speed, const nav_msgs::msg::Path &plan, const geometry_msgs::msg::Pose &goal, nav2_core::GoalChecker *goal_checker)
Prepare state information on new request for trajectory rollouts.
void integrateStateVelocities(models::Trajectories &trajectories, const models::State &state) const
Rollout velocities in state to poses.
void updateControlSequence()
Update control sequence with state controls weighted by costs using softmax function.
void generateNoisedTrajectories()
updates generated trajectories with noised trajectories from the last cycle's optimal control
bool fallback(bool fail)
Perform fallback behavior to try to recover from a set of trajectories in collision.
bool isHolonomic() const
Whether the motion model is holonomic.
models::Trajectories & getGeneratedTrajectories()
Get the trajectories generated in a cycle for visualization.
void updateInitialStateVelocities(models::State &state) const
Update initial velocity in state.
void shutdown()
Shutdown for optimizer at process end.
void optimize()
Main function to generate, score, and return trajectories.
void setSpeedLimit(double speed_limit, bool percentage)
Set the maximum speed based on the speed limits callback.
void shiftControlSequence()
Shift the optimal control sequence after processing for next iterations initial conditions after exec...
void applyControlSequenceConstraints()
Apply hard vehicle constraints on control sequence.
void getParams()
Obtain the main controller's parameters.
void propagateStateVelocitiesFromInitials(models::State &state) const
predict velocities in state using model for time horizon equal to timesteps
void initialize(rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string &name, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros, ParametersHandler *dynamic_parameters_handler)
Initializes optimizer on startup.
geometry_msgs::msg::TwistStamped getControlFromSequenceAsTwist(const builtin_interfaces::msg::Time &stamp)
Convert control sequence to a twist command.
Handles getting parameters and dynamic parameter changes.
void addPostCallback(T &&callback)
Set a callback to process after parameter changes.
auto getParamGetter(const std::string &ns)
Get an object to retrieve parameters.
Function-object for checking whether a goal has been reached.
A control sequence over time (e.g. trajectory)
State information: velocities, controls, poses, speed.
void reset(unsigned int batch_size, unsigned int time_steps)
Reset state data.
void reset(unsigned int batch_size, unsigned int time_steps)
Reset state data.