Error compiling send_goal function of action client - WallFollower Project

Hi,
I am working on part3 of the WallFollower project. While adding the Action Client to my main node, I am getting the following compilation error:

I tried to follow the instructions of the course, I don’t understand what could be the problem. My code related to the constructor and action client function is posted bellow:

class WallFollower : public rclcpp::Node
{
public:
    using OdomRecord = custom_interfaces::action::OdomRecord;
    using GoalHandleOdomRecord = rclcpp_action::ClientGoalHandle<OdomRecord>;

    explicit WallFollower(const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions())
    : Node("wall_follower", node_options), goal_done_(false)
    {
        subscribers_callback_group =this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
        publishers_callback_group =this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
        action_client_callback_group =this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
        
        rclcpp::SubscriptionOptions options1;
        options1.callback_group = subscribers_callback_group;

        vel_publisher = this->create_publisher<geometry_msgs::msg::Twist>("cmd_vel", 10);
        odom_subscriber = this->create_subscription<nav_msgs::msg::Odometry>(
            "odom", 10, std::bind(&WallFollower::odom_subs_callback, this, _7), options1);
        scan_subscriber = this->create_subscription<sensor_msgs::msg::LaserScan>(
            "scan", rclcpp::SensorDataQoS(), std::bind(&WallFollower::scan_subs_callback, this, _7), options1);
        timer_ = this->create_wall_timer(500ms, std::bind(&WallFollower::robot_motion, this), publishers_callback_group);
        print_timer = this->create_wall_timer(2000ms, std::bind(&WallFollower::print_function, this), publishers_callback_group);
        
        this->client_ptr_ = rclcpp_action::create_client<OdomRecord>(
            this->get_node_base_interface(),
            this->get_node_graph_interface(),
            this->get_node_logging_interface(),
            this->get_node_waitables_interface(),
            "record_odom");

        this->action_client_timer_ = this->create_wall_timer(std::chrono::milliseconds(500), std::bind(&WallFollower::send_goal, this), action_client_callback_group);

        this->rotation_z = 0.0;
        this->distance_to_wall = 0.0;
        this->distance_to_front_wall= 0.0;
        this->offset_angle = 0.0;
        this->linear_vel = 0.1;
        this->angular_vel = 0.1;
        this->dist_tol = 0.02;
        this->angle_tol = 3.0*M_PI/180;
        this->timer_period = 0.5;

    }

    bool is_goal_done() const
    {
        return this->goal_done_;
    }

    void send_goal()
    {
        using namespace std::placeholders;

        this->action_client_timer_->cancel();

        this->goal_done_ = false;

        if (!this->client_ptr_) {
            RCLCPP_ERROR(this->get_logger(), "Action client not initialized");
        }

        if (!this->client_ptr_->wait_for_action_server(std::chrono::seconds(10))) {
            RCLCPP_ERROR(this->get_logger(), "Action server not available after waiting");
            this->goal_done_ = true;
            return;
        }

        auto goal_msg = OdomRecord::Goal();

        RCLCPP_INFO(this->get_logger(), "Sending goal");

        auto send_goal_options = rclcpp_action::Client<OdomRecord>::SendGoalOptions();
                    
        send_goal_options.goal_response_callback = 
        std::bind(&WallFollower::goal_response_callback, this, _1);

        send_goal_options.feedback_callback =
        std::bind(&WallFollower::feedback_callback, this, _1, _2);

        send_goal_options.result_callback =
        std::bind(&WallFollower::result_callback, this, _1);
        
        auto goal_handle_future = this->client_ptr_->async_send_goal(goal_msg, send_goal_options);
    }


void goal_response_callback(const GoalHandleOdomRecord::SharedPtr & goal_handle)
    {
        if (!goal_handle) {
        RCLCPP_ERROR(this->get_logger(), "Goal was rejected by server");
        } else {
        RCLCPP_INFO(this->get_logger(), "Goal accepted by server, waiting for result");
        }
    }

    void feedback_callback(
        GoalHandleOdomRecord::SharedPtr,
        const std::shared_ptr<const OdomRecord::Feedback> feedback)
    {
        RCLCPP_INFO(
        this->get_logger(), "Feedback received: Total current distance = %f", feedback->current_total);
    }

    void result_callback(const GoalHandleOdomRecord::WrappedResult & result)
    {
        this->goal_done_ = true;
        switch (result.code) {
        case rclcpp_action::ResultCode::SUCCEEDED:
            break;
        case rclcpp_action::ResultCode::ABORTED:
            RCLCPP_ERROR(this->get_logger(), "Goal was aborted");
            return;
        case rclcpp_action::ResultCode::CANCELED:
            RCLCPP_ERROR(this->get_logger(), "Goal was canceled");
            return;
        default:
            RCLCPP_ERROR(this->get_logger(), "Unknown result code");
            return;
        }

        RCLCPP_INFO(this->get_logger(), "RESULT RECEIVED");
    }

Hi @w.ronaldo.cd ,

I have not gone through your code yet, but from what I did, I am telling you.
That error what the IDE produces is a false-positive.

A error would be a true error only if the error is produced during actual compilation - colcon build ... in your case since you are working with ROS2.
Do not be carried away by the IDE false-positives.

If you get the same error during colcon build ... then post the complete error here as code-block.

Regards,
Girish

Hi @girishkumar.kannan ,
The error appears during compilation (colcon build) I posted that image because it shows where the problem is and the error. I will keep reviewing my code.
Best regards

Paste the errors that occur during compilation carefully here, screenshot or just copy and paste in a code block (better).

Hi @bayodesegun
The error is quite large

/home/user/ros2_ws/src/Wall Follower/wall_follower/src/wall_follower_part3.cpp: In member function 'void WallFollower::send_goal()':
/home/user/ros2_ws/src/Wall Follower/wall_follower/src/wall_follower_part3.cpp:119:66: error: no match for 'operator=' (operand types are 'rclcpp_action::Client<custom_interfaces::action::OdomRecord>::GoalResponseCallback' {aka 'std::function<void(std::shared_future<std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> > >)>'} and 'std::_Bind_helper<false, void (WallFollower::*)(const std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> >&), WallFollower*, const std::_Placeholder<1>&>::type' {aka 'std::_Bind<void (WallFollower::*(WallFollower*, std::_Placeholder<1>))(const std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> >&)>'})
  119 |         std::bind(&WallFollower::goal_response_callback, this, _1);
      |                                                                  ^
In file included from /usr/include/c++/9/functional:59,
                 from /opt/ros/foxy/include/rclcpp/utilities.hpp:19,
                 from /opt/ros/foxy/include/rclcpp/logging.hpp:25,
                 from /home/user/ros2_ws/src/Wall Follower/wall_follower/src/wall_follower_part3.cpp:3:
/usr/include/c++/9/bits/std_function.h:462:7: note: candidate: 'std::function<_Res(_ArgTypes ...)>& std::function<_Res(_ArgTypes ...)>::operator=(const std::function<_Res(_ArgTypes ...)>&) [with _Res = void; _ArgTypes = {std::shared_future<std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> > >}]'
  462 |       operator=(const function& __x)
      |       ^~~~~~~~
/usr/include/c++/9/bits/std_function.h:462:33: note:   no known conversion for argument 1 from 'std::_Bind_helper<false, void (WallFollower::*)(const std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> >&), WallFollower*, const std::_Placeholder<1>&>::type' {aka 'std::_Bind<void (WallFollower::*(WallFollower*, std::_Placeholder<1>))(const std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> >&)>'} to 'const std::function<void(std::shared_future<std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> > >)>&'
  462 |       operator=(const function& __x)
      |                 ~~~~~~~~~~~~~~~~^~~
/usr/include/c++/9/bits/std_function.h:480:7: note: candidate: 'std::function<_Res(_ArgTypes ...)>& std::function<_Res(_ArgTypes ...)>::operator=(std::function<_Res(_ArgTypes ...)>&&) [with _Res = void; _ArgTypes = {std::shared_future<std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> > >}]'
  480 |       operator=(function&& __x) noexcept
      |       ^~~~~~~~
/usr/include/c++/9/bits/std_function.h:480:28: note:   no known conversion for argument 1 from 'std::_Bind_helper<false, void (WallFollower::*)(const std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> >&), WallFollower*, const std::_Placeholder<1>&>::type' {aka 'std::_Bind<void (WallFollower::*(WallFollower*, std::_Placeholder<1>))(const std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> >&)>'} to 'std::function<void(std::shared_future<std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> > >)>&&'
  480 |       operator=(function&& __x) noexcept
      |                 ~~~~~~~~~~~^~~
/usr/include/c++/9/bits/std_function.h:494:7: note: candidate: 'std::function<_Res(_ArgTypes ...)>& std::function<_Res(_ArgTypes ...)>::operator=(std::nullptr_t) [with _Res = void; _ArgTypes = {std::shared_future<std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> > >}; std::nullptr_t = std::nullptr_t]'
  494 |       operator=(nullptr_t) noexcept
      |       ^~~~~~~~
/usr/include/c++/9/bits/std_function.h:494:17: note:   no known conversion for argument 1 from 'std::_Bind_helper<false, void (WallFollower::*)(const std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> >&), WallFollower*, const std::_Placeholder<1>&>::type' {aka 'std::_Bind<void (WallFollower::*(WallFollower*, std::_Placeholder<1>))(const std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> >&)>'} to 'std::nullptr_t'
  494 |       operator=(nullptr_t) noexcept
      |                 ^~~~~~~~~
/usr/include/c++/9/bits/std_function.h:523:2: note: candidate: 'template<class _Functor> std::function<_Res(_ArgTypes ...)>::_Requires<std::function<_Res(_ArgTypes ...)>::_Callable<typename std::decay<_Functor>::type>, std::function<_Res(_ArgTypes ...)>&> std::function<_Res(_ArgTypes ...)>::operator=(_Functor&&) [with _Functor = _Functor; _Res = void; _ArgTypes = {std::shared_future<std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> > >}]'
  523 |  operator=(_Functor&& __f)
      |  ^~~~~~~~
/usr/include/c++/9/bits/std_function.h:523:2: note:   template argument deduction/substitution failed:
/usr/include/c++/9/bits/std_function.h: In substitution of 'template<class _Res, class ... _ArgTypes> template<class _Cond, class _Tp> using _Requires = typename std::enable_if<_Cond::value, _Tp>::type [with _Cond = std::function<void(std::shared_future<std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> > >)>::_Callable<std::_Bind<void (WallFollower::*(WallFollower*, std::_Placeholder<1>))(const std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> >&)>, std::__invoke_result<std::_Bind<void (WallFollower::*(WallFollower*, std::_Placeholder<1>))(const std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> >&)>&, std::shared_future<std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> > > > >; _Tp = std::function<void(std::shared_future<std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> > >)>&; _Res = void; _ArgTypes = {std::shared_future<std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> > >}]':
/usr/include/c++/9/bits/std_function.h:523:2:   required by substitution of 'template<class _Functor> std::function<void(std::shared_future<std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> > >)>::_Requires<std::function<void(std::shared_future<std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> > >)>::_Callable<typename std::decay<_Tp>::type, std::__invoke_result<typename std::decay<_Tp>::type&, std::shared_future<std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> > > > >, std::function<void(std::shared_future<std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> > >)>&> std::function<void(std::shared_future<std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> > >)>::operator=<_Functor>(_Functor&&) [with _Functor = std::_Bind<void (WallFollower::*(WallFollower*, std::_Placeholder<1>))(const std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> >&)>]'
/home/user/ros2_ws/src/Wall Follower/wall_follower/src/wall_follower_part3.cpp:119:66:   required from here
/usr/include/c++/9/bits/std_function.h:385:8: error: no type named 'type' in 'struct std::enable_if<false, std::function<void(std::shared_future<std::shared_ptr<rclcpp_action::ClientGoalHandle<custom_interfaces::action::OdomRecord> > >)>&>'
  385 |  using _Requires = typename enable_if<_Cond::value, _Tp>::type;

It continues with:

/opt/ros/foxy/include/rclcpp/any_subscription_callback.hpp: In instantiation of 'void rclcpp::AnySubscriptionCallback<MessageT, Alloc>::set(CallbackT) [with CallbackT = std::_Bind<void (WallFollower::*(WallFollower*, std::_Placeholder<7>))(std::shared_ptr<nav_msgs::msg::Odometry_<std::allocator<void> > >)>; typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, std::function<void(std::shared_ptr<_Tp>)> >::value>::type* <anonymous> = 0; MessageT = nav_msgs::msg::Odometry_<std::allocator<void> >; Alloc = std::allocator<void>]':
/opt/ros/foxy/include/rclcpp/subscription_factory.hpp:97:3:   required from 'rclcpp::SubscriptionFactory rclcpp::create_subscription_factory(CallbackT&&,const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>&, typename MessageMemoryStrategyT::SharedPtr, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<CallbackMessageT> >) [with MessageT = nav_msgs::msg::Odometry_<std::allocator<void> >; CallbackT = std::_Bind<void (WallFollower::*(WallFollower*, std::_Placeholder<7>))(std::shared_ptr<nav_msgs::msg::Odometry_<std::allocator<void> > >)>; AllocatorT = std::allocator<void>; CallbackMessageT = nav_msgs::msg::Odometry_<std::allocator<void> >; SubscriptionT = rclcpp::Subscription<nav_msgs::msg::Odometry_<std::allocator<void> > >; MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<nav_msgs::msg::Odometry_<std::allocator<void> >, std::allocator<void> >; typename MessageMemoryStrategyT::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<nav_msgs::msg::Odometry_<std::allocator<void> >, std::allocator<void> > >]'
/opt/ros/foxy/include/rclcpp/create_subscription.hpp:144:63:   required from 'std::shared_ptr<SubscriptionT> rclcpp::create_subscription(NodeT&&, const string&, const rclcpp::QoS&, CallbackT&&, const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>&, typename MessageMemoryStrategyT::SharedPtr) [with MessageT = nav_msgs::msg::Odometry_<std::allocator<void> >; CallbackT = std::_Bind<void (WallFollower::*(WallFollower*, std::_Placeholder<7>))(std::shared_ptr<nav_msgs::msg::Odometry_<std::allocator<void> > >)>; AllocatorT = std::allocator<void>; CallbackMessageT = nav_msgs::msg::Odometry_<std::allocator<void> >; SubscriptionT = rclcpp::Subscription<nav_msgs::msg::Odometry_<std::allocator<void> > >; MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<nav_msgs::msg::Odometry_<std::allocator<void> >, std::allocator<void> >; NodeT = rclcpp::Node&; std::string = std::__cxx11::basic_string<char>; typename MessageMemoryStrategyT::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<nav_msgs::msg::Odometry_<std::allocator<void> >, std::allocator<void> > >]'
/opt/ros/foxy/include/rclcpp/node_impl.hpp:98:47:   required from 'std::shared_ptr<SubscriptionT> rclcpp::Node::create_subscription(const string&, const rclcpp::QoS&, CallbackT&&, const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>&, typename MessageMemoryStrategyT::SharedPtr) [with MessageT = nav_msgs::msg::Odometry_<std::allocator<void> >; CallbackT = std::_Bind<void (WallFollower::*(WallFollower*, std::_Placeholder<7>))(std::shared_ptr<nav_msgs::msg::Odometry_<std::allocator<void> > >)>; AllocatorT = std::allocator<void>; CallbackMessageT = nav_msgs::msg::Odometry_<std::allocator<void> >; SubscriptionT = rclcpp::Subscription<nav_msgs::msg::Odometry_<std::allocator<void> > >; MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<nav_msgs::msg::Odometry_<std::allocator<void> >, std::allocator<void> >; std::string = std::__cxx11::basic_string<char>; typename MessageMemoryStrategyT::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<nav_msgs::msg::Odometry_<std::allocator<void> >, std::allocator<void> > >]'
/home/user/ros2_ws/src/Wall Follower/wall_follower/src/wall_follower_part3.cpp:62:89:   required from here
/usr/include/c++/9/bits/std_function.h:532:2: note: candidate: 'template<class _Functor> std::function<_Res(_ArgTypes ...)>& std::function<_Res(_ArgTypes...)>::operator=(std::reference_wrapper<_Functor>) [with _Functor = _Functor; _Res = void; _ArgTypes = {std::shared_ptr<nav_msgs::msg::Odometry_<std::allocator<void> > >}]'
  532 |  operator=(reference_wrapper<_Functor> __f) noexcept
      |  ^~~~~~~~
/usr/include/c++/9/bits/std_function.h:532:2: note:   template argument deduction/substitution failed:
In file included from /opt/ros/foxy/include/rclcpp/subscription_base.hpp:29,
                 from /opt/ros/foxy/include/rclcpp/callback_group.hpp:26,
                 from /opt/ros/foxy/include/rclcpp/any_executable.hpp:20,
                 from /opt/ros/foxy/include/rclcpp/memory_strategy.hpp:24,
                 from /opt/ros/foxy/include/rclcpp/memory_strategies.hpp:18,
                 from /opt/ros/foxy/include/rclcpp/executor_options.hpp:20,
                 from /opt/ros/foxy/include/rclcpp/executor.hpp:33,
                 from /opt/ros/foxy/include/rclcpp/executors/multi_threaded_executor.hpp:26,
                 from /opt/ros/foxy/include/rclcpp/executors.hpp:21,
                 from /opt/ros/foxy/include/rclcpp/rclcpp.hpp:146,
                 from /home/user/ros2_ws/src/Wall Follower/wall_follower/src/wall_follower_part3.cpp:5:
/opt/ros/foxy/include/rclcpp/any_subscription_callback.hpp:85:26: note:   'std::_Bind<void (WallFollower::*(WallFollower*, std::_Placeholder<7>))(std::shared_ptr<nav_msgs::msg::Odometry_<std::allocator<void> > >)>' is not derived from 'std::reference_wrapper<_Tp>'
   85 |     shared_ptr_callback_ = callback;
      |     ~~~~~~~~~~~~~~~~~~~~~^~~~~~~~~~
/opt/ros/foxy/include/rclcpp/any_subscription_callback.hpp: In instantiation of 'void rclcpp::AnySubscriptionCallback<MessageT, Alloc>::set(CallbackT) [with CallbackT = std::_Bind<void (WallFollower::*(WallFollower*, std::_Placeholder<7>))(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> >>)>; typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, std::function<void(std::shared_ptr<_Tp>)> >::value>::type* <anonymous> = 0; MessageT = sensor_msgs::msg::LaserScan_<std::allocator<void> >; Alloc = std::allocator<void>]':
/opt/ros/foxy/include/rclcpp/subscription_factory.hpp:97:3:   required from 'rclcpp::SubscriptionFactory rclcpp::create_subscription_factory(CallbackT&&,const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>&, typename MessageMemoryStrategyT::SharedPtr, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<CallbackMessageT> >) [with MessageT = sensor_msgs::msg::LaserScan_<std::allocator<void> >; CallbackT = std::_Bind<void (WallFollower::*(WallFollower*, std::_Placeholder<7>))(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > >)>; AllocatorT = std::allocator<void>; CallbackMessageT = sensor_msgs::msg::LaserScan_<std::allocator<void> >; SubscriptionT = rclcpp::Subscription<sensor_msgs::msg::LaserScan_<std::allocator<void>> >; MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<sensor_msgs::msg::LaserScan_<std::allocator<void> >, std::allocator<void> >; typename MessageMemoryStrategyT::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<sensor_msgs::msg::LaserScan_<std::allocator<void> >, std::allocator<void> > >]'
/opt/ros/foxy/include/rclcpp/create_subscription.hpp:144:63:   required from 'std::shared_ptr<SubscriptionT> rclcpp::create_subscription(NodeT&&, const string&, const rclcpp::QoS&, CallbackT&&, const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>&, typename MessageMemoryStrategyT::SharedPtr) [with MessageT = sensor_msgs::msg::LaserScan_<std::allocator<void> >; CallbackT = std::_Bind<void (WallFollower::*(WallFollower*, std::_Placeholder<7>))(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > >)>; AllocatorT = std::allocator<void>; CallbackMessageT = sensor_msgs::msg::LaserScan_<std::allocator<void> >; SubscriptionT = rclcpp::Subscription<sensor_msgs::msg::LaserScan_<std::allocator<void> > >; MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<sensor_msgs::msg::LaserScan_<std::allocator<void> >, std::allocator<void> >; NodeT = rclcpp::Node&; std::string = std::__cxx11::basic_string<char>; typename MessageMemoryStrategyT::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<sensor_msgs::msg::LaserScan_<std::allocator<void> >, std::allocator<void> > >]'
/opt/ros/foxy/include/rclcpp/node_impl.hpp:98:47:   required from 'std::shared_ptr<SubscriptionT> rclcpp::Node::create_subscription(const string&, const rclcpp::QoS&, CallbackT&&, const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>&, typename MessageMemoryStrategyT::SharedPtr) [with MessageT = sensor_msgs::msg::LaserScan_<std::allocator<void> >; CallbackT = std::_Bind<void (WallFollower::*(WallFollower*, std::_Placeholder<7>))(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > >)>; AllocatorT = std::allocator<void>; CallbackMessageT = sensor_msgs::msg::LaserScan_<std::allocator<void> >; SubscriptionT = rclcpp::Subscription<sensor_msgs::msg::LaserScan_<std::allocator<void> > >; MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<sensor_msgs::msg::LaserScan_<std::allocator<void> >, std::allocator<void> >; std::string = std::__cxx11::basic_string<char>; typenameMessageMemoryStrategyT::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<sensor_msgs::msg::LaserScan_<std::allocator<void> >, std::allocator<void> > >]'

Hi @w.ronaldo.cd ,

Here is a simple trick to understand long error outputs: It is usually the reference to the first line of error that has the actual bug. The remaining errors are caused because of the first error.

In your case, The first error is this part:

The other error outputs are just irrelevant and will just make you nervous. So don’t panic!

So the error says operator mismatch in the line:
std::bind(&WallFollower::goal_response_callback, this, _1);.

I know exactly, why you are getting this error.
Reason: The rosject uses Foxy as ROS2 version while You have learned ROS2 Basics with Humble.
There was a major syntax difference in Goal Response Callback function.
So the error is not in the reported line but the function itself!
Handling these errors requires some finesse which you will develop as you code.

ROS2 Foxy GoalResponseCallback:

void goal_response_callback(std::shared_future<GoalHandleOdomRecord::SharedPtr> future)
{
    // ...
}

ROS2 Humble GoalResponseCallback:

void goal_response_callback(const GoalHandleOdomRecord::SharedPtr & goal_handle)
{
    // ...
}

Do you notice the function definition difference here?

So just use the Foxy version’s definition in your Rosject. This will fix your issue.

Sorry, I could not identify this error earlier. My bad. Thanks for your patience. Much appreciated!

Let me know if this gets your problem fixed. I believe this should get your issue fixed.

Regards,
Girish

Thank you, it worked.

Best Regards

This topic was automatically closed 5 days after the last reply. New replies are no longer allowed.