ros-navigation / navigation2

ROS 2 Navigation Framework and System
https://nav2.org/
Other
2.52k stars 1.28k forks source link

Nav2 build fails due to deprecated declare_parameter #2220

Closed AlexeyMerzlyakov closed 3 years ago

AlexeyMerzlyakov commented 3 years ago

Bug report

Navigation2 stack build fails on latest ros2 rolling release with following message:

--- stderr: nav2_lifecycle_manager                                                                              
/home/leha/navigation2_ws/src/navigation2/nav2_lifecycle_manager/src/lifecycle_manager.cpp: In constructor ‘nav2_lifecycle_manager::LifecycleManager::LifecycleManager()’:
/home/leha/navigation2_ws/src/navigation2/nav2_lifecycle_manager/src/lifecycle_manager.cpp:41:33: error: ‘const rclcpp::ParameterValue& rclcpp::Node::declare_parameter(const string&)’ is deprecated: declare_parameter() with only a name is deprecated and will be deleted in the future.\nIf you want to declare a parameter that won't change type without a default value use:\n`node->declare_parameter<ParameterT>(name)`, where e.g. ParameterT=int64_t.\n\nIf you want to declare a parameter that can dynamically change type use:\n```\nrcl_interfaces::msg::ParameterDescriptor descriptor;\ndescriptor.dynamic_typing = true;\nnode->declare_parameter(name, rclcpp::ParameterValue{}, descriptor);\n``` [-Werror=deprecated-declarations]
   41 |   declare_parameter("node_names");
      |                                 ^
In file included from /home/leha/ros2_foxy/install/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp:28,
                 from /home/leha/ros2_foxy/install/rclcpp/include/rclcpp/executors.hpp:22,
                 from /home/leha/ros2_foxy/install/rclcpp/include/rclcpp/rclcpp.hpp:146,
                 from /home/leha/navigation2_ws/install/nav2_util/include/nav2_util/node_utils.hpp:19,
                 from /home/leha/navigation2_ws/install/nav2_util/include/nav2_util/service_client.hpp:20,
                 from /home/leha/navigation2_ws/install/nav2_util/include/nav2_util/lifecycle_service_client.hpp:24,
                 from /home/leha/navigation2_ws/src/navigation2/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp:24,
                 from /home/leha/navigation2_ws/src/navigation2/nav2_lifecycle_manager/src/lifecycle_manager.cpp:15:
/home/leha/ros2_foxy/install/rclcpp/include/rclcpp/node.hpp:359:3: note: declared here
  359 |   declare_parameter(const std::string & name);
      |   ^~~~~~~~~~~~~~~~~
cc1plus: all warnings being treated as errors
make[2]: *** [CMakeFiles/nav2_lifecycle_manager_core.dir/build.make:63: CMakeFiles/nav2_lifecycle_manager_core.dir/src/lifecycle_manager.cpp.o] Error 1
make[1]: *** [CMakeFiles/Makefile2:150: CMakeFiles/nav2_lifecycle_manager_core.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
make: *** [Makefile:141: all] Error 2
---
Failed   <<< nav2_lifecycle_manager [ Exited with code 2 ]

Required Info:

Steps to reproduce issue

  1. Build latest ROS2 rolling release:

    $ mkdir -p ~/ros2_foxy/src
    $ cd ~/ros2_foxy
    $ wget https://raw.githubusercontent.com/ros2/ros2/master/ros2.repos
    $ vcs import src < ros2.repos
    (rosdep update & install)
    $ colcon build --symlink-install
  2. Build nav2 dependencies:

    $ mkdir -p ~/nav2_depend_ws/src
    $ cd ~/nav2_depend_ws
    $ wget https://raw.githubusercontent.com/ros-planning/navigation2/main/tools/underlay.repos
    $ vcs import src < underlay.repos
    (rosdep install)
    $ colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release
  3. Source ros2_foxy and nav2_depend_ws workspaces

  4. Build nav2 stack and got the failure from above.

Additional information

From the ros2 headers I've got the following:

$ vim ~/ros2_foxy/install/rclcpp/include/rclcpp/node.hpp
...
  /// Declare a parameter
  [[deprecated(
    "declare_parameter() with only a name is deprecated and will be deleted in the future.\n" \
    "If you want to declare a parameter that won't change type without a default value use:\n" \
    "`node->declare_parameter<ParameterT>(name)`, where e.g. ParameterT=int64_t.\n\n" \
    "If you want to declare a parameter that can dynamically change type use:\n" \
    "```\n" \
    "rcl_interfaces::msg::ParameterDescriptor descriptor;\n" \
    "descriptor.dynamic_typing = true;\n" \
    "node->declare_parameter(name, rclcpp::ParameterValue{}, descriptor);\n" \
    "```"
  )]]
  RCLCPP_PUBLIC
  const rclcpp::ParameterValue &
  declare_parameter(const std::string & name);

So, it looks indeed the declare_parameter("with_one_argument") API will be closed soon. So we will need to prepare for this.

SteveMacenski commented 3 years ago

Seems like something we should make sure is done before Galactic, do you know how many-ish of these you saw? I'm glancing through the codebase and this seems like it would be relatively small. Many something we could get done in a few minutes

Trilion99 commented 3 years ago

For me the issue occured in:

nav2_lifecycle_manager/src/lifecycle_manager.cpp
nav2_map_server/src/map_server/map_server.cpp
nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp

As recommended in the warning, something like

rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.dynamic_typing = true;
declare_parameter("node_names", rclcpp::ParameterValue{}, descriptor);

fixed the build. Will test tomorrow.

Trilion99 commented 3 years ago

I do get an error further down the line when running nav2:

[controller_server-2] [INFO] [1615189129.370961414] [local_costmap.local_costmap]: Configuring
[controller_server-2] [ERROR] [1615189129.377984100] []: Caught exception in callback for transition 10
[controller_server-2] [ERROR] [1615189129.379926889] []: Original error: parameter 'voxel_layer.plugin' has invalid type: cannot declare a statically typed parameter with an uninitialized value
[controller_server-2] [WARN] [1615189129.380714955] []: Error occurred while doing error handling.
[controller_server-2] [FATAL] [1615189129.381328773] [controller_server]: Lifecycle node controller_server does not have error state implemented
[lifecycle_manager-7] [ERROR] [1615189129.418561243] [lifecycle_manager_navigation]: Failed to change state for node: controller_server
[lifecycle_manager-7] [ERROR] [1615189129.418655077] [lifecycle_manager_navigation]: Failed to bring up all requested nodes. Aborting bringup.

Not sure if that's related.

Trilion99 commented 3 years ago

It is related. Modifying declare_parameter_if_not_declared in node_utils.hpp to something like the below fixes it. I think.. Need to do more testing.

template<typename NodeT>
void declare_parameter_if_not_declared(
  NodeT node,
  const std::string & param_name,
  const rclcpp::ParameterValue & default_value = rclcpp::ParameterValue())
{
  rcl_interfaces::msg::ParameterDescriptor descriptor;
  descriptor.dynamic_typing = true;

  if (!node->has_parameter(param_name)) {
    node->declare_parameter(param_name, default_value, descriptor);
  }
}
SteveMacenski commented 3 years ago

I don't think we want dynamic typing, rather we want to declare parameters without any default value (e.g. requiring that a value is set in param files) but of a consistent type

Trilion99 commented 3 years ago

That makes sense, I just went for the quick fix there. We have a customer demo on Thursday, but will try do do it properly afterwards, if the ticket is still open.

AlexeyMerzlyakov commented 3 years ago

Related announcement on Discourse for RCLCPP API change: https://discourse.ros.org/t/feedback-required-should-parameters-be-able-to-change-of-type/18319/2. Here I'd like also agree that we have to use new static parameters rather than dynamic ones. Static parameters should be explicitly specified which type are they of. For that, we need to update Nav2 API, more specifically:

... and do change for all dependent from this API code and tests.

Today I've tried to play with it, however I've faced one more problem with that RCLCPP change. When I trying to set a static parameter with no default value (e.g. by using node->declare_parameter("my_param", rclcpp::PARAMETER_INTEGER, descriptor)), it causes a NoParameterOverrideProvided exception during the call. This seems really strange as I deliberately did not set a default value for this parameter in the hope of later setting it by using set_parameter() call. However, even if I catch and ignore this exception, set_parameter() will later fail to execute. This appears due to the https://github.com/ros2/rclcpp/commit/24bb6530#diff-676b13acdb382d7be6e1bf294bf204c4368448e0d18c6bd141981a1ce06b5ef6R464-R466 logic in declare_parameter(). I did not find that this point being documented in original PR (https://github.com/ros2/rclcpp/pull/1522) or in documentation update (https://github.com/ros2/rclcpp/pull/1568, currently in progress). So, not sure that this is expected behavior, or a bug. The related test is a: nav2_costmap_2d/test/unit/declare_parameter_test.cpp where we are relying on declare_parameter() with no default value, but later setting it by using node->set_parameter(rclcpp::Parameter("test_layer.test2", "test_val2")); nicely shows the problem.

Analysis of the root cause is in progress. Possibly, I need to contact a RCLCPP developers with this question.

SteveMacenski commented 3 years ago

@AlexeyMerzlyakov please comment on those PRs/tickets then bringing this up. Being able to declare a static type with no default is incredibly important.


// declares an int parameter that cannot change of type, but no default value is provided.
// if no param override is provided, it will start with type PARAMETER_NOT_SET
node->declare_parameter("my_param", rclcpp::PARAMETER_INTEGER);

but that PR has a version of this that says that it works and the docs say that too. Are you sure you did that right?

You should obviously expect an exception when you didn't set the parameter and then also launched it, but if it you launched it and the parameter was provided in a file, that should work. That's no different than how it is right now with default-less declares: it will throw an exception when the parameter isn't set in the file due to lack of default provided for use.

AlexeyMerzlyakov commented 3 years ago

Are you sure you did that right?

I am using the following code snippet:

#include <memory>
#include <string>
#include <exception>
#include <stdio.h>

#include "rclcpp/rclcpp.hpp"

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("test_node");

  try {
    node->declare_parameter("param1", rclcpp::PARAMETER_STRING);
  } catch (const std::exception & e) {
    printf("Excpetion at declare_parameter(): %s\n", e.what());
  }
  try {
    node->set_parameter(rclcpp::Parameter("param1", "value1"));
  } catch (const std::exception & e) {
    printf("Excpetion at set_parameter(): %s\n", e.what());
  }

  try {
    std::string val = node->get_parameter("param1").as_string();
    printf("param1 = %s\n", val.c_str());
  } catch (const std::exception & e) {
    printf("Failed to get parameter value: %s\n", e.what());
  }

  fflush(stdout);

  rclcpp::shutdown();
  return 0;
}

That gives a full of error output:

static_issue_ws$ ./install/test/lib/test/test_exec 
Excpetion at declare_parameter(): parameter 'param1' requires an user provided parameter override
Excpetion at set_parameter(): parameter 'param1' cannot be set because it was not declared
Failed to get parameter value: param1

We could do a parameter re-declaration with YAML parameter file or in the code later, like:

 node->declare_parameter("param1", rclcpp::PARAMETER_STRING);
 ...
 node->declare_parameter("param1", "value1");

However this makes first node->declare_parameter("param1", rclcpp::PARAMETER_STRING) call to be absolute useless. Instead of it I can call declare_parameter once with a specific value. So, I think here is the reason to contact RCLCPP developers and ask them about such a use-case (I think this is important for us): what should I do if I want to declare parameter with no default value and set it later.


As an alternative for today, we can use dynamic parameters in Nav2. Something like:

rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.dynamic_typing = true;
node->declare_parameter("param1", rclcpp::ParameterValue{}, descriptor);

will work as previously permitted declare_parameter("with_one_argument"). But I still lean towards using static parameters.

SteveMacenski commented 3 years ago

Please file that with the tickets / PRs above in rclcpp with your minimal example. Looks like an oversight since their PR even specifically says that should work.