Skip to content

Commit 924f167

Browse files
[MPPI Optimization] adding regenerate noise param + adding docs (ros-navigation#3868)
* adding regenerate noise param + adding docs * fix tests * remove unnecessary normalization * Update optimizer.cpp
1 parent 57dd8d4 commit 924f167

File tree

11 files changed

+62
-39
lines changed

11 files changed

+62
-39
lines changed

nav2_mppi_controller/CMakeLists.txt

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,10 @@ add_definitions(-DXTENSOR_USE_XSIMD)
66

77
set(XTENSOR_USE_TBB 0)
88
set(XTENSOR_USE_OPENMP 0)
9+
set(XTENSOR_USE_XSIMD 1)
910

11+
# set(XTENSOR_DEFAULT_LAYOUT column_major) # row_major, column_major
12+
# set(XTENSOR_DEFAULT_TRAVERSAL row_major) # row_major, column_major
1013

1114
find_package(ament_cmake REQUIRED)
1215
find_package(xtensor REQUIRED)
@@ -86,7 +89,7 @@ set(libraries mppi_controller mppi_critics)
8689

8790
foreach(lib IN LISTS libraries)
8891
target_compile_options(${lib} PUBLIC -fconcepts)
89-
target_include_directories(${lib} PUBLIC include ${xsimd_INCLUDE_DIRS} ${OpenMP_INCLUDE_DIRS})
92+
target_include_directories(${lib} PUBLIC include ${xsimd_INCLUDE_DIRS}) # ${OpenMP_INCLUDE_DIRS}
9093
target_link_libraries(${lib} xtensor xtensor::optimize xtensor::use_xsimd)
9194
ament_target_dependencies(${lib} ${dependencies_pkgs})
9295
endforeach()

nav2_mppi_controller/README.md

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,7 @@ This process is then repeated a number of times and returns a converged solution
2929
- Includes fallback mechanisms to handle soft-failures before escalating to recovery behaviors
3030
- High-quality code implementation with Doxygen, high unit test coverage, documentation, and parameter guide
3131
- Easily extensible to support modern research variants of MPPI
32+
- Comes pre-tuned for good out-of-the-box behavior
3233

3334
## Configuration
3435

@@ -52,6 +53,8 @@ This process is then repeated a number of times and returns a converged solution
5253
| gamma | double | Default: 0.015. A trade-off between smoothness (high) and low energy (low). This is a complex parameter that likely won't need to be changed from the default of `0.1` which works well for a broad range of cases. See Section 3D-2 in "Information Theoretic Model Predictive Control: Theory and Applications to Autonomous Driving" for detailed information. |
5354
| visualize | bool | Default: false. Publish visualization of trajectories, which can slow down the controller significantly. Use only for debugging. |
5455
| retry_attempt_limit | int | Default 1. Number of attempts to find feasible trajectory on failure for soft-resets before reporting failure. |
56+
| regenerate_noises | bool | Default false. Whether to regenerate noises each iteration or use single noise distribution computed on initialization and reset. Practically, this is found to work fine since the trajectories are being sampled stochastically from a normal distribution and reduces compute jittering at run-time due to thread wake-ups to resample normal distribution. |
57+
5558
#### Trajectory Visualizer
5659
| Parameter | Type | Definition |
5760
| --------------- | ------ | ----------------------------------------------------------------------------------------------------------- |
@@ -254,6 +257,8 @@ The most common parameters you might want to start off changing are the velocity
254257

255258
If you don't require path following behavior (e.g. just want to follow a goal pose and let the model predictive elements decide the best way to accomplish that), you may easily remove the PathAlign, PathFollow and PathAngle critics.
256259

260+
By default, the controller is tuned and has the capabilities established in the PathAlign/Obstacle critics to generally follow the path closely when no obstacles prevent it, but able to deviate from the path when blocked. See `PathAlignCritic::score()` for details, but it is disabled when the local path is blocked so the obstacle critic takes over in that state.
261+
257262
### Prediction Horizon, Costmap Sizing, and Offsets
258263

259264
As this is a predictive planner, there is some relationship between maximum speed, prediction times, and costmap size that users should keep in mind while tuning for their application. If a controller server costmap is set to 3.0m in size, that means that with the robot in the center, there is 1.5m of information on either side of the robot. When your prediction horizon (time_steps * model_dt) at maximum speed (vx_max) is larger than this, then your robot will be artificially limited in its maximum speeds and behavior by the costmap limitation. For example, if you predict forward 3 seconds (60 steps @ 0.05s per step) at 0.5m/s maximum speed, the **minimum** required costmap radius is 1.5m - or 3m total width.

nav2_mppi_controller/include/nav2_mppi_controller/tools/noise_generator.hpp

Lines changed: 9 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -25,8 +25,9 @@
2525
#include <xtensor/xview.hpp>
2626

2727
#include "nav2_mppi_controller/models/optimizer_settings.hpp"
28-
#include <nav2_mppi_controller/models/control_sequence.hpp>
29-
#include <nav2_mppi_controller/models/state.hpp>
28+
#include "nav2_mppi_controller/tools/parameters_handler.hpp"
29+
#include "nav2_mppi_controller/models/control_sequence.hpp"
30+
#include "nav2_mppi_controller/models/state.hpp"
3031

3132
namespace mppi
3233
{
@@ -47,8 +48,12 @@ class NoiseGenerator
4748
* @brief Initialize noise generator with settings and model types
4849
* @param settings Settings of controller
4950
* @param is_holonomic If base is holonomic
51+
* @param name Namespace for configs
52+
* @param param_handler Get parameters util
5053
*/
51-
void initialize(mppi::models::OptimizerSettings & settings, bool is_holonomic);
54+
void initialize(
55+
mppi::models::OptimizerSettings & settings,
56+
bool is_holonomic, const std::string & name, ParametersHandler * param_handler);
5257

5358
/**
5459
* @brief Shutdown noise generator thread
@@ -99,7 +104,7 @@ class NoiseGenerator
99104
std::thread noise_thread_;
100105
std::condition_variable noise_cond_;
101106
std::mutex noise_lock_;
102-
bool active_{false}, ready_{false};
107+
bool active_{false}, ready_{false}, regenerate_noises_{false};
103108
};
104109

105110
} // namespace mppi

nav2_mppi_controller/src/critics/goal_angle_critic.cpp

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -35,11 +35,7 @@ void GoalAngleCritic::initialize()
3535

3636
void GoalAngleCritic::score(CriticData & data)
3737
{
38-
if (!enabled_) {
39-
return;
40-
}
41-
42-
if (!utils::withinPositionGoalTolerance(
38+
if (!enabled_ || !utils::withinPositionGoalTolerance(
4339
threshold_to_consider_, data.state.pose.pose, data.path))
4440
{
4541
return;

nav2_mppi_controller/src/critics/goal_critic.cpp

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -35,11 +35,7 @@ void GoalCritic::initialize()
3535

3636
void GoalCritic::score(CriticData & data)
3737
{
38-
if (!enabled_) {
39-
return;
40-
}
41-
42-
if (!utils::withinPositionGoalTolerance(
38+
if (!enabled_ || !utils::withinPositionGoalTolerance(
4339
threshold_to_consider_, data.state.pose.pose, data.path))
4440
{
4541
return;

nav2_mppi_controller/src/critics/obstacles_critic.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -152,7 +152,7 @@ void ObstaclesCritic::score(CriticData & data)
152152
}
153153

154154
if (!trajectory_collide) {all_trajectories_collide = false;}
155-
raw_cost[i] = static_cast<float>(trajectory_collide ? collision_cost_ : traj_cost);
155+
raw_cost[i] = trajectory_collide ? collision_cost_ : traj_cost;
156156
}
157157

158158
data.costs += xt::pow(

nav2_mppi_controller/src/critics/prefer_forward_critic.cpp

Lines changed: 3 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -33,12 +33,9 @@ void PreferForwardCritic::initialize()
3333
void PreferForwardCritic::score(CriticData & data)
3434
{
3535
using xt::evaluation_strategy::immediate;
36-
37-
if (!enabled_) {
38-
return;
39-
}
40-
41-
if (utils::withinPositionGoalTolerance(threshold_to_consider_, data.state.pose.pose, data.path)) {
36+
if (!enabled_ ||
37+
utils::withinPositionGoalTolerance(threshold_to_consider_, data.state.pose.pose, data.path))
38+
{
4239
return;
4340
}
4441

nav2_mppi_controller/src/critics/twirling_critic.cpp

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -31,11 +31,9 @@ void TwirlingCritic::initialize()
3131
void TwirlingCritic::score(CriticData & data)
3232
{
3333
using xt::evaluation_strategy::immediate;
34-
if (!enabled_) {
35-
return;
36-
}
37-
38-
if (utils::withinPositionGoalTolerance(data.goal_checker, data.state.pose.pose, data.path)) {
34+
if (!enabled_ ||
35+
utils::withinPositionGoalTolerance(data.goal_checker, data.state.pose.pose, data.path))
36+
{
3937
return;
4038
}
4139

nav2_mppi_controller/src/noise_generator.cpp

Lines changed: 19 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -23,12 +23,22 @@
2323
namespace mppi
2424
{
2525

26-
void NoiseGenerator::initialize(mppi::models::OptimizerSettings & settings, bool is_holonomic)
26+
void NoiseGenerator::initialize(
27+
mppi::models::OptimizerSettings & settings, bool is_holonomic,
28+
const std::string & name, ParametersHandler * param_handler)
2729
{
2830
settings_ = settings;
2931
is_holonomic_ = is_holonomic;
3032
active_ = true;
31-
noise_thread_ = std::thread(std::bind(&NoiseGenerator::noiseThread, this));
33+
34+
auto getParam = param_handler->getParamGetter(name);
35+
getParam(regenerate_noises_, "regenerate_noises", false);
36+
37+
if (regenerate_noises_) {
38+
noise_thread_ = std::thread(std::bind(&NoiseGenerator::noiseThread, this));
39+
} else {
40+
generateNoisedControls();
41+
}
3242
}
3343

3444
void NoiseGenerator::shutdown()
@@ -44,7 +54,7 @@ void NoiseGenerator::shutdown()
4454
void NoiseGenerator::generateNextNoises()
4555
{
4656
// Trigger the thread to run in parallel to this iteration
47-
// to generate the next iteration's noises.
57+
// to generate the next iteration's noises (if applicable).
4858
{
4959
std::unique_lock<std::mutex> guard(noise_lock_);
5060
ready_ = true;
@@ -76,7 +86,12 @@ void NoiseGenerator::reset(mppi::models::OptimizerSettings & settings, bool is_h
7686
xt::noalias(noises_wz_) = xt::zeros<float>({settings_.batch_size, settings_.time_steps});
7787
ready_ = true;
7888
}
79-
noise_cond_.notify_all();
89+
90+
if (regenerate_noises_) {
91+
noise_cond_.notify_all();
92+
} else {
93+
generateNoisedControls();
94+
}
8095
}
8196

8297
void NoiseGenerator::noiseThread()

nav2_mppi_controller/src/optimizer.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include <stdexcept>
2020
#include <string>
2121
#include <vector>
22+
#include <cmath>
2223
#include <xtensor/xmath.hpp>
2324
#include <xtensor/xrandom.hpp>
2425
#include <xtensor/xnoalias.hpp>
@@ -49,7 +50,7 @@ void Optimizer::initialize(
4950
getParams();
5051

5152
critic_manager_.on_configure(parent_, name_, costmap_ros_, parameters_handler_);
52-
noise_generator_.initialize(settings_, isHolonomic());
53+
noise_generator_.initialize(settings_, isHolonomic(), name_, parameters_handler_);
5354

5455
reset();
5556
}
@@ -268,7 +269,7 @@ void Optimizer::integrateStateVelocities(
268269
xt::xtensor<float, 2> & trajectory,
269270
const xt::xtensor<float, 2> & sequence) const
270271
{
271-
double initial_yaw = tf2::getYaw(state_.pose.pose.orientation);
272+
float initial_yaw = tf2::getYaw(state_.pose.pose.orientation);
272273

273274
const auto vx = xt::view(sequence, xt::all(), 0);
274275
const auto vy = xt::view(sequence, xt::all(), 2);
@@ -278,8 +279,7 @@ void Optimizer::integrateStateVelocities(
278279
auto traj_y = xt::view(trajectory, xt::all(), 1);
279280
auto traj_yaws = xt::view(trajectory, xt::all(), 2);
280281

281-
xt::noalias(traj_yaws) =
282-
utils::normalize_angles(xt::cumsum(wz * settings_.model_dt, 0) + initial_yaw);
282+
xt::noalias(traj_yaws) = xt::cumsum(wz * settings_.model_dt, 0 + initial_yaw);
283283

284284
auto && yaw_cos = xt::xtensor<float, 1>::from_shape(traj_yaws.shape());
285285
auto && yaw_sin = xt::xtensor<float, 1>::from_shape(traj_yaws.shape());
@@ -307,10 +307,10 @@ void Optimizer::integrateStateVelocities(
307307
models::Trajectories & trajectories,
308308
const models::State & state) const
309309
{
310-
const double initial_yaw = tf2::getYaw(state.pose.pose.orientation);
310+
const float initial_yaw = tf2::getYaw(state.pose.pose.orientation);
311311

312312
xt::noalias(trajectories.yaws) =
313-
utils::normalize_angles(xt::cumsum(state.wz * settings_.model_dt, 1) + initial_yaw);
313+
xt::cumsum(state.wz * settings_.model_dt, 1) + initial_yaw;
314314

315315
const auto yaws_cutted = xt::view(trajectories.yaws, xt::all(), xt::range(0, -1));
316316

0 commit comments

Comments
 (0)