ros2 / rclcpp

rclcpp (ROS Client Library for C++)
Apache License 2.0
545 stars 417 forks source link

Retrieving(get_parameter()) value of parameter of type std::vector<int> won't build #2577

Open Pratham-Pandey opened 3 months ago

Pratham-Pandey commented 3 months ago

Bug report

Required Info:

Steps to reproduce issue

  1. Create a ROS2 package
ros2 pkg create --build-type ament_cmake vector_int_pkg
  1. Create a simple node the declares a parameter of type std::vector in file src/test_vector_int.cpp
    
    #include "rclcpp/rclcpp.hpp"

int main(int argc, char ** argv) { rclcpp::init(argc, argv);

std::shared_ptr node = rclcpp::Node::make_shared("vector_integer_parameters");

// Declaring Params node->declare_parameter("param", std::vector{});

// Getting Params std::vector clamps_iters = {1,2,3}; node->get_parameter("param", clamps_iters);

rclcpp::spin(node); rclcpp::shutdown(); }

3. Adjust the CMakeLists.txt file

cmake_minimum_required(VERSION 3.5) project(vector_int_pkg)

if (NOT CMAKE_C_STANDARD) set(CMAKE_C_STANDARD 99) endif ()

if (NOT CMAKE_CXX_STANDARD) set(CMAKE_CXX_STANDARD 14) endif ()

if (CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif ()

find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED)

add_executable(test_vector_int src/test_vector_int.cpp) ament_target_dependencies(test_vector_int rclcpp)

ament_package()

4. Adjust the package.xml

<?xml version="1.0"?> <?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>

vector_int_pkg 0.0.0 TODO: Package description John Doe TODO: License declaration ament_cmake rclcpp ament_lint_auto ament_lint_common ament_cmake

5. Build the package

colcon build --packages-select vector_int_pkg

#### Expected behavior
The package should build successfully.

#### Actual behavior
The build fails with the following error:

/home/user/ros_ws/src/vector_int_pkg/src/test_vector_int.cpp:14:22: required from here /opt/ros/iron/include/rclcpp/rclcpp/node_impl.hpp:343:17: error: no matching function for call to ‘std::vector::vector(std::vector<long int, std::allocator >)’ 343 | parameter = static_cast(parameter_variant.get_value()); | ^~~~~~~~~~~~~~



#### Additional information
The issue seems similar to #1585. The only difference is that issue was related to declaring parameter values and this one is related to retrieving values. 
NOTE: The code in #1585 is building successfully on my system.
Barry-Xu-2018 commented 3 months ago

In ParameterValue, std::vector\ and std::vector are of the same type.

https://github.com/ros2/rclcpp/blob/c743c173e68d92af872cf163e10721a8dbe51dd0/rclcpp/src/rclcpp/parameter_value.cpp#L188-L198

Both are stored as std::vector.

The returned value when retrieving is also std::vector

https://github.com/ros2/rclcpp/blob/c743c173e68d92af872cf163e10721a8dbe51dd0/rclcpp/include/rclcpp/parameter_value.hpp#L305-L313

A simple workaround is std::vector<int64_t> clamps_iters = {1,2,3};

Regarding the fix, I'm considering modifying get() for std::vector as the below

  template<typename type>
  typename std::enable_if<
    std::is_convertible<
      type, const std::vector<int> &>::value, const std::vector<int>>::type
  get() const
  {
    std::vector<int> convert;
    auto array = get<ParameterType::PARAMETER_INTEGER_ARRAY>();
    convert.reserve(array.size());
    for(const auto& val : array) {
      convert.push_back(static_cast<int>(val));
    }
    return convert;
  }

Is there a better way?

Pratham-Pandey commented 3 months ago

In ParameterValue, std::vector and std::vector are of the same type.

Barry-Xu-2018 commented 3 months ago

In ParameterValue, std::vector and std::vector are of the same type.

std::vector -> std:vector\

If both are of same type then what is the need of having 2 different functions? Could you explain the actual cause of the issue?

I think you mean these 2 functions. https://github.com/ros2/rclcpp/blob/c743c173e68d92af872cf163e10721a8dbe51dd0/rclcpp/include/rclcpp/parameter_value.hpp#L305-L323

While executing node->get_parameter("param", clamps_iters); Regardless of whether the type of clamps_iters is std::vector or std::vector, the function above returns the internally stored std::vector.

The issue lies in the static conversion here. While the type of clamps_iters is std::vector\, it wants to convert std::vector to std:vector\. But there's no default conversion function.
https://github.com/ros2/rclcpp/blob/c743c173e68d92af872cf163e10721a8dbe51dd0/rclcpp/include/rclcpp/node_impl.hpp#L345