Skip to content

Commit f66a666

Browse files
authored
Merge pull request #4 from enwaytech/av/mppi_feedback_clean
Use last command to initialize state - fix oscillations & nervous steering
2 parents 2b8f925 + 3e42f4b commit f66a666

File tree

6 files changed

+61
-35
lines changed

6 files changed

+61
-35
lines changed

‎nav2_mppi_controller/include/nav2_mppi_controller/models/trajectories.hpp‎

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,7 @@ struct Trajectories
2929
Eigen::ArrayXXf x;
3030
Eigen::ArrayXXf y;
3131
Eigen::ArrayXXf yaws;
32+
Eigen::ArrayXf costs;
3233

3334
/**
3435
* @brief Reset state data

‎nav2_mppi_controller/include/nav2_mppi_controller/motion_models.hpp‎

Lines changed: 10 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -89,13 +89,15 @@ class MotionModel
8989
0).select(state.vx.col(i - 1) + max_delta_vx,
9090
state.vx.col(i - 1) - min_delta_vx);
9191

92-
state.vx.col(i) = state.cvx.col(i - 1)
92+
state.cvx.col(i - 1) = state.cvx.col(i - 1)
9393
.cwiseMax(lower_bound_vx)
9494
.cwiseMin(upper_bound_vx);
95+
state.vx.col(i) = state.cvx.col(i - 1);
9596

96-
state.wz.col(i) = state.cwz.col(i - 1)
97+
state.cwz.col(i - 1) = state.cwz.col(i - 1)
9798
.cwiseMax(state.wz.col(i - 1) - max_delta_wz)
9899
.cwiseMin(state.wz.col(i - 1) + max_delta_wz);
100+
state.wz.col(i) = state.cwz.col(i - 1);
99101

100102
if (is_holo) {
101103
auto lower_bound_vy = (state.vy.col(i - 1) >
@@ -105,9 +107,10 @@ class MotionModel
105107
0).select(state.vy.col(i - 1) + max_delta_vy,
106108
state.vy.col(i - 1) - min_delta_vy);
107109

108-
state.vy.col(i) = state.cvy.col(i - 1)
110+
state.cvy.col(i - 1) = state.cvy.col(i - 1)
109111
.cwiseMax(lower_bound_vy)
110112
.cwiseMin(upper_bound_vy);
113+
state.vy.col(i) = state.cvy.col(i - 1);
111114
}
112115
}
113116
}
@@ -161,14 +164,10 @@ class AckermannMotionModel : public MotionModel
161164
*/
162165
void applyConstraints(models::ControlSequence & control_sequence) override
163166
{
164-
const auto vx_ptr = control_sequence.vx.data();
165-
auto wz_ptr = control_sequence.wz.data();
166-
int steps = control_sequence.vx.size();
167-
for(int i = 0; i < steps; i++) {
168-
float wz_constrained = fabs(*(vx_ptr + i) / min_turning_r_);
169-
float & wz_curr = *(wz_ptr + i);
170-
wz_curr = utils::clamp(-1 * wz_constrained, wz_constrained, wz_curr);
171-
}
167+
const auto wz_constrained = control_sequence.vx.abs() / min_turning_r_;
168+
control_sequence.wz = control_sequence.wz
169+
.max((-wz_constrained))
170+
.min(wz_constrained);
172171
}
173172

174173
/**

‎nav2_mppi_controller/include/nav2_mppi_controller/optimizer.hpp‎

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -190,13 +190,13 @@ class Optimizer
190190
* @brief Update velocities in state
191191
* @param state fill state with velocities on each step
192192
*/
193-
void updateStateVelocities(models::State & state) const;
193+
void updateStateVelocities(models::State & state);
194194

195195
/**
196196
* @brief Update initial velocity in state
197197
* @param state fill state
198198
*/
199-
void updateInitialStateVelocities(models::State & state) const;
199+
void updateInitialStateVelocities(models::State & state);
200200

201201
/**
202202
* @brief predict velocities in state using model
@@ -280,6 +280,7 @@ class Optimizer
280280
models::Path path_;
281281
geometry_msgs::msg::Pose goal_;
282282
Eigen::ArrayXf costs_;
283+
Eigen::Array3f initial_velocities_;
283284

284285
CriticData critics_data_ = {
285286
state_, generated_trajectories_, path_, goal_,

‎nav2_mppi_controller/src/critics/constraint_critic.cpp‎

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -82,8 +82,12 @@ void ConstraintCritic::score(CriticData & data)
8282
if (acker != nullptr) {
8383
auto & vx = data.state.vx;
8484
auto & wz = data.state.wz;
85-
float min_turning_rad = acker->getMinTurningRadius();
86-
auto out_of_turning_rad_motion = (min_turning_rad - (vx.abs() / wz.abs())).max(0.0f);
85+
const float min_turning_rad = acker->getMinTurningRadius();
86+
87+
const float epsilon = 1e-6f;
88+
auto wz_safe = wz.abs().max(epsilon); // Replace small wz values to avoid division by 0
89+
auto out_of_turning_rad_motion = (min_turning_rad - (vx.abs() / wz_safe)).max(0.0f);
90+
8791
if (power_ > 1u) {
8892
data.costs += ((((vx - max_vel_).max(0.0f) + (min_vel_ - vx).max(0.0f) +
8993
out_of_turning_rad_motion) * data.model_dt).rowwise().sum().eval() *

‎nav2_mppi_controller/src/optimizer.cpp‎

Lines changed: 23 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -210,7 +210,6 @@ std::tuple<geometry_msgs::msg::TwistStamped, Eigen::ArrayXXf> Optimizer::evalCon
210210
}
211211
} while (fallback(critics_data_.fail_flag || !trajectory_valid));
212212

213-
utils::savitskyGolayFilter(control_sequence_, control_history_, settings_);
214213
auto control = getControlFromSequenceAsTwist(plan.header.stamp);
215214

216215
if (settings_.shift_control_sequence) {
@@ -226,6 +225,7 @@ void Optimizer::optimize()
226225
generateNoisedTrajectories();
227226
critic_manager_.evalTrajectoriesScores(critics_data_);
228227
updateControlSequence();
228+
generated_trajectories_.costs = costs_;
229229
}
230230
}
231231

@@ -258,7 +258,7 @@ void Optimizer::prepare(
258258
state_.pose = robot_pose;
259259
state_.speed = robot_speed;
260260
path_ = utils::toTensor(plan);
261-
costs_.setZero();
261+
costs_.setZero(settings_.batch_size);
262262
goal_ = goal;
263263

264264
critics_data_.fail_flag = false;
@@ -299,17 +299,17 @@ void Optimizer::applyControlSequenceConstraints()
299299
float max_delta_vy = s.model_dt * s.constraints.ay_max;
300300
float min_delta_vy = s.model_dt * s.constraints.ay_min;
301301
float max_delta_wz = s.model_dt * s.constraints.az_max;
302-
float vx_last = utils::clamp(s.constraints.vx_min, s.constraints.vx_max, control_sequence_.vx(0));
303-
float wz_last = utils::clamp(-s.constraints.wz, s.constraints.wz, control_sequence_.wz(0));
304-
control_sequence_.vx(0) = vx_last;
305-
control_sequence_.wz(0) = wz_last;
302+
303+
// limit acceleration between current initial_velocities_ and first control in the sequence
304+
float vx_last = initial_velocities_(0);
305+
float wz_last = initial_velocities_(2);
306+
306307
float vy_last = 0;
307308
if (isHolonomic()) {
308-
vy_last = utils::clamp(-s.constraints.vy, s.constraints.vy, control_sequence_.vy(0));
309-
control_sequence_.vy(0) = vy_last;
309+
vy_last = initial_velocities_(1);
310310
}
311311

312-
for (unsigned int i = 1; i != control_sequence_.vx.size(); i++) {
312+
for (unsigned int i = 0; i != control_sequence_.vx.size(); i++) {
313313
float & vx_curr = control_sequence_.vx(i);
314314
vx_curr = utils::clamp(s.constraints.vx_min, s.constraints.vx_max, vx_curr);
315315
if(vx_last > 0) {
@@ -340,21 +340,25 @@ void Optimizer::applyControlSequenceConstraints()
340340
}
341341

342342
void Optimizer::updateStateVelocities(
343-
models::State & state) const
343+
models::State & state)
344344
{
345345
updateInitialStateVelocities(state);
346346
propagateStateVelocitiesFromInitials(state);
347347
}
348348

349349
void Optimizer::updateInitialStateVelocities(
350-
models::State & state) const
350+
models::State & state)
351351
{
352-
state.vx.col(0) = static_cast<float>(state.speed.linear.x);
353-
state.wz.col(0) = static_cast<float>(state.speed.angular.z);
352+
state.vx.col(0) = control_sequence_.vx(0);
353+
state.wz.col(0) = control_sequence_.wz(0);
354354

355355
if (isHolonomic()) {
356-
state.vy.col(0) = static_cast<float>(state.speed.linear.y);
356+
state.vy.col(0) = control_sequence_.vy(0);
357357
}
358+
359+
initial_velocities_(0) = control_sequence_.vx(0);
360+
initial_velocities_(1) = control_sequence_.vy(0);
361+
initial_velocities_(2) = control_sequence_.wz(0);
358362
}
359363

360364
void Optimizer::propagateStateVelocitiesFromInitials(
@@ -514,19 +518,19 @@ void Optimizer::updateControlSequence()
514518
control_sequence_.vy = state_.cvy.transpose().matrix() * softmax_mat;
515519
}
516520

521+
utils::savitskyGolayFilter(control_sequence_, control_history_, settings_);
522+
517523
applyControlSequenceConstraints();
518524
}
519525

520526
geometry_msgs::msg::TwistStamped Optimizer::getControlFromSequenceAsTwist(
521527
const builtin_interfaces::msg::Time & stamp)
522528
{
523-
unsigned int offset = settings_.shift_control_sequence ? 1 : 0;
524-
525-
auto vx = control_sequence_.vx(offset);
526-
auto wz = control_sequence_.wz(offset);
529+
auto vx = control_sequence_.vx(0);
530+
auto wz = control_sequence_.wz(0);
527531

528532
if (isHolonomic()) {
529-
auto vy = control_sequence_.vy(offset);
533+
auto vy = control_sequence_.vy(0);
530534
return utils::toTwistStamped(vx, vy, wz, stamp, costmap_ros_->getBaseFrameID());
531535
}
532536

‎nav2_mppi_controller/src/trajectory_visualizer.cpp‎

Lines changed: 18 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -111,6 +111,23 @@ void TrajectoryVisualizer::add(
111111
const float shape_1 = static_cast<float>(n_cols);
112112
points_->markers.reserve(floor(n_rows / trajectory_step_) * floor(n_cols * time_step_));
113113

114+
std::vector<std::pair<size_t, float>> sorted_costs;
115+
sorted_costs.reserve(std::ceil(n_rows / trajectory_step_));
116+
117+
for (size_t i = 0; i < n_rows; i += trajectory_step_) {
118+
sorted_costs.emplace_back(i, trajectories.costs(i));
119+
}
120+
std::sort(sorted_costs.begin(), sorted_costs.end(),
121+
[](const auto & a, const auto & b) { return a.second < b.second; });
122+
123+
const float step = 1.0f / static_cast<float>(sorted_costs.size());
124+
float color_component = 1.0f;
125+
std::map<size_t, float> cost_color_map;
126+
for (const auto & pair : sorted_costs) {
127+
cost_color_map[pair.first] = color_component;
128+
color_component -= step;
129+
}
130+
114131
for (size_t i = 0; i < n_rows; i += trajectory_step_) {
115132
for (size_t j = 0; j < n_cols; j += time_step_) {
116133
const float j_flt = static_cast<float>(j);
@@ -119,7 +136,7 @@ void TrajectoryVisualizer::add(
119136

120137
auto pose = utils::createPose(trajectories.x(i, j), trajectories.y(i, j), 0.03);
121138
auto scale = utils::createScale(0.03, 0.03, 0.03);
122-
auto color = utils::createColor(0, green_component, blue_component, 1);
139+
auto color = utils::createColor(cost_color_map[i], green_component, blue_component, 1);
123140
auto marker = utils::createMarker(
124141
marker_id_++, pose, scale, color, frame_id_, marker_namespace);
125142

0 commit comments

Comments
 (0)