Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

mppi parameters_handler: Improve verbose handling (#4704) #4711

Open
wants to merge 3 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -210,7 +210,16 @@
setParam<ParamT>(setting, name, node);

if (param_type == ParameterType::Dynamic) {
if (verbose_) {
RCLCPP_INFO(node->get_logger(), "setDynamicParamCallback for %s", name.c_str());

Check warning on line 214 in nav2_mppi_controller/include/nav2_mppi_controller/tools/parameters_handler.hpp

View check run for this annotation

Codecov / codecov/patch

nav2_mppi_controller/include/nav2_mppi_controller/tools/parameters_handler.hpp#L214

Added line #L214 was not covered by tests
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
}
setDynamicParamCallback(setting, name);
} else {
if (verbose_) {
RCLCPP_DEBUG(

Check warning on line 219 in nav2_mppi_controller/include/nav2_mppi_controller/tools/parameters_handler.hpp

View check run for this annotation

Codecov / codecov/patch

nav2_mppi_controller/include/nav2_mppi_controller/tools/parameters_handler.hpp#L219

Added line #L219 was not covered by tests
node->get_logger(), "ParameterType::Static therefore no setDynamicParamCallback for %s",
name.c_str());
}
}
}

Expand Down
19 changes: 14 additions & 5 deletions nav2_mppi_controller/src/parameters_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,13 +38,15 @@ ParametersHandler::~ParametersHandler()
void ParametersHandler::start()
{
auto node = node_.lock();

// Register the special case "verbose" parameter before registering dynamicParamsCallback
auto get_param = getParamGetter(node_name_);
get_param(verbose_, "verbose", false);

on_set_param_handler_ = node->add_on_set_parameters_callback(
std::bind(
&ParametersHandler::dynamicParamsCallback, this,
std::placeholders::_1));

auto get_param = getParamGetter(node_name_);
get_param(verbose_, "verbose", false);
}

rcl_interfaces::msg::SetParametersResult
Expand All @@ -53,6 +55,7 @@ ParametersHandler::dynamicParamsCallback(
{
rcl_interfaces::msg::SetParametersResult result;
std::lock_guard<std::mutex> lock(parameters_change_mutex_);
bool success;
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved

for (auto & pre_cb : pre_callbacks_) {
pre_cb();
Expand All @@ -66,15 +69,21 @@ ParametersHandler::dynamicParamsCallback(
{
callback->second(param);
} else {
RCLCPP_WARN(logger_, "Parameter %s not found", param_name.c_str());
if (verbose_) {
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
// Expected if static parameter, ie one with no registered callback is attempted
// to be changed
RCLCPP_WARN(logger_, "Parameter callback func for '%s' not found", param_name.c_str());
}
// success = true; // Decision ??? Still return true to avoid exception ???
success = false;
}
}

for (auto & post_cb : post_callbacks_) {
post_cb();
}

result.successful = true;
result.successful = success;
return result;
}

Expand Down
45 changes: 43 additions & 2 deletions nav2_mppi_controller/test/parameter_handler_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -168,8 +168,49 @@ TEST(ParameterHandlerTest, DynamicAndStaticParametersTest)
node->get_node_services_interface());

auto results = rec_param->set_parameters_atomically(
{rclcpp::Parameter("dynamic_int", 10),
rclcpp::Parameter("static_int", 10)});
{
rclcpp::Parameter("my_node.verbose", true),
rclcpp::Parameter("dynamic_int", 10),
rclcpp::Parameter("static_int", 10)
});

rclcpp::spin_until_future_complete(
node->get_node_base_interface(),
results);

// Now, only param1 should change, param 2 should be the same
EXPECT_EQ(p1, 10);
EXPECT_EQ(p2, 7);
}

TEST(ParameterHandlerTest, DynamicAndStaticParametersNotVerboseTest)
{
auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("my_node");
node->declare_parameter("dynamic_int", rclcpp::ParameterValue(7));
node->declare_parameter("static_int", rclcpp::ParameterValue(7));
ParametersHandlerWrapper handler(node);
handler.start();

// Get parameters and check they have initial values
auto getParamer = handler.getParamGetter("");
int p1 = 0, p2 = 0;
getParamer(p1, "dynamic_int", 0, ParameterType::Dynamic);
getParamer(p2, "static_int", 0, ParameterType::Static);
EXPECT_EQ(p1, 7);
EXPECT_EQ(p2, 7);

// Now change them both via dynamic parameters
auto rec_param = std::make_shared<rclcpp::AsyncParametersClient>(
node->get_node_base_interface(), node->get_node_topics_interface(),
node->get_node_graph_interface(),
node->get_node_services_interface());

auto results = rec_param->set_parameters_atomically(
{
// Don't set default param rclcpp::Parameter("my_node.verbose", false),
rclcpp::Parameter("dynamic_int", 10),
rclcpp::Parameter("static_int", 10)
});

rclcpp::spin_until_future_complete(
node->get_node_base_interface(),
Expand Down
Loading