Skip to content

Commit 2900652

Browse files
aosmwJakubach
authored andcommitted
mppi parameters_handler: Improve verbose handling (ros-navigation#4704) (ros-navigation#4711)
* mppi parameters_handler: Improve verbose handling (ros-navigation#4704) The "verbose" parameter of the parameters_handler is a special case that needs registration before the dynamic parameter handler callback is registered. In verbose mode make the parameter handler info/warn/debug messages more expressive. Signed-off-by: Mike Wake <[email protected]> * Address review comments. (ros-navigation#4704) * remove comments. * Use RCLCPP_DEBUG instead of INFO for low level messages. * Add test for trying to access parameters that are not declared. Signed-off-by: Mike Wake <[email protected]> * mppi parameters_handler: Improve static/dynamic/not defined logging (ros-navigation#4704) Attempts to change undefined parameters will not be successful and will log an error. Attempts to change static parameters will be ignored, a debug message is logged if a change in parameters is attempted. Signed-off-by: Mike Wake <[email protected]> * mppi parameters_handler: populate SetParametersResult (ros-navigation#4704) Provide a mechanism to populate an rcl_interfaces::msg::SetParametersResult with the reasons for unsuccessful parameter setting, so that it may be propogated back to a set parameter client. The mechanism provides feedback when attempting to set undefined parameters, static parameters and could be used to validate dynamic parameters and provide a reason for rejection. NOTE: This changes public interface of ParametersHandler class. s/setDynamicParamCallback/setParamCallback s/addDynamicParamCallback/addParamCallback which takes a callback function that is able to populate a rcl_interfaces::msg::SetParametersResult. In order to indicate an unsuccessful parameter change and the reason, callback functions should append a "\n" to the reason before appending to if it is not empty. Signed-off-by: Mike Wake <[email protected]> * mppi parameters_handler: fix reason handling and improve tests Signed-off-by: Mike Wake <[email protected]> --------- Signed-off-by: Mike Wake <[email protected]> Signed-off-by: Jakubach <[email protected]>
1 parent 743a788 commit 2900652

File tree

4 files changed

+182
-34
lines changed

4 files changed

+182
-34
lines changed

nav2_mppi_controller/include/nav2_mppi_controller/tools/parameters_handler.hpp

Lines changed: 38 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -36,12 +36,13 @@ enum class ParameterType { Dynamic, Static };
3636

3737
/**
3838
* @class mppi::ParametersHandler
39-
* @brief Handles getting parameters and dynamic parmaeter changes
39+
* @brief Handles getting parameters and dynamic parameter changes
4040
*/
4141
class ParametersHandler
4242
{
4343
public:
44-
using get_param_func_t = void (const rclcpp::Parameter & param);
44+
using get_param_func_t = void (const rclcpp::Parameter & param,
45+
rcl_interfaces::msg::SetParametersResult & result);
4546
using post_callback_t = void ();
4647
using pre_callback_t = void ();
4748

@@ -100,9 +101,11 @@ class ParametersHandler
100101
* @brief Set a parameter to a dynamic parameter callback
101102
* @param setting Parameter
102103
* @param name Name of parameter
104+
* @param param_type Type of parameter (dynamic or static)
103105
*/
104106
template<typename T>
105-
void setDynamicParamCallback(T & setting, const std::string & name);
107+
void setParamCallback(
108+
T & setting, const std::string & name, ParameterType param_type = ParameterType::Dynamic);
106109

107110
/**
108111
* @brief Get mutex lock for changing parameters
@@ -114,12 +117,20 @@ class ParametersHandler
114117
}
115118

116119
/**
117-
* @brief Set a parameter to a dynamic parameter callback
120+
* @brief register a function to be called when setting a parameter
121+
*
122+
* The callback funciton is expected to behave as follows.
123+
* Successful parameter changes should not interfere with
124+
* the result parameter.
125+
* Unsuccessful parameter changes should set the result.successful = false
126+
* The result.reason should have "\n" appended if not empty before
127+
* appending the reason that setting THIS parameter has failed.
128+
*
118129
* @param name Name of parameter
119130
* @param callback Parameter callback
120131
*/
121132
template<typename T>
122-
void addDynamicParamCallback(const std::string & name, T && callback);
133+
void addParamCallback(const std::string & name, T && callback);
123134

124135
protected:
125136
/**
@@ -160,8 +171,7 @@ class ParametersHandler
160171

161172
bool verbose_{false};
162173

163-
std::unordered_map<std::string, std::function<get_param_func_t>>
164-
get_param_callbacks_;
174+
std::unordered_map<std::string, std::function<get_param_func_t>> get_param_callbacks_;
165175

166176
std::vector<std::function<pre_callback_t>> pre_callbacks_;
167177
std::vector<std::function<post_callback_t>> post_callbacks_;
@@ -179,7 +189,7 @@ inline auto ParametersHandler::getParamGetter(const std::string & ns)
179189
}
180190

181191
template<typename T>
182-
void ParametersHandler::addDynamicParamCallback(const std::string & name, T && callback)
192+
void ParametersHandler::addParamCallback(const std::string & name, T && callback)
183193
{
184194
get_param_callbacks_[name] = callback;
185195
}
@@ -208,10 +218,7 @@ void ParametersHandler::getParam(
208218
node, name, rclcpp::ParameterValue(default_value));
209219

210220
setParam<ParamT>(setting, name, node);
211-
212-
if (param_type == ParameterType::Dynamic) {
213-
setDynamicParamCallback(setting, name);
214-
}
221+
setParamCallback(setting, name, param_type);
215222
}
216223

217224
template<typename ParamT, typename SettingT, typename NodeT>
@@ -224,24 +231,37 @@ void ParametersHandler::setParam(
224231
}
225232

226233
template<typename T>
227-
void ParametersHandler::setDynamicParamCallback(T & setting, const std::string & name)
234+
void ParametersHandler::setParamCallback(
235+
T & setting, const std::string & name, ParameterType param_type)
228236
{
229237
if (get_param_callbacks_.find(name) != get_param_callbacks_.end()) {
230238
return;
231239
}
232240

233-
auto callback = [this, &setting, name](const rclcpp::Parameter & param) {
241+
auto dynamic_callback =
242+
[this, &setting, name](
243+
const rclcpp::Parameter & param, rcl_interfaces::msg::SetParametersResult & /*result*/) {
234244
setting = as<T>(param);
235-
236245
if (verbose_) {
237246
RCLCPP_INFO(logger_, "Dynamic parameter changed: %s", std::to_string(param).c_str());
238247
}
239248
};
240249

241-
addDynamicParamCallback(name, callback);
250+
auto static_callback =
251+
[this, &setting, name](
252+
const rclcpp::Parameter & param, rcl_interfaces::msg::SetParametersResult & result) {
253+
std::string reason = "Rejected change to static parameter: " + std::to_string(param);
254+
result.successful = false;
255+
if (!result.reason.empty()) {
256+
result.reason += "\n";
257+
}
258+
result.reason += reason;
259+
};
242260

243-
if (verbose_) {
244-
RCLCPP_INFO(logger_, "Dynamic Parameter added %s", name.c_str());
261+
if (param_type == ParameterType::Dynamic) {
262+
addParamCallback(name, dynamic_callback);
263+
} else {
264+
addParamCallback(name, static_callback);
245265
}
246266
}
247267

nav2_mppi_controller/src/critics/cost_critic.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -35,10 +35,11 @@ void CostCritic::initialize()
3535
weight_ /= 254.0f;
3636

3737
// Normalize weight when parameter is changed dynamically as well
38-
auto weightDynamicCb = [&](const rclcpp::Parameter & weight) {
38+
auto weightDynamicCb = [&](
39+
const rclcpp::Parameter & weight, rcl_interfaces::msg::SetParametersResult & /*result*/) {
3940
weight_ = weight.as_double() / 254.0f;
4041
};
41-
parameters_handler_->addDynamicParamCallback(name_ + ".cost_weight", weightDynamicCb);
42+
parameters_handler_->addParamCallback(name_ + ".cost_weight", weightDynamicCb);
4243

4344
collision_checker_.setCostmap(costmap_);
4445
possible_collision_cost_ = findCircumscribedCost(costmap_ros_);

nav2_mppi_controller/src/parameters_handler.cpp

Lines changed: 16 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -38,20 +38,24 @@ ParametersHandler::~ParametersHandler()
3838
void ParametersHandler::start()
3939
{
4040
auto node = node_.lock();
41+
42+
auto get_param = getParamGetter(node_name_);
43+
get_param(verbose_, "verbose", false);
44+
4145
on_set_param_handler_ = node->add_on_set_parameters_callback(
4246
std::bind(
4347
&ParametersHandler::dynamicParamsCallback, this,
4448
std::placeholders::_1));
45-
46-
auto get_param = getParamGetter(node_name_);
47-
get_param(verbose_, "verbose", false);
4849
}
4950

5051
rcl_interfaces::msg::SetParametersResult
5152
ParametersHandler::dynamicParamsCallback(
5253
std::vector<rclcpp::Parameter> parameters)
5354
{
5455
rcl_interfaces::msg::SetParametersResult result;
56+
result.successful = true;
57+
result.reason = "";
58+
5559
std::lock_guard<std::mutex> lock(parameters_change_mutex_);
5660

5761
for (auto & pre_cb : pre_callbacks_) {
@@ -64,17 +68,23 @@ ParametersHandler::dynamicParamsCallback(
6468
if (auto callback = get_param_callbacks_.find(param_name);
6569
callback != get_param_callbacks_.end())
6670
{
67-
callback->second(param);
71+
callback->second(param, result);
6872
} else {
69-
RCLCPP_WARN(logger_, "Parameter %s not found", param_name.c_str());
73+
result.successful = false;
74+
if (!result.reason.empty()) {
75+
result.reason += "\n";
76+
}
77+
result.reason += "get_param_callback func for '" + param_name + "' not found.\n";
7078
}
7179
}
7280

7381
for (auto & post_cb : post_callbacks_) {
7482
post_cb();
7583
}
7684

77-
result.successful = true;
85+
if (!result.successful) {
86+
RCLCPP_ERROR(logger_, result.reason.c_str());
87+
}
7888
return result;
7989
}
8090

nav2_mppi_controller/test/parameter_handler_test.cpp

Lines changed: 125 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -93,7 +93,8 @@ TEST(ParameterHandlerTest, PrePostDynamicCallbackTest)
9393
post_triggered = true;
9494
};
9595

96-
auto dynamicCb = [&](const rclcpp::Parameter & /*param*/) {
96+
auto dynamicCb = [&](const rclcpp::Parameter & /*param*/,
97+
rcl_interfaces::msg::SetParametersResult & /*result*/) {
9798
dynamic_triggered = true;
9899
};
99100

@@ -104,8 +105,8 @@ TEST(ParameterHandlerTest, PrePostDynamicCallbackTest)
104105
ParametersHandlerWrapper a;
105106
a.addPreCallback(preCb);
106107
a.addPostCallback(postCb);
107-
a.addDynamicParamCallback("use_sim_time", dynamicCb);
108-
a.setDynamicParamCallback(val, "blah_blah");
108+
a.addParamCallback("use_sim_time", dynamicCb);
109+
a.setParamCallback(val, "blah_blah");
109110

110111
// Dynamic callback should not trigger, wrong parameter, but val should be updated
111112
a.dynamicParamsCallback(std::vector<rclcpp::Parameter>{random_param});
@@ -146,6 +147,52 @@ TEST(ParameterHandlerTest, GetSystemParamsTest)
146147
}
147148

148149
TEST(ParameterHandlerTest, DynamicAndStaticParametersTest)
150+
{
151+
auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("my_node");
152+
153+
node->declare_parameter("dynamic_int", rclcpp::ParameterValue(7));
154+
node->declare_parameter("static_int", rclcpp::ParameterValue(7));
155+
ParametersHandlerWrapper handler(node);
156+
handler.start();
157+
158+
// Get parameters and check they have initial values
159+
auto getParamer = handler.getParamGetter("");
160+
int p1 = 0, p2 = 0;
161+
getParamer(p1, "dynamic_int", 0, ParameterType::Dynamic);
162+
getParamer(p2, "static_int", 0, ParameterType::Static);
163+
EXPECT_EQ(p1, 7);
164+
EXPECT_EQ(p2, 7);
165+
166+
// Now change them both via dynamic parameters
167+
auto rec_param = std::make_shared<rclcpp::AsyncParametersClient>(
168+
node->get_node_base_interface(), node->get_node_topics_interface(),
169+
node->get_node_graph_interface(),
170+
node->get_node_services_interface());
171+
172+
std::shared_future<rcl_interfaces::msg::SetParametersResult> result_future =
173+
rec_param->set_parameters_atomically({
174+
rclcpp::Parameter("my_node.verbose", true),
175+
rclcpp::Parameter("dynamic_int", 10),
176+
rclcpp::Parameter("static_int", 10)
177+
});
178+
179+
auto rc = rclcpp::spin_until_future_complete(
180+
node->get_node_base_interface(),
181+
result_future);
182+
ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, rc);
183+
184+
auto result = result_future.get();
185+
EXPECT_EQ(result.successful, false);
186+
EXPECT_FALSE(result.reason.empty());
187+
EXPECT_EQ(result.reason, std::string("Rejected change to static parameter: ") +
188+
"{\"name\": \"static_int\", \"type\": \"integer\", \"value\": \"10\"}");
189+
190+
// Now, only param1 should change, param 2 should be the same
191+
EXPECT_EQ(p1, 10);
192+
EXPECT_EQ(p2, 7);
193+
}
194+
195+
TEST(ParameterHandlerTest, DynamicAndStaticParametersNotVerboseTest)
149196
{
150197
auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("my_node");
151198
node->declare_parameter("dynamic_int", rclcpp::ParameterValue(7));
@@ -167,15 +214,85 @@ TEST(ParameterHandlerTest, DynamicAndStaticParametersTest)
167214
node->get_node_graph_interface(),
168215
node->get_node_services_interface());
169216

170-
auto results = rec_param->set_parameters_atomically(
171-
{rclcpp::Parameter("dynamic_int", 10),
172-
rclcpp::Parameter("static_int", 10)});
217+
std::shared_future<rcl_interfaces::msg::SetParametersResult> result_future =
218+
rec_param->set_parameters_atomically({
219+
// Don't set default param rclcpp::Parameter("my_node.verbose", false),
220+
rclcpp::Parameter("dynamic_int", 10),
221+
rclcpp::Parameter("static_int", 10)
222+
});
173223

174-
rclcpp::spin_until_future_complete(
224+
auto rc = rclcpp::spin_until_future_complete(
175225
node->get_node_base_interface(),
176-
results);
226+
result_future);
227+
ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, rc);
228+
229+
auto result = result_future.get();
230+
EXPECT_EQ(result.successful, false);
231+
EXPECT_FALSE(result.reason.empty());
232+
EXPECT_EQ(result.reason, std::string("Rejected change to static parameter: ") +
233+
"{\"name\": \"static_int\", \"type\": \"integer\", \"value\": \"10\"}");
177234

178235
// Now, only param1 should change, param 2 should be the same
179236
EXPECT_EQ(p1, 10);
180237
EXPECT_EQ(p2, 7);
181238
}
239+
240+
TEST(ParameterHandlerTest, DynamicAndStaticParametersNotDeclaredTest)
241+
{
242+
auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("my_node");
243+
244+
node->declare_parameter("dynamic_int", rclcpp::ParameterValue(7));
245+
node->declare_parameter("static_int", rclcpp::ParameterValue(7));
246+
ParametersHandlerWrapper handler(node);
247+
handler.start();
248+
249+
// Set verbose true to get more information about bad parameter usage
250+
auto getParamer = handler.getParamGetter("");
251+
auto rec_param = std::make_shared<rclcpp::AsyncParametersClient>(
252+
node->get_node_base_interface(), node->get_node_topics_interface(),
253+
node->get_node_graph_interface(),
254+
node->get_node_services_interface());
255+
256+
std::shared_future<rcl_interfaces::msg::SetParametersResult>
257+
result_future = rec_param->set_parameters_atomically({
258+
rclcpp::Parameter("my_node.verbose", true),
259+
});
260+
261+
auto rc = rclcpp::spin_until_future_complete(
262+
node->get_node_base_interface(),
263+
result_future);
264+
ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, rc);
265+
266+
auto result = result_future.get();
267+
EXPECT_EQ(result.successful, true);
268+
EXPECT_TRUE(result.reason.empty());
269+
270+
// Try to access some parameters that have not been declared
271+
int p1 = 0, p2 = 0;
272+
EXPECT_THROW(getParamer(p1, "not_declared", 8, ParameterType::Dynamic),
273+
rclcpp::exceptions::InvalidParameterValueException);
274+
EXPECT_THROW(getParamer(p2, "not_declared2", 9, ParameterType::Static),
275+
rclcpp::exceptions::InvalidParameterValueException);
276+
277+
// Try to set some parameters that have not been declared via the service client
278+
result_future = rec_param->set_parameters_atomically({
279+
rclcpp::Parameter("static_int", 10),
280+
rclcpp::Parameter("not_declared", true),
281+
rclcpp::Parameter("not_declared2", true),
282+
});
283+
284+
rc = rclcpp::spin_until_future_complete(
285+
node->get_node_base_interface(),
286+
result_future);
287+
ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, rc);
288+
289+
result = result_future.get();
290+
EXPECT_EQ(result.successful, false);
291+
EXPECT_FALSE(result.reason.empty());
292+
// The ParameterNotDeclaredException handler in rclcpp/parameter_service.cpp
293+
// overrides any other reasons and does not provide details to the service client.
294+
EXPECT_EQ(result.reason, std::string("One or more parameters were not declared before setting"));
295+
296+
EXPECT_EQ(p1, 0);
297+
EXPECT_EQ(p2, 0);
298+
}

0 commit comments

Comments
 (0)