Skip to content

Commit

Permalink
min_turning_r_ getting param fix (#4510)
Browse files Browse the repository at this point in the history
* min_turning_r_ getting param fix

Signed-off-by: Ivan Radionov <[email protected]>

* Update nav2_mppi_controller/include/nav2_mppi_controller/motion_models.hpp

Signed-off-by: Steve Macenski <[email protected]>
Signed-off-by: Ivan Radionov <[email protected]>

---------

Signed-off-by: Ivan Radionov <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Ivan Radionov <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>
  • Loading branch information
3 people committed Aug 23, 2024
1 parent 324bcdd commit 1daf261
Show file tree
Hide file tree
Showing 4 changed files with 5 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -88,9 +88,9 @@ class AckermannMotionModel : public MotionModel
/**
* @brief Constructor for mppi::AckermannMotionModel
*/
explicit AckermannMotionModel(ParametersHandler * param_handler)
explicit AckermannMotionModel(ParametersHandler * param_handler, const std::string & name)
{
auto getParam = param_handler->getParamGetter("AckermannConstraints");
auto getParam = param_handler->getParamGetter(name + ".AckermannConstraints");
getParam(min_turning_r_, "min_turning_r", 0.2);
}

Expand Down
2 changes: 1 addition & 1 deletion nav2_mppi_controller/src/optimizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -410,7 +410,7 @@ void Optimizer::setMotionModel(const std::string & model)
} else if (model == "Omni") {
motion_model_ = std::make_shared<OmniMotionModel>();
} else if (model == "Ackermann") {
motion_model_ = std::make_shared<AckermannMotionModel>(parameters_handler_);
motion_model_ = std::make_shared<AckermannMotionModel>(parameters_handler_, name_);
} else {
throw std::runtime_error(
std::string(
Expand Down
2 changes: 1 addition & 1 deletion nav2_mppi_controller/test/critics_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ TEST(CriticTests, ConstraintsCritic)
// Now with ackermann, all in constraint so no costs to score
state.vx = 0.40 * xt::ones<float>({1000, 30});
state.wz = 1.5 * xt::ones<float>({1000, 30});
data.motion_model = std::make_shared<AckermannMotionModel>(&param_handler);
data.motion_model = std::make_shared<AckermannMotionModel>(&param_handler, node->get_name());
critic.score(data);
EXPECT_NEAR(xt::sum(costs, immediate)(), 0, 1e-6);

Expand Down
2 changes: 1 addition & 1 deletion nav2_mppi_controller/test/motion_model_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ TEST(MotionModelTests, AckermannTest)
auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("my_node");
ParametersHandler param_handler(node);
std::unique_ptr<AckermannMotionModel> model =
std::make_unique<AckermannMotionModel>(&param_handler);
std::make_unique<AckermannMotionModel>(&param_handler, node->get_name());

// Check that predict properly populates the trajectory velocities with the control velocities
state.cvx = 10 * xt::ones<float>({batches, timesteps});
Expand Down

0 comments on commit 1daf261

Please sign in to comment.