You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
BtActionServer logs the following warning message, even when the error_code_names parameter is set.
Error_code parameters were not set. Using default values of: follow_path_error_code
[component_container_isolated-6] compute_path_error_code
[component_container_isolated-6] Make sure these match your BT and there are not other sources of error codes you want reported to your application
Additional information
In nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp the warning logging happens because the parameter is not declared.
if (!node->has_parameter("error_code_names")) {
std::string error_codes_str;
for (const auto & error_code : error_code_names) {
error_codes_str += error_code + "\n";
}
RCLCPP_WARN_STREAM(
logger_, "Error_code parameters were not set. Using default values of: "
<< error_codes_str
<< "Make sure these match your BT and there are not other sources of error codes you want "
"reported to your application");
node->declare_parameter("error_code_names", error_code_names);
}
A workaround could be to declare the variable without default value first and check if it is set:
if (!node->has_parameter("error_code_names")) {
const rclcpp::ParameterValue value = node->declare_parameter(
"error_code_names",
rclcpp::PARAMETER_STRING_ARRAY);
if (value.get_type() == rclcpp::PARAMETER_NOT_SET) {
node->set_parameter(rclcpp::Parameter("error_code_names", error_code_names));
std::string error_codes_str;
for (const auto & error_code : error_code_names) {
error_codes_str += error_code + "\n";
}
RCLCPP_WARN_STREAM(
logger_, "Error_code parameters were not set. Using default values of: "
<< error_codes_str
<< "Make sure these match your BT and there are not other sources of error codes you want "
"reported to your application");
}
}
The text was updated successfully, but these errors were encountered:
I agree looking at this, this was not done correctly. It should declare them without defaults. If we get it and it throws because no value is set, then run the log warning. Else, use the values set.
I was about to report the same. I think all the has_parameter usage should be rethink if there is no chance that a declare_parameter was used before (it will always fail).
(to be fair, the rclpcpp param API is still quite confusing)
Bug report
Required Info:
Steps to reproduce issue
Simply run the getting started's bringup code:
ros2 launch nav2_bringup tb3_simulation_launch.py headless:=False
Expected behavior
There should be no warning message.
Actual behavior
BtActionServer logs the following warning message, even when the
error_code_names
parameter is set.Additional information
In
nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp
the warning logging happens because the parameter is not declared.A workaround could be to declare the variable without default value first and check if it is set:
The text was updated successfully, but these errors were encountered: