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

Error_code parameters were not set warning message #3626

Closed
RBT22 opened this issue Jun 14, 2023 · 3 comments
Closed

Error_code parameters were not set warning message #3626

RBT22 opened this issue Jun 14, 2023 · 3 comments

Comments

@RBT22
Copy link
Contributor

RBT22 commented Jun 14, 2023

Bug report

Required Info:

  • Operating System:
    • Ubuntu 22.04
  • ROS2 Version:
    • Rolling
  • DDS implementation:
    • CycloneDDS

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.

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");
    }
}
@SteveMacenski
Copy link
Member

@jwallace42 this one's all you 😄

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.

@doisyg
Copy link
Contributor

doisyg commented Jun 15, 2023

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)

@SteveMacenski
Copy link
Member

All other uses look correct to me other than this one feature!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

No branches or pull requests

3 participants