Skip to content

Cannot use free function in rclcpp::create_timer because of invalid static_cast #1915

@sloretz

Description

@sloretz

Bug report

Required Info:

  • Operating System:
    • Jammy
  • Installation type:
    • Source
  • Version or commit hash:
  • DDS implementation:
    • Fast-DDS
  • Client library (if applicable):
    • rclcpp

Steps to reproduce issue

#include <iostream>
#include "rclcpp/rclcpp.hpp"

void timer_callback()
{
  std::cerr << "timer ran\n";
}

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

  auto node = std::make_shared<rclcpp::Node>("rclcpp_create_timer");

  auto some_timer = rclcpp::create_timer(
      node,
      node->get_clock(),
      rclcpp::Duration(10, 0),
      timer_callback);

  rclcpp::executors::SingleThreadedExecutor exe;
  exe.add_node(node);
  exe.spin();

  rclcpp::shutdown();

  return 0;
}
add_executable(rclcpp_create_timer
  src/rclcpp_create_timer.cpp)
target_link_libraries(rclcpp_create_timer
  rclcpp::rclcpp)

Expected behavior

Successful compilation

Actual behavior

Compilation fails.

In file included from /home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/service.hpp:34,
                 from /home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/callback_group.hpp:25,
                 from /home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/any_executable.hpp:20,
                 from /home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/memory_strategy.hpp:25,
                 from /home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/memory_strategies.hpp:18,
                 from /home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/executor_options.hpp:20,
                 from /home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/executor.hpp:37,
                 from /home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/executors/multi_threaded_executor.hpp:25,
                 from /home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/executors.hpp:21,
                 from /home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/rclcpp.hpp:155,
                 from /home/osrf/ws/ros2/src/ros2/demos/lifecycle/src/rclcpp_create_timer.cpp:2:
/home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/timer.hpp: In instantiation of ‘rclcpp::GenericTimer<FunctorT, <anonymous> >::GenericTimer(rclcpp::Clock::SharedPtr, std::chrono::nanoseconds, FunctorT&&, rclcpp::Context::SharedPtr) [with FunctorT = void (&)(); typename std::enable_if<(rclcpp::function_traits::same_arguments<FunctorT, std::function<void()> >::value || rclcpp::function_traits::same_arguments<FunctorT, std::function<void(rclcpp::TimerBase&)> >::value)>::type* <anonymous> = 0; rclcpp::Clock::SharedPtr = std::shared_ptr<rclcpp::Clock>; std::chrono::nanoseconds = std::chrono::duration<long int, std::ratio<1, 1000000000> >; rclcpp::Context::SharedPtr = std::shared_ptr<rclcpp::Context>]’:
/usr/include/c++/11/ext/new_allocator.h:162:4:   required from ‘void __gnu_cxx::new_allocator<_Tp>::construct(_Up*, _Args&& ...) [with _Up = rclcpp::GenericTimer<void (&)(), 0>; _Args = {std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long int, std::ratio<1, 1000000000> >, void (&)(), std::shared_ptr<rclcpp::Context>}; _Tp = rclcpp::GenericTimer<void (&)(), 0>]’
/usr/include/c++/11/bits/alloc_traits.h:516:17:   required from ‘static void std::allocator_traits<std::allocator<_CharT> >::construct(std::allocator_traits<std::allocator<_CharT> >::allocator_type&, _Up*, _Args&& ...) [with _Up = rclcpp::GenericTimer<void (&)(), 0>; _Args = {std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long int, std::ratio<1, 1000000000> >, void (&)(), std::shared_ptr<rclcpp::Context>}; _Tp = rclcpp::GenericTimer<void (&)(), 0>; std::allocator_traits<std::allocator<_CharT> >::allocator_type = std::allocator<rclcpp::GenericTimer<void (&)(), 0> >]’
/usr/include/c++/11/bits/shared_ptr_base.h:519:39:   required from ‘std::_Sp_counted_ptr_inplace<_Tp, _Alloc, _Lp>::_Sp_counted_ptr_inplace(_Alloc, _Args&& ...) [with _Args = {std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long int, std::ratio<1, 1000000000> >, void (&)(), std::shared_ptr<rclcpp::Context>}; _Tp = rclcpp::GenericTimer<void (&)(), 0>; _Alloc = std::allocator<rclcpp::GenericTimer<void (&)(), 0> >; __gnu_cxx::_Lock_policy _Lp = __gnu_cxx::_S_atomic]’
/usr/include/c++/11/bits/shared_ptr_base.h:650:16:   required from ‘std::__shared_count<_Lp>::__shared_count(_Tp*&, std::_Sp_alloc_shared_tag<_Alloc>, _Args&& ...) [with _Tp = rclcpp::GenericTimer<void (&)(), 0>; _Alloc = std::allocator<rclcpp::GenericTimer<void (&)(), 0> >; _Args = {std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long int, std::ratio<1, 1000000000> >, void (&)(), std::shared_ptr<rclcpp::Context>}; __gnu_cxx::_Lock_policy _Lp = __gnu_cxx::_S_atomic]’
/usr/include/c++/11/bits/shared_ptr_base.h:1342:14:   [ skipping 2 instantiation contexts, use -ftemplate-backtrace-limit=0 to disable ]
/usr/include/c++/11/bits/shared_ptr.h:862:14:   required from ‘std::shared_ptr<_Tp> std::allocate_shared(const _Alloc&, _Args&& ...) [with _Tp = rclcpp::GenericTimer<void (&)(), 0>; _Alloc = std::allocator<rclcpp::GenericTimer<void (&)(), 0> >; _Args = {std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long int, std::ratio<1, 1000000000> >, void (&)(), std::shared_ptr<rclcpp::Context>}]’
/usr/include/c++/11/bits/shared_ptr.h:878:39:   required from ‘std::shared_ptr<_Tp> std::make_shared(_Args&& ...) [with _Tp = rclcpp::GenericTimer<void (&)(), 0>; _Args = {std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long int, std::ratio<1, 1000000000> >, void (&)(), std::shared_ptr<rclcpp::Context>}]’
/home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/timer.hpp:174:3:   required from ‘static std::shared_ptr<rclcpp::GenericTimer<FunctorT, <anonymous> > > rclcpp::GenericTimer<FunctorT, <anonymous> >::make_shared(Args&& ...) [with Args = {std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long int, std::ratio<1, 1000000000> >, void (&)(), std::shared_ptr<rclcpp::Context>}; FunctorT = void (&)(); typename std::enable_if<(rclcpp::function_traits::same_arguments<FunctorT, std::function<void()> >::value || rclcpp::function_traits::same_arguments<FunctorT, std::function<void(rclcpp::TimerBase&)> >::value)>::type* <anonymous> = 0]’
/home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/create_timer.hpp:44:60:   required from ‘rclcpp::TimerBase::SharedPtr rclcpp::create_timer(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTimersInterface>, rclcpp::Clock::SharedPtr, rclcpp::Duration, CallbackT&&, rclcpp::CallbackGroup::SharedPtr) [with CallbackT = void (&)(); rclcpp::TimerBase::SharedPtr = std::shared_ptr<rclcpp::TimerBase>; rclcpp::Clock::SharedPtr = std::shared_ptr<rclcpp::Clock>; rclcpp::CallbackGroup::SharedPtr = std::shared_ptr<rclcpp::CallbackGroup>]’
/home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/create_timer.hpp:64:22:   required from ‘rclcpp::TimerBase::SharedPtr rclcpp::create_timer(NodeT, rclcpp::Clock::SharedPtr, rclcpp::Duration, CallbackT&&, rclcpp::CallbackGroup::SharedPtr) [with NodeT = std::shared_ptr<rclcpp::Node>; CallbackT = void (&)(); rclcpp::TimerBase::SharedPtr = std::shared_ptr<rclcpp::TimerBase>; rclcpp::Clock::SharedPtr = std::shared_ptr<rclcpp::Clock>; rclcpp::CallbackGroup::SharedPtr = std::shared_ptr<rclcpp::CallbackGroup>]’
/home/osrf/ws/ros2/src/ros2/demos/lifecycle/src/rclcpp_create_timer.cpp:15:41:   required from here
/home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/timer.hpp:189:5: error: invalid ‘static_cast’ from type ‘void (*)()’ to type ‘const void*’
  189 |     TRACEPOINT(
      |     ^~~~~~~~~~
/home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/timer.hpp:193:5: error: invalid ‘static_cast’ from type ‘void (*)()’ to type ‘const void*’
  193 |     TRACEPOINT(
      |     ^~~~~~~~~~
/home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/timer.hpp: In instantiation of ‘void rclcpp::GenericTimer<FunctorT, <anonymous> >::execute_callback() [with FunctorT = void (&)(); typename std::enable_if<(rclcpp::function_traits::same_arguments<FunctorT, std::function<void()> >::value || rclcpp::function_traits::same_arguments<FunctorT, std::function<void(rclcpp::TimerBase&)> >::value)>::type* <anonymous> = 0]’:
/home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/timer.hpp:227:3:   required from here
/home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/timer.hpp:229:5: error: invalid ‘static_cast’ from type ‘void (*)()’ to type ‘const void*’
  229 |     TRACEPOINT(callback_start, static_cast<const void *>(&callback_), false);
      |     ^~~~~~~~~~
/home/osrf/ws/ros2/install/rclcpp/include/rclcpp/rclcpp/timer.hpp:231:5: error: invalid ‘static_cast’ from type ‘void (*)()’ to type ‘const void*’
  231 |     TRACEPOINT(callback_end, static_cast<const void *>(&callback_));
      |     ^~~~~~~~~~
gmake[2]: *** [CMakeFiles/rclcpp_create_timer.dir/build.make:76: CMakeFiles/rclcpp_create_timer.dir/src/rclcpp_create_timer.cpp.o] Error 1
gmake[1]: *** [CMakeFiles/Makefile2:221: CMakeFiles/rclcpp_create_timer.dir/all] Error 2
gmake: *** [Makefile:146: all] Error 2

Additional information

It looks like the cast added in #1263 tries to convert a function pointer to a void *, which isn't static_cast'able. reinterpret_cast might be required here.

Wrapping timer_callback in std::bind solves the issue.

  auto some_timer = rclcpp::create_timer(
      node,
      node->get_clock(),
      rclcpp::Duration(10, 0),
      std::bind(timer_callback));

Metadata

Metadata

Assignees

No one assigned

    Labels

    bugSomething isn't working

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions