ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

[ROS2 Foxy] rclcpp_action "no match for ‘operator=’ "

asked 2021-03-12 01:26:18 -0500

Hystersis gravatar image

Greetings,

I'm trying to write an action client that sends poses to the Navigation Stack 2, to the TurtleBot3. In doing so, I have tried to follow the tutorial in the documentation: https://docs.ros.org/en/foxy/Tutorial...

Meanwhile, the TurtleBot3's instructions can be found on this page. https://navigation.ros.org/getting_st...

Adapting the code however, poses a few problems. I think the core of it stems from this type mismatch:

error: no match for ‘operator=’ (operand types are ‘rclcpp_action::Client<nav2_msgs::action::NavigateToPose>::GoalResponseCallback’ {aka ‘std::function<void(std::shared_future<std::shared_ptr<rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose> > >)>’} and ‘std::_Bind_helper<false, void (TurtleMover::*)(std::shared_future<rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose> >), TurtleMover*, const std::_Placeholder<1>&>::type’ {aka ‘std::_Bind<void (TurtleMover::*(TurtleMover*, std::_Placeholder<1>))(std::shared_future<rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose> >)>’}) 42 | send_goal_options.goal_response_callback = std::bind(&TurtleMover::goal_response_callback, this, std::placeholders::_1);

This occurs for all the function callbacks that I send to the SendGoalOptions().

Here is my attempted source code.

#include <functional>
#include <future>
#include <memory>
#include <thread>

#include <rclcpp/rclcpp.hpp>
#include <rclcpp_action/rclcpp_action.hpp>
#include <rclcpp_components/register_node_macro.hpp>

#include <std_msgs/msg/string.hpp>
#include <nav2_msgs/action/navigate_to_pose.hpp>

class TurtleMover : public rclcpp::Node
{
public:
  explicit TurtleMover(const rclcpp::NodeOptions & options) : Node("Turtle_Mover", options)
  {
    this->client_ptr_ = rclcpp_action::create_client<nav2_msgs::action::NavigateToPose>(this, "navigate_to_pose");
    this->timer_ = this->create_wall_timer(std::chrono::milliseconds(500), std::bind(&TurtleMover::send_goal, this));
  }

  void send_goal()
  {
    this->timer_->cancel();
    if(!this->client_ptr_->wait_for_action_server())
    {
      RCLCPP_ERROR(this->get_logger(), "Action server not available after waiting.");
      rclcpp::shutdown();
    }

    auto goal_msg = nav2_msgs::action::NavigateToPose::Goal();
    goal_msg.pose.header.frame_id = "map";
    //goal_msg.pose.header.stamp = rclcpp::Time::now();

    goal_msg.pose.pose.position.x = 0.0;
    goal_msg.pose.pose.position.y = 0.0;
    goal_msg.pose.pose.orientation.w = 1.0;

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

    auto send_goal_options = rclcpp_action::Client<nav2_msgs::action::NavigateToPose>::SendGoalOptions();
    send_goal_options.goal_response_callback = std::bind(&TurtleMover::goal_response_callback, this, std::placeholders::_1);
    send_goal_options.feedback_callback = std::bind(&TurtleMover::feedback_callback, this, std::placeholders::_1, std::placeholders::_2);
    send_goal_options.result_callback = std::bind(&TurtleMover::result_callback, this, std::placeholders::_1);

    this->client_ptr_->async_send_goal(goal_msg, send_goal_options);
  }

private:
  rclcpp_action::Client<nav2_msgs::action::NavigateToPose>::SharedPtr client_ptr_;
  rclcpp::TimerBase::SharedPtr timer_;

  void goal_response_callback(std::shared_future< rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose> > future)
  {
    auto goal_handle = future.get();
    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(rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose>::SharedPtr, const std::shared_ptr<const nav2_msgs::action::NavigateToPose::Feedback> feedback)
  {
    auto distance_feedback_msg = std_msgs::msg::String();
    distance_feedback_msg.data = "Remaining Distance from Destination: " + std::to_string(feedback->distance_remaining);
    RCLCPP_INFO(this->get_logger(), distance_feedback_msg.data);
  }

  void result_callback(rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose>::WrappedResult &result)
  {
    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::shutdown();
  }
};


RCLCPP_COMPONENTS_REGISTER_NODE(TurtleMover)

Here is my CMake list.

cmake_minimum_required(VERSION 3.5)
project(nav2_demo)

# Default to C99
if(NOT CMAKE_C_STANDARD)
  set(CMAKE_C_STANDARD 99)
endif()

# Default to C++14
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 dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
1

answered 2021-03-19 22:25:11 -0500

Hystersis gravatar image

Figured it out,

Turns out the argument in

void goal_response_callback(std::shared_future< rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose> > future)

Has to be

void goal_response_callback(std::shared_future< rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose::SharedPtr> > future)

Where after the action name, ::SharedPtr must be called.

Also in the CMake file, I omitted

add_executable(mover src/nav2_demo.cpp)
ament_target_dependencies(mover rclcpp rclcpp_action std_msgs nav2_msgs)

Otherwise, there is an undefined reference to main.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2021-03-12 01:26:18 -0500

Seen: 2,424 times

Last updated: Mar 19 '21