机器人多节点动作通信编程方法

描述

编程方法

相比之前话题和服务的程序,动作通信的例程相对较长,我们一起来运行并分析一下。

运行示例程序

程序

$ source /opt/tros/local_setup.bash
$ source install/local_setup.bash
$ ros2 run learning_action_cpp server 
$ ros2 run learning_action_cpp client

代码解析

动作的服务器fibonacci_action_server.cpp:

#include < inttypes.h >
#include < memory >
#include "learning_action_cpp/action/fibonacci.hpp"
#include "rclcpp/rclcpp.hpp"
// TODO(jacobperron): Remove this once it is included as part of 'rclcpp.hpp'
#include "rclcpp_action/rclcpp_action.hpp"


class MinimalActionServer : public rclcpp::Node
{
public:
  using Fibonacci = learning_action_cpp::action::Fibonacci;
  using GoalHandleFibonacci = rclcpp_action::ServerGoalHandle< Fibonacci >;


  explicit MinimalActionServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions())
  : Node("minimal_action_server", options)
{
    using namespace std::placeholders;


    this- >action_server_ = rclcpp_action::create_server< Fibonacci >(
      this- >get_node_base_interface(),
      this- >get_node_clock_interface(),
      this- >get_node_logging_interface(),
      this- >get_node_waitables_interface(),
      "fibonacci",
      std::bind(&MinimalActionServer::handle_goal, this, _1, _2),
      std::bind(&MinimalActionServer::handle_cancel, this, _1),
      std::bind(&MinimalActionServer::handle_accepted, this, _1));
  }


private:
  rclcpp_action::Server< Fibonacci >::SharedPtr action_server_;


  rclcpp_action::GoalResponse handle_goal(
    const rclcpp_action::GoalUUID & uuid,
    std::shared_ptr< const Fibonacci::Goal > goal)
{
    RCLCPP_INFO(this- >get_logger(), "Received goal request with order %d", goal- >order);
    (void)uuid;
    // Let's reject sequences that are over 9000
    if (goal- >order > 9000) {
      return rclcpp_action::GoalResponse::REJECT;
    }
    return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
  }


  rclcpp_action::CancelResponse handle_cancel(
    const std::shared_ptr< GoalHandleFibonacci > goal_handle)
{
    RCLCPP_INFO(this- >get_logger(), "Received request to cancel goal");
    (void)goal_handle;
    return rclcpp_action::CancelResponse::ACCEPT;
  }


  void execute(const std::shared_ptr< GoalHandleFibonacci > goal_handle)
{
    RCLCPP_INFO(this- >get_logger(), "Executing goal");
    rclcpp::Rate loop_rate(1);
    const auto goal = goal_handle- >get_goal();
    auto feedback = std::make_shared< Fibonacci::Feedback >();
    auto & sequence = feedback- >sequence;
    sequence.push_back(0);
    sequence.push_back(1);
    auto result = std::make_shared< Fibonacci::Result >();


    for (int i = 1; (i < goal- >order) && rclcpp::ok(); ++i) {
      // Check if there is a cancel request
      if (goal_handle- >is_canceling()) {
        result- >sequence = sequence;
        goal_handle- >canceled(result);
        RCLCPP_INFO(this- >get_logger(), "Goal Canceled");
        return;
      }
      // Update sequence
      sequence.push_back(sequence[i] + sequence[i - 1]);
      // Publish feedback
      goal_handle- >publish_feedback(feedback);
      RCLCPP_INFO(this- >get_logger(), "Publish Feedback");


      loop_rate.sleep();
    }


    // Check if goal is done
    if (rclcpp::ok()) {
      result- >sequence = sequence;
      goal_handle- >succeed(result);
      RCLCPP_INFO(this- >get_logger(), "Goal Succeeded");
    }
  }


  void handle_accepted(const std::shared_ptr< GoalHandleFibonacci > goal_handle)
{
    using namespace std::placeholders;
    // this needs to return quickly to avoid blocking the executor, so spin up a new thread
    std::thread{std::bind(&MinimalActionServer::execute, this, _1), goal_handle}.detach();
  }
};  // class MinimalActionServer


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


  auto action_server = std::make_shared< MinimalActionServer >();


  rclcpp::spin(action_server);


  rclcpp::shutdown();
  return 0;
}

动作的客户端fibonacci_action_client.cpp:

#include < inttypes.h >
#include < memory >
#include < string >
#include < iostream >
#include "learning_action_cpp/action/fibonacci.hpp"
#include "rclcpp/rclcpp.hpp"
// TODO(jacobperron): Remove this once it is included as part of 'rclcpp.hpp'
#include "rclcpp_action/rclcpp_action.hpp"


class MinimalActionClient : public rclcpp::Node
{
public:
  using Fibonacci = learning_action_cpp::action::Fibonacci;
  using GoalHandleFibonacci = rclcpp_action::ClientGoalHandle< Fibonacci >;


  explicit MinimalActionClient(const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions())
  : Node("minimal_action_client", node_options), goal_done_(false)
{
    this- >client_ptr_ = rclcpp_action::create_client< Fibonacci >(
      this- >get_node_base_interface(),
      this- >get_node_graph_interface(),
      this- >get_node_logging_interface(),
      this- >get_node_waitables_interface(),
      "fibonacci");


    this- >timer_ = this- >create_wall_timer(
      std::chrono::milliseconds(500),
      std::bind(&MinimalActionClient::send_goal, this));
  }


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


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


    this- >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 = Fibonacci::Goal();
    goal_msg.order = 10;


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


    auto send_goal_options = rclcpp_action::Client< Fibonacci >::SendGoalOptions();
    send_goal_options.goal_response_callback =
      std::bind(&MinimalActionClient::goal_response_callback, this, _1);
    send_goal_options.feedback_callback =
      std::bind(&MinimalActionClient::feedback_callback, this, _1, _2);
    send_goal_options.result_callback =
      std::bind(&MinimalActionClient::result_callback, this, _1);
    auto goal_handle_future = this- >client_ptr_- >async_send_goal(goal_msg, send_goal_options);
  }


private:
  rclcpp_action::Client< Fibonacci >::SharedPtr client_ptr_;
  rclcpp::TimerBase::SharedPtr timer_;
  bool goal_done_;


  void goal_response_callback(std::shared_future< GoalHandleFibonacci::SharedPtr > 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(
    GoalHandleFibonacci::SharedPtr,
    const std::shared_ptr< const Fibonacci::Feedback > feedback)
{
    RCLCPP_INFO(
      this- >get_logger(),
      "Next number in sequence received: %" PRId32,
      feedback- >sequence.back());
  }


  void result_callback(const GoalHandleFibonacci::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");
    for (auto number : result.result- >sequence) {
      RCLCPP_INFO(this- >get_logger(), "%" PRId32, number);
    }
  }
};  // class MinimalActionClient


int main(int argc, char ** argv)
{
  rclcpp::init(argc, argv);
  auto action_client = std::make_shared< MinimalActionClient >();


  while (!action_client- >is_goal_done()) {
    rclcpp::spin_some(action_client);
  }


  rclcpp::shutdown();
  return 0;
}
打开APP阅读更多精彩内容
声明:本文内容及配图由入驻作者撰写或者入驻合作网站授权转载。文章观点仅代表作者本人,不代表电子发烧友网立场。文章及其配图仅供工程师学习之用,如有内容侵权或者其他违规问题,请联系本站处理。 举报投诉

全部0条评论

快来发表一下你的评论吧 !

×
20
完善资料,
赚取积分