Skip to content

Commit aaedb05

Browse files
committed
Scale cost critic's weight when dynamically updated
Signed-off-by: pepisg <[email protected]>
1 parent 0be2f25 commit aaedb05

File tree

1 file changed

+6
-0
lines changed

1 file changed

+6
-0
lines changed

nav2_mppi_controller/src/critics/cost_critic.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,12 @@ void CostCritic::initialize()
3434
// Normalized by cost value to put in same regime as other weights
3535
weight_ /= 254.0f;
3636

37+
// Normalize weight when parameter is changed dynamically as well
38+
auto weightDynamicCb = [&](const rclcpp::Parameter & weight) {
39+
weight_ = weight.as_double() / 254.0f;
40+
};
41+
parameters_handler_->addDynamicParamCallback(name_ + ".cost_weight", weightDynamicCb);
42+
3743
collision_checker_.setCostmap(costmap_);
3844
possible_collision_cost_ = findCircumscribedCost(costmap_ros_);
3945

0 commit comments

Comments
 (0)