rclcpp
rclcpp copied to clipboard
Unable to compile code that uses rclcpp::SubsciptionOptions with ROS Humble
Bug report
Required Info:
- Operating System: Ubuntu 22.04
- Installation type: Binaries
- Version or commit hash: humble release version
- DDS implementation: default
- Client library (if applicable): rclcpp
Steps to reproduce issue
Moving from Galactic to Humble
Unable to compile code that uses rclcpp::SubsciptionOptions
Expected behavior
Code compiles and can use subscription options for multi-threaded executor
Actual behavior
Code doesnt compile
Additional information
--- stderr: sdcar_arrow
In file included from /opt/ros/humble/include/rclcpp/rclcpp/subscription.hpp:45,
from /opt/ros/humble/include/rclcpp/rclcpp/any_executable.hpp:25,
from /opt/ros/humble/include/rclcpp/rclcpp/memory_strategy.hpp:25,
from /opt/ros/humble/include/rclcpp/rclcpp/memory_strategies.hpp:18,
from /opt/ros/humble/include/rclcpp/rclcpp/executor_options.hpp:20,
from /opt/ros/humble/include/rclcpp/rclcpp/executor.hpp:37,
from /opt/ros/humble/include/rclcpp/rclcpp/executors/multi_threaded_executor.hpp:25,
from /opt/ros/humble/include/rclcpp/rclcpp/executors.hpp:21,
from /opt/ros/humble/include/rclcpp/rclcpp/rclcpp.hpp:155,
from /home/nick/sdcar-poc5-ws/src/sdcar-arrow/src/arrow_sink_node.cpp:5:
/opt/ros/humble/include/rclcpp/rclcpp/subscription_options.hpp:100:47: error: expected unqualified-id before ‘)’ token
100 | SubscriptionOptionsWithAllocator<Allocator>() {}
| ^
In file included from /opt/ros/humble/include/rclcpp/rclcpp/publisher.hpp:42,
from /opt/ros/humble/include/rclcpp/rclcpp/topic_statistics/subscription_topic_statistics.hpp:31,
from /opt/ros/humble/include/rclcpp/rclcpp/subscription.hpp:50,
from /opt/ros/humble/include/rclcpp/rclcpp/any_executable.hpp:25,
from /opt/ros/humble/include/rclcpp/rclcpp/memory_strategy.hpp:25,
from /opt/ros/humble/include/rclcpp/rclcpp/memory_strategies.hpp:18,
from /opt/ros/humble/include/rclcpp/rclcpp/executor_options.hpp:20,
from /opt/ros/humble/include/rclcpp/rclcpp/executor.hpp:37,
from /opt/ros/humble/include/rclcpp/rclcpp/executors/multi_threaded_executor.hpp:25,
from /opt/ros/humble/include/rclcpp/rclcpp/executors.hpp:21,
from /opt/ros/humble/include/rclcpp/rclcpp/rclcpp.hpp:155,
from /home/nick/sdcar-poc5-ws/src/sdcar-arrow/src/arrow_sink_node.cpp:5:
/opt/ros/humble/include/rclcpp/rclcpp/publisher_options.hpp:75:44: error: expected unqualified-id before ‘)’ token
75 | PublisherOptionsWithAllocator<Allocator>() {}
|
..
/home/nick/sdcar-poc5-ws/src/sdcar-arrow/src/arrow_sink_node.cpp:74:58: error: no matching function for call to ‘rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> >::SubscriptionOptionsWithAllocator()’
74 | auto subscriptions_opt = rclcpp::SubscriptionOptions();
| ^
In file included from /opt/ros/humble/include/rclcpp/rclcpp/subscription.hpp:45,
from /opt/ros/humble/include/rclcpp/rclcpp/any_executable.hpp:25,
from /opt/ros/humble/include/rclcpp/rclcpp/memory_strategy.hpp:25,
from /opt/ros/humble/include/rclcpp/rclcpp/memory_strategies.hpp:18,
from /opt/ros/humble/include/rclcpp/rclcpp/executor_options.hpp:20,
from /opt/ros/humble/include/rclcpp/rclcpp/executor.hpp:37,
from /opt/ros/humble/include/rclcpp/rclcpp/executors/multi_threaded_executor.hpp:25,
from /opt/ros/humble/include/rclcpp/rclcpp/executors.hpp:21,
from /opt/ros/humble/include/rclcpp/rclcpp/rclcpp.hpp:155,
from /home/nick/sdcar-poc5-ws/src/sdcar-arrow/src/arrow_sink_node.cpp:5:
/opt/ros/humble/include/rclcpp/rclcpp/subscription_options.hpp:103:12: note: candidate: ‘rclcpp::SubscriptionOptionsWithAllocator<Allocator>::SubscriptionOptionsWithAllocator(const rclcpp::SubscriptionOptionsBase&) [with Allocator = std::allocator<void>]’
103 | explicit SubscriptionOptionsWithAllocator(
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
/opt/ros/humble/include/rclcpp/rclcpp/subscription_options.hpp:103:12: note: candidate expects 1 argument, 0 provided
/opt/ros/humble/include/rclcpp/rclcpp/subscription_options.hpp:91:8: note: candidate: ‘rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> >::SubscriptionOptionsWithAllocator(const rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> >&)’
91 | struct SubscriptionOptionsWithAllocator : public SubscriptionOptionsBase
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
/opt/ros/humble/include/rclcpp/rclcpp/subscription_options.hpp:91:8: note: candidate expects 1 argument, 0 provided
/opt/ros/humble/include/rclcpp/rclcpp/subscription_options.hpp:91:8: note: candidate: ‘rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> >::SubscriptionOptionsWithAllocator(rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> >&&)’
/opt/ros/humble/include/rclcpp/rclcpp/subscription_options.hpp:91:8: note: candidate expects 1 argument, 0 provided
/home/nick/sdcar-poc5-ws/src/sdcar-arrow/src/arrow_sink_node.cpp:76:64: error: no matching function for call to ‘rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> >::SubscriptionOptionsWithAllocator()’
76 | auto subscriptions_image_opt = rclcpp::SubscriptionOptions();
| ^
In file included from /opt/ros/humble/include/rclcpp/rclcpp/subscription.hpp:45,
from /opt/ros/humble/include/rclcpp/rclcpp/any_executable.hpp:25,
from /opt/ros/humble/include/rclcpp/rclcpp/memory_strategy.hpp:25,
from /opt/ros/humble/include/rclcpp/rclcpp/memory_strategies.hpp:18,
from /opt/ros/humble/include/rclcpp/rclcpp/executor_options.hpp:20,
from /opt/ros/humble/include/rclcpp/rclcpp/executor.hpp:37,
from /opt/ros/humble/include/rclcpp/rclcpp/executors/multi_threaded_executor.hpp:25,
from /opt/ros/humble/include/rclcpp/rclcpp/executors.hpp:21,
from /opt/ros/humble/include/rclcpp/rclcpp/rclcpp.hpp:155,
from /home/nick/sdcar-poc5-ws/src/sdcar-arrow/src/arrow_sink_node.cpp:5:
/opt/ros/humble/include/rclcpp/rclcpp/subscription_options.hpp:103:12: note: candidate: ‘rclcpp::SubscriptionOptionsWithAllocator<Allocator>::SubscriptionOptionsWithAllocator(const rclcpp::SubscriptionOptionsBase&) [with Allocator = std::allocator<void>]’
103 | explicit SubscriptionOptionsWithAllocator(
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
/opt/ros/humble/include/rclcpp/rclcpp/subscription_options.hpp:103:12: note: candidate expects 1 argument, 0 provided
/opt/ros/humble/include/rclcpp/rclcpp/subscription_options.hpp:91:8: note: candidate: ‘rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> >::SubscriptionOptionsWithAllocator(const rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> >&)’
91 | struct SubscriptionOptionsWithAllocator : public SubscriptionOptionsBase
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
/opt/ros/humble/include/rclcpp/rclcpp/subscription_options.hpp:91:8: note: candidate expects 1 argument, 0 provided
/opt/ros/humble/include/rclcpp/rclcpp/subscription_options.hpp:91:8: note: candidate: ‘rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> >::SubscriptionOptionsWithAllocator(rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> >&&)’
/opt/ros/humble/include/rclcpp/rclcpp/subscription_options.hpp:91:8: note: candidate expects 1 argument, 0 provided
I can't remember exactly, but we may have changed that API. Can you give a link to code to reproduce the issue?
All I’m doing is trying to use rclcpp:subscriptionIOptions the same as in galactic.
The actual code I’m using is private and has some other external library dependencies.
The compile error seems to suggest any program declaring a variable of that type will now fail.
On 20 May 2022, at 9:04 pm, Chris Lalancette @.***> wrote:
I can't remember exactly, but we may have changed that API. Can you give a link to code to reproduce the issue?
— Reply to this email directly, view it on GitHub, or unsubscribe. You are receiving this because you authored the thread.
It's a little hard to tell what is going on from the original report, so a minimal reproducible example would be helpful.
Examples of currently working SubscriptionOptions
and PublisherOptions
are in https://github.com/ros2/demos/blob/bd49f4b64ee7f65616dccbe37e96fb64a9cad6ee/demo_nodes_cpp/src/topics/content_filtering_subscriber.cpp#L51-L60 and https://github.com/ros2/demos/blob/bd49f4b64ee7f65616dccbe37e96fb64a9cad6ee/quality_of_service_demo/rclcpp/src/qos_overrides_talker.cpp#L59-L98 , so maybe that will give you some idea of what is different.
I’m using it with the multithreaded executor to place subscriptions in different callback groups.
#include
#include "sensor_msgs/msg/imu.hpp" #include "sensor_msgs/msg/time_reference.hpp" #include "sensor_msgs/msg/image.hpp"
#include "std_msgs/msg/float64.hpp"
#include "sdcar_arrow_interfaces/srv/write_table.hpp"
#include "car_msgs/msg/vehicle_state.hpp"
#include <arrow/api.h>
#include <parquet/arrow/writer.h>
#include <parquet/exception.h>
#include
#include "sdcar_arrow/visibility.h"
#include "sdcar_arrow/arrow_writer.hpp" #include <ublox_ubx_msgs/msg/ubx_nav_hp_pos_llh.hpp>
using namespace std::chrono_literals; using namespace std; using std::placeholders::_1; using std::placeholders::_2; using std::placeholders::_3;
…
callback_group_subscribers_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
callback_group_image_subscribers_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
callback_group_pointcloud2_subscribers_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
callback_group_writers_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
auto subscriptions_opt = rclcpp::SubscriptionOptions();
subscriptions_opt.callback_group = callback_group_subscribers_;
auto subscriptions_image_opt = rclcpp::SubscriptionOptions();
subscriptions_image_opt.callback_group = callback_group_image_subscribers_;
auto subscription_pointcloud2_opt = rclcpp::SubscriptionOptions();
subscription_pointcloud2_opt.callback_group = callback_group_pointcloud2_subscribers_;
….
left_image_sub_ = this->create_subscription<sensor_msgs::msg::Image>( "/stereo/left/image_raw", qos, std::bind(&ArrowSinkNode::left_image_callback, this, 1), subscriptions_image_opt); right_image_sub = this->create_subscription<sensor_msgs::msg::Image>( "/stereo/right/image_raw", qos, std::bind(&ArrowSinkNode::right_image_callback, this, 1), subscriptions_image_opt); // imu_sub = this->create_subscription<sensor_msgs::msg::Imu> // ("/jy901/imu/data", qos, std::bind(&ArrowSink::imu_callback, this, 1)); // imu2_sub = this->create_subscription<sensor_msgs::msg::Imu> // ("/imu/data", qos, std::bind(&ArrowSink::imu_callback, this, 1)); vehicle_state_sub = this->create_subscription<car_msgs::msg::VehicleState>( "/car/state", qos, std::bind( &ArrowSinkNode::vehicle_state_callback, this, 1), subscriptions_opt); point_cloud_sub = this->create_subscription<sensor_msgs::msg::PointCloud2>( "/lidar_point_cloud", qos, std::bind(&ArrowSinkNode::point_cloud_callback, this, _1), subscription_pointcloud2_opt);
ubx_nav_hpposllh_sub_ = create_subscription<ublox_ubx_msgs::msg::UBXNavHPPosLLH>(
"/ubx_nav_hp_pos_llh", qos, std::bind(&ArrowSinkNode::ubx_nav_hpposllh_callback, this, _1),
subscriptions_opt);
timer_ = this->create_wall_timer(5s, std::bind(&ArrowSinkNode::timer_callback, this),
callback_group_writers_);
On 20 May 2022, at 10:10 pm, Chris Lalancette @.***> wrote:
It's a little hard to tell what is going on from the original report, so a minimal reproducible example would be helpful.
Examples of currently working SubscriptionOptions and PublisherOptions are in https://github.com/ros2/demos/blob/bd49f4b64ee7f65616dccbe37e96fb64a9cad6ee/demo_nodes_cpp/src/topics/content_filtering_subscriber.cpp#L51-L60 and https://github.com/ros2/demos/blob/bd49f4b64ee7f65616dccbe37e96fb64a9cad6ee/quality_of_service_demo/rclcpp/src/qos_overrides_talker.cpp#L59-L98 , so maybe that will give you some idea of what is different.
— Reply to this email directly, view it on GitHub, or unsubscribe. You are receiving this because you authored the thread.
this is related to https://github.com/ros2/rclcpp/pull/1926 (humble backport is W.I.P, https://github.com/ros2/rclcpp/pull/1937)
@hortovanyi do you use C++20? if that is so, that leads to the following compile error.
--- stderr: rclcpp
In file included from /root/ros2_ws/colcon_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/subscription.hpp:45,
from /root/ros2_ws/colcon_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_executable.hpp:25,
from /root/ros2_ws/colcon_ws/src/ros2/rclcpp/rclcpp/src/rclcpp/any_executable.cpp:15:
/root/ros2_ws/colcon_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/subscription_options.hpp:100:47: error: expected unqualified-id before ‘)’ token
100 | SubscriptionOptionsWithAllocator<Allocator>() {}
| ^
gmake[2]: *** [CMakeFiles/rclcpp.dir/build.make:181: CMakeFiles/rclcpp.dir/src/rclcpp/any_executable.cpp.o] Error 1
gmake[2]: *** Waiting for unfinished jobs....
In file included from /root/ros2_ws/colcon_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/subscription.hpp:45,
from /root/ros2_ws/colcon_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_executable.hpp:25,
from /root/ros2_ws/colcon_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/memory_strategy.hpp:25,
from /root/ros2_ws/colcon_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/memory_strategies.hpp:18,
from /root/ros2_ws/colcon_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/executor_options.hpp:20,
from /root/ros2_ws/colcon_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/executor.hpp:37,
from /root/ros2_ws/colcon_ws/src/ros2/rclcpp/rclcpp/src/rclcpp/executor.cpp:28:
/root/ros2_ws/colcon_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/subscription_options.hpp:100:47: error: expected unqualified-id before ‘)’ token
100 | SubscriptionOptionsWithAllocator<Allocator>() {}
| ^
...<snip>
we use C++ 17 in default, see https://github.com/ros2/rclcpp/pull/1926#issuecomment-1124426168. https://github.com/ros2/rclcpp/blob/491475f2324bb9dfcc943f4b9f3d4528d6e81716/rclcpp/CMakeLists.txt#L25-L28
@fujitatomoya I changed it from c++14 to c++17 for Humble .... ohh the target_compile_features statement had cxx_std_20. Changed it to cxx_std_17 and it worked. Strange compiled on Galactic
cmake_minimum_required(VERSION 3.8)
project(sdcar_arrow)
# Default to C99
if(NOT CMAKE_C_STANDARD)
set(CMAKE_C_STANDARD 99)
endif()
# Default to C++17
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
LIST(INSERT CMAKE_MODULE_PATH 0 ${CMAKE_CURRENT_SOURCE_DIR}/CMake)
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(ublox_ubx_msgs REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(std_msgs REQUIRED)
find_package(Zstd REQUIRED)
if (ZSTD_FOUND)
set(ZSTD_LIB ${ZSTD_LIBRARY})
endif (ZSTD_FOUND)
find_package(Arrow REQUIRED)
find_package(car_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(sdcar_arrow_interfaces REQUIRED)
include_directories(include SYSTEM ${ARROW_INCLUDE_DIR} ${PARQUET_INCLUDE_DIR})
add_library(sdcar_arrow_components SHARED
src/arrow_sink_node.cpp
)
ament_generate_version_header(sdcar_arrow_components)
target_compile_definitions(sdcar_arrow_components
PRIVATE "SDCAR_ARROW_BUILDING_DLL"
)
target_compile_features(sdcar_arrow_components PUBLIC c_std_99 cxx_std_20) # Require C99 and C++20
ament_target_dependencies(sdcar_arrow_components
rclcpp
rclcpp_components
std_msgs
sensor_msgs
ublox_ubx_msgs
sdcar_arrow_interfaces
car_msgs
)
target_link_libraries(sdcar_arrow_components
arrow
parquet
plasma
)
rclcpp_components_register_node(sdcar_arrow_components PLUGIN "sdcar::ArrowSinkNode" EXECUTABLE arrow_sink_node)
install(TARGETS
sdcar_arrow_components
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)
install(
DIRECTORY launch
DESTINATION share/${PROJECT_NAME}
)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()
@hortovanyi thanks for checking, the fix will be delivered in next patch release. (see https://github.com/ros2/rclcpp/pull/1937#issuecomment-1133327125)
It worked for my application switching from: set(CMAKE_CXX_STANDARD 20) to: set(CMAKE_CXX_STANDARD 17)
Since both of the backports have been merged and the original problem has been fixed, is this issue finished?
Since both of the backports have been merged and the original problem has been fixed, is this issue finished?
Yeah, good call. I'll close this out.