15 #include "nav2_mppi_controller/optimizer.hpp"
23 #include <xtensor/xmath.hpp>
24 #include <xtensor/xrandom.hpp>
25 #include <xtensor/xnoalias.hpp>
27 #include "nav2_costmap_2d/costmap_filters/filter_values.hpp"
32 using namespace xt::placeholders;
33 using xt::evaluation_strategy::immediate;
36 rclcpp_lifecycle::LifecycleNode::WeakPtr parent,
const std::string & name,
37 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros,
42 costmap_ros_ = costmap_ros;
43 costmap_ = costmap_ros_->getCostmap();
44 parameters_handler_ = param_handler;
46 auto node = parent_.lock();
47 logger_ = node->get_logger();
51 critic_manager_.on_configure(parent_, name_, costmap_ros_, parameters_handler_);
52 noise_generator_.initialize(settings_, isHolonomic(), name_, parameters_handler_);
59 noise_generator_.shutdown();
64 std::string motion_model_name;
67 auto getParam = parameters_handler_->getParamGetter(name_);
68 auto getParentParam = parameters_handler_->getParamGetter(
"");
69 getParam(s.model_dt,
"model_dt", 0.05f);
70 getParam(s.time_steps,
"time_steps", 56);
71 getParam(s.batch_size,
"batch_size", 1000);
72 getParam(s.iteration_count,
"iteration_count", 1);
73 getParam(s.temperature,
"temperature", 0.3f);
74 getParam(s.gamma,
"gamma", 0.015f);
75 getParam(s.base_constraints.vx_max,
"vx_max", 0.5);
76 getParam(s.base_constraints.vx_min,
"vx_min", -0.35);
77 getParam(s.base_constraints.vy,
"vy_max", 0.5);
78 getParam(s.base_constraints.wz,
"wz_max", 1.9);
79 getParam(s.sampling_std.vx,
"vx_std", 0.2);
80 getParam(s.sampling_std.vy,
"vy_std", 0.2);
81 getParam(s.sampling_std.wz,
"wz_std", 0.4);
82 getParam(s.retry_attempt_limit,
"retry_attempt_limit", 1);
84 getParam(motion_model_name,
"motion_model", std::string(
"DiffDrive"));
86 s.constraints = s.base_constraints;
87 setMotionModel(motion_model_name);
88 parameters_handler_->addPostCallback([
this]() {reset();});
90 double controller_frequency;
91 getParentParam(controller_frequency,
"controller_frequency", 0.0, ParameterType::Static);
92 setOffset(controller_frequency);
97 const double controller_period = 1.0 / controller_frequency;
98 constexpr
double eps = 1e-6;
100 if ((controller_period + eps) < settings_.model_dt) {
103 "Controller period is less then model dt, consider setting it equal");
104 }
else if (abs(controller_period - settings_.model_dt) < eps) {
107 "Controller period is equal to model dt. Control sequence "
109 settings_.shift_control_sequence =
true;
111 throw std::runtime_error(
112 "Controller period more then model dt, set it equal to model dt");
118 state_.reset(settings_.batch_size, settings_.time_steps);
119 control_sequence_.reset(settings_.time_steps);
120 control_history_[0] = {0.0, 0.0, 0.0};
121 control_history_[1] = {0.0, 0.0, 0.0};
122 control_history_[2] = {0.0, 0.0, 0.0};
123 control_history_[3] = {0.0, 0.0, 0.0};
125 settings_.constraints = settings_.base_constraints;
127 costs_ = xt::zeros<float>({settings_.batch_size});
128 generated_trajectories_.reset(settings_.batch_size, settings_.time_steps);
130 noise_generator_.reset(settings_, isHolonomic());
131 RCLCPP_INFO(logger_,
"Optimizer reset");
135 const geometry_msgs::msg::PoseStamped & robot_pose,
136 const geometry_msgs::msg::Twist & robot_speed,
139 prepare(robot_pose, robot_speed, plan, goal_checker);
143 }
while (fallback(critics_data_.fail_flag));
145 utils::savitskyGolayFilter(control_sequence_, control_history_, settings_);
146 auto control = getControlFromSequenceAsTwist(plan.header.stamp);
148 if (settings_.shift_control_sequence) {
149 shiftControlSequence();
157 for (
size_t i = 0; i < settings_.iteration_count; ++i) {
158 generateNoisedTrajectories();
159 critic_manager_.evalTrajectoriesScores(critics_data_);
160 updateControlSequence();
166 static size_t counter = 0;
175 if (++counter > settings_.retry_attempt_limit) {
177 throw std::runtime_error(
"Optimizer fail to compute path");
184 const geometry_msgs::msg::PoseStamped & robot_pose,
185 const geometry_msgs::msg::Twist & robot_speed,
188 state_.pose = robot_pose;
189 state_.speed = robot_speed;
190 path_ = utils::toTensor(plan);
193 critics_data_.fail_flag =
false;
194 critics_data_.goal_checker = goal_checker;
195 critics_data_.motion_model = motion_model_;
196 critics_data_.furthest_reached_path_point.reset();
197 critics_data_.path_pts_valid.reset();
202 using namespace xt::placeholders;
203 control_sequence_.vx = xt::roll(control_sequence_.vx, -1);
204 control_sequence_.wz = xt::roll(control_sequence_.wz, -1);
207 xt::view(control_sequence_.vx, -1) =
208 xt::view(control_sequence_.vx, -2);
210 xt::view(control_sequence_.wz, -1) =
211 xt::view(control_sequence_.wz, -2);
215 control_sequence_.vy = xt::roll(control_sequence_.vy, -1);
216 xt::view(control_sequence_.vy, -1) =
217 xt::view(control_sequence_.vy, -2);
223 noise_generator_.setNoisedControls(state_, control_sequence_);
224 noise_generator_.generateNextNoises();
225 updateStateVelocities(state_);
226 integrateStateVelocities(generated_trajectories_, state_);
233 auto & s = settings_;
236 control_sequence_.vy = xt::clip(control_sequence_.vy, -s.constraints.vy, s.constraints.vy);
239 control_sequence_.vx = xt::clip(control_sequence_.vx, s.constraints.vx_min, s.constraints.vx_max);
240 control_sequence_.wz = xt::clip(control_sequence_.wz, -s.constraints.wz, s.constraints.wz);
242 motion_model_->applyConstraints(control_sequence_);
248 updateInitialStateVelocities(state);
249 propagateStateVelocitiesFromInitials(state);
255 xt::noalias(xt::view(state.vx, xt::all(), 0)) = state.speed.linear.x;
256 xt::noalias(xt::view(state.wz, xt::all(), 0)) = state.speed.angular.z;
259 xt::noalias(xt::view(state.vy, xt::all(), 0)) = state.speed.linear.y;
266 motion_model_->predict(state);
270 xt::xtensor<float, 2> & trajectory,
271 const xt::xtensor<float, 2> & sequence)
const
273 float initial_yaw = tf2::getYaw(state_.pose.pose.orientation);
275 const auto vx = xt::view(sequence, xt::all(), 0);
276 const auto vy = xt::view(sequence, xt::all(), 2);
277 const auto wz = xt::view(sequence, xt::all(), 1);
279 auto traj_x = xt::view(trajectory, xt::all(), 0);
280 auto traj_y = xt::view(trajectory, xt::all(), 1);
281 auto traj_yaws = xt::view(trajectory, xt::all(), 2);
283 xt::noalias(traj_yaws) = xt::cumsum(wz * settings_.model_dt, 0) + initial_yaw;
285 auto && yaw_cos = xt::xtensor<float, 1>::from_shape(traj_yaws.shape());
286 auto && yaw_sin = xt::xtensor<float, 1>::from_shape(traj_yaws.shape());
288 const auto yaw_offseted = xt::view(traj_yaws, xt::range(1, _));
290 xt::noalias(xt::view(yaw_cos, 0)) = cosf(initial_yaw);
291 xt::noalias(xt::view(yaw_sin, 0)) = sinf(initial_yaw);
292 xt::noalias(xt::view(yaw_cos, xt::range(1, _))) = xt::cos(yaw_offseted);
293 xt::noalias(xt::view(yaw_sin, xt::range(1, _))) = xt::sin(yaw_offseted);
295 auto && dx = xt::eval(vx * yaw_cos);
296 auto && dy = xt::eval(vx * yaw_sin);
299 dx = dx - vy * yaw_sin;
300 dy = dy + vy * yaw_cos;
303 xt::noalias(traj_x) = state_.pose.pose.position.x + xt::cumsum(dx * settings_.model_dt, 0);
304 xt::noalias(traj_y) = state_.pose.pose.position.y + xt::cumsum(dy * settings_.model_dt, 0);
311 const float initial_yaw = tf2::getYaw(state.pose.pose.orientation);
313 xt::noalias(trajectories.yaws) =
314 xt::cumsum(state.wz * settings_.model_dt, 1) + initial_yaw;
316 const auto yaws_cutted = xt::view(trajectories.yaws, xt::all(), xt::range(0, -1));
318 auto && yaw_cos = xt::xtensor<float, 2>::from_shape(trajectories.yaws.shape());
319 auto && yaw_sin = xt::xtensor<float, 2>::from_shape(trajectories.yaws.shape());
320 xt::noalias(xt::view(yaw_cos, xt::all(), 0)) = cosf(initial_yaw);
321 xt::noalias(xt::view(yaw_sin, xt::all(), 0)) = sinf(initial_yaw);
322 xt::noalias(xt::view(yaw_cos, xt::all(), xt::range(1, _))) = xt::cos(yaws_cutted);
323 xt::noalias(xt::view(yaw_sin, xt::all(), xt::range(1, _))) = xt::sin(yaws_cutted);
325 auto && dx = xt::eval(state.vx * yaw_cos);
326 auto && dy = xt::eval(state.vx * yaw_sin);
329 dx = dx - state.vy * yaw_sin;
330 dy = dy + state.vy * yaw_cos;
333 xt::noalias(trajectories.x) = state.pose.pose.position.x +
334 xt::cumsum(dx * settings_.model_dt, 1);
335 xt::noalias(trajectories.y) = state.pose.pose.position.y +
336 xt::cumsum(dy * settings_.model_dt, 1);
342 xt::xtensor<float, 2>::from_shape({settings_.time_steps, isHolonomic() ? 3u : 2u});
343 auto && trajectories = xt::xtensor<float, 2>::from_shape({settings_.time_steps, 3});
345 xt::noalias(xt::view(sequence, xt::all(), 0)) = control_sequence_.vx;
346 xt::noalias(xt::view(sequence, xt::all(), 1)) = control_sequence_.wz;
349 xt::noalias(xt::view(sequence, xt::all(), 2)) = control_sequence_.vy;
352 integrateStateVelocities(trajectories, sequence);
353 return std::move(trajectories);
358 auto & s = settings_;
359 auto bounded_noises_vx = state_.cvx - control_sequence_.vx;
360 auto bounded_noises_wz = state_.cwz - control_sequence_.wz;
361 xt::noalias(costs_) +=
362 s.gamma / powf(s.sampling_std.vx, 2) * xt::sum(
363 xt::view(control_sequence_.vx, xt::newaxis(), xt::all()) * bounded_noises_vx, 1, immediate);
364 xt::noalias(costs_) +=
365 s.gamma / powf(s.sampling_std.wz, 2) * xt::sum(
366 xt::view(control_sequence_.wz, xt::newaxis(), xt::all()) * bounded_noises_wz, 1, immediate);
369 auto bounded_noises_vy = state_.cvy - control_sequence_.vy;
370 xt::noalias(costs_) +=
371 s.gamma / powf(s.sampling_std.vy, 2) * xt::sum(
372 xt::view(control_sequence_.vy, xt::newaxis(), xt::all()) * bounded_noises_vy,
376 auto && costs_normalized = costs_ - xt::amin(costs_, immediate);
377 auto && exponents = xt::eval(xt::exp(-1 / settings_.temperature * costs_normalized));
378 auto && softmaxes = xt::eval(exponents / xt::sum(exponents, immediate));
379 auto && softmaxes_extened = xt::eval(xt::view(softmaxes, xt::all(), xt::newaxis()));
381 xt::noalias(control_sequence_.vx) = xt::sum(state_.cvx * softmaxes_extened, 0, immediate);
382 xt::noalias(control_sequence_.wz) = xt::sum(state_.cwz * softmaxes_extened, 0, immediate);
384 xt::noalias(control_sequence_.vy) = xt::sum(state_.cvy * softmaxes_extened, 0, immediate);
387 applyControlSequenceConstraints();
391 const builtin_interfaces::msg::Time & stamp)
393 unsigned int offset = settings_.shift_control_sequence ? 1 : 0;
395 auto vx = control_sequence_.vx(offset);
396 auto wz = control_sequence_.wz(offset);
399 auto vy = control_sequence_.vy(offset);
400 return utils::toTwistStamped(vx, vy, wz, stamp, costmap_ros_->getBaseFrameID());
403 return utils::toTwistStamped(vx, wz, stamp, costmap_ros_->getBaseFrameID());
408 if (model ==
"DiffDrive") {
409 motion_model_ = std::make_shared<DiffDriveMotionModel>();
410 }
else if (model ==
"Omni") {
411 motion_model_ = std::make_shared<OmniMotionModel>();
412 }
else if (model ==
"Ackermann") {
413 motion_model_ = std::make_shared<AckermannMotionModel>(parameters_handler_, name_);
415 throw std::runtime_error(
417 "Model " + model +
" is not valid! Valid options are DiffDrive, Omni, "
424 auto & s = settings_;
425 if (speed_limit == nav2_costmap_2d::NO_SPEED_LIMIT) {
426 s.constraints.vx_max = s.base_constraints.vx_max;
427 s.constraints.vx_min = s.base_constraints.vx_min;
428 s.constraints.vy = s.base_constraints.vy;
429 s.constraints.wz = s.base_constraints.wz;
433 double ratio = speed_limit / 100.0;
434 s.constraints.vx_max = s.base_constraints.vx_max * ratio;
435 s.constraints.vx_min = s.base_constraints.vx_min * ratio;
436 s.constraints.vy = s.base_constraints.vy * ratio;
437 s.constraints.wz = s.base_constraints.wz * ratio;
440 double ratio = speed_limit / s.base_constraints.vx_max;
441 s.constraints.vx_max = s.base_constraints.vx_max * ratio;
442 s.constraints.vx_min = s.base_constraints.vx_min * ratio;
443 s.constraints.vy = s.base_constraints.vy * ratio;
444 s.constraints.wz = s.base_constraints.wz * ratio;
451 return generated_trajectories_;
void updateStateVelocities(models::State &state) const
Update velocities in state.
void setMotionModel(const std::string &model)
Set the motion model of the vehicle platform.
void setOffset(double controller_frequency)
Using control frequence and time step size, determine if trajectory offset should be used to populate...
void integrateStateVelocities(models::Trajectories &trajectories, const models::State &state) const
Rollout velocities in state to poses.
void prepare(const geometry_msgs::msg::PoseStamped &robot_pose, const geometry_msgs::msg::Twist &robot_speed, const nav_msgs::msg::Path &plan, nav2_core::GoalChecker *goal_checker)
Prepare state information on new request for trajectory rollouts.
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, nav2_core::GoalChecker *goal_checker)
Compute control using MPPI algorithm.
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.
xt::xtensor< float, 2 > getOptimizedTrajectory()
Get the optimal trajectory for a cycle for visualization.
void shutdown()
Shutdown for optimizer at process end.
void optimize()
Main function to generate, score, and return trajectories.
void reset()
Reset the optimization problem to initial conditions.
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 commant.
Handles getting parameters and dynamic parmaeter changes.
Function-object for checking whether a goal has been reached.
State information: velocities, controls, poses, speed.