Robot Operating System——Action通信机制概念及Client端

在ROS 2(Robot Operating System 2)中,Action是一种强大的通信机制,特别适用于需要长时间运行且需要定期反馈的任务。Action结合了话题(Topic)和服务(Service)的特性,提供了一个更加灵活和强大的方式来控制和管理机器人的复杂行为。

Action概念

组成

Action由三个主要部分组成:

  1. 目标(Goal):这是由Action客户端(Client)发送给Action服务器(Server)的请求,指示服务器需要执行的具体任务。例如,在控制一个机器人旋转的任务中,目标可能是指定机器人需要旋转的角度。
  2. 反馈(Feedback):在执行目标的过程中,Action服务器会定期向客户端发送反馈,以报告当前的执行状态和进度。这种反馈机制使得客户端能够实时了解任务的执行情况,并在必要时进行干预或调整。
  3. 结果(Result):当目标执行完成后,Action服务器会向客户端发送一个结果,表明任务的最终执行状态。这个结果可以是成功完成、失败或者部分完成等状态信息。

特点

  1. 可抢占性:与服务(Service)不同,Action是可抢占的。这意味着在执行过程中,客户端可以随时取消当前的目标,或者发送一个新的目标来覆盖旧的目标。这种特性使得Action在控制复杂机器人行为时更加灵活和可靠。
  2. 稳定的反馈:Action提供了持续的反馈机制,这使得客户端能够实时跟踪任务的执行情况。这种稳定的反馈不仅提高了系统的透明度和可控性,还使得客户端能够更好地适应任务执行过程中的变化。
  3. 长时间的运行:由于Action适用于长时间运行的任务,因此它非常适合用于控制需要较长时间才能完成的复杂机器人行为。例如,在导航、机械臂操作等场景中,Action都能够发挥重要作用。

使用场景

Action在机器人系统中有着广泛的应用场景,包括但不限于:

  1. 导航:机器人可以使用Action来发送导航指令,并实时接收路径规划的反馈。
  2. 物流自动驾驶:无人驾驶汽车或物流车可以使用Action来接收路径指令并执行。
  3. 人机交互:机器人可以通过Action来接收用户的指令和反馈,从而实现更加自然和流畅的交互体验。
  4. 复杂运动规划:机器人可以使用Action来发送运动指令,并在执行过程中接收运动的反馈,以实现精确和可靠的运动控制。

总之,ROS 2 Action是一种强大而灵活的通信机制,它为机器人系统的控制和管理提供了更加高效和可靠的方式。通过结合话题和服务的特性,Action能够实现对长时间运行任务的精确控制和实时反馈,从而推动机器人技术的进一步发展。

代码

我们通过action_tutorials/action_tutorials_cpp/src/fibonacci_action_server.cpp和action_tutorials/action_tutorials_cpp/src/fibonacci_action_client.cpp两个例子讲解Action服务端和客户端的编码实现。

客户端

客户端代码相对简单,我们可以从它先入手,讲解Action的组成。

构建rclcpp_action::Client

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

  ACTION_TUTORIALS_CPP_PUBLIC
  explicit FibonacciActionClient(const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions())
  : Node("fibonacci_action_client", node_options)
  {
    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),
      [this]() {return this->send_goal();});
  }
……

private:
  rclcpp_action::Client<Fibonacci>::SharedPtr client_ptr_;
  rclcpp::TimerBase::SharedPtr timer_;
};  // class FibonacciActionClient

首先我们需要一个rclcpp_action::Client对象,它的模板类是Fibonacci。

Fibonacci类是通过IDL文件(action_tutorials/install/action_tutorials_interfaces/share/action_tutorials_interfaces/action/Fibonacci.idl)生成的。通过下面这个结构,可以看到我们在“概念”一节中介绍的Goal、Feedback和Result三部分。

// generated from rosidl_adapter/resource/action.idl.em
// with input from action_tutorials_interfaces/action/Fibonacci.action
// generated code does not contain a copyright notice


module action_tutorials_interfaces {
  module action {
    struct Fibonacci_Goal {
      int32 order;
    };
    struct Fibonacci_Result {
      sequence<int32> sequence;
    };
    struct Fibonacci_Feedback {
      sequence<int32> partial_sequence;
    };
  };
};

而这个文件又是由Fibonacci.action文件(action_tutorials/install/action_tutorials_interfaces/share/action_tutorials_interfaces/action/Fibonacci.action)生成

int32 order
---
int32[] sequence
---
int32[] partial_sequence

准备好基本框架后,我们就要看主要逻辑——定时器具体执行了什么?

进入定时器后,我们先终止该定时器后续再次执行。这是因为后续设置逻辑只要执行一次即可。

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

    this->timer_->cancel();

等待和服务端的连接

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

构建目标任务

    auto goal_msg = Fibonacci::Goal();
    goal_msg.order = 10;

Fibonacci::Goal也是由上述idl文件构建。

构建SendGoalOptions

    auto send_goal_options = rclcpp_action::Client<Fibonacci>::SendGoalOptions();

SendGoalOptions是由三个回调函数构成

  struct SendGoalOptions
  {
    SendGoalOptions()
    : goal_response_callback(nullptr),
      feedback_callback(nullptr),
      result_callback(nullptr)
    {
    }

    /// Function called when the goal is accepted or rejected.
    /**
     * Takes a single argument that is a goal handle shared pointer.
     * If the goal is accepted, then the pointer points to a valid goal handle.
     * If the goal is rejected, then pointer has the value `nullptr`.
     */
    GoalResponseCallback goal_response_callback;

    /// Function called whenever feedback is received for the goal.
    FeedbackCallback feedback_callback;

    /// Function called when the result for the goal is received.
    ResultCallback result_callback;
  };

我们看下这三个回调的实现

GoalResponseCallback

当Action客户端向服务端发送请求后,服务端会返回“接收”或者“拒绝”该请求,这个时候客户端的这个函数就会被调用。

如果服务端接收了该请求,则goal_handle非空;否则就是nullptr。

    send_goal_options.goal_response_callback = [this](
      const GoalHandleFibonacci::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");
        }
      };
FeedbackCallback

在任务处理的过程中,服务端不断向客户端发送Feedback,用于告知任务处理的当前状态。客户端就会通过该回调来接收服务端的响应。

FeedbackCallback有两个参数:

  1. GoalHandleFibonacci::SharedPtr和GoalResponseCallback回调中的参数一样。
  2. Fibonacci::Feedback是之前介绍的IDL文件生成的。它用来承载任务中间状态。

本例中它返回了当前服务端计算出来的斐波那契数列的值。

    send_goal_options.feedback_callback = [this](
      GoalHandleFibonacci::SharedPtr,
      const std::shared_ptr<const Fibonacci::Feedback> feedback)
      {
        std::stringstream ss;
        ss << "Next number in sequence received: ";
        for (auto number : feedback->partial_sequence) {
          ss << number << " ";
        }
        RCLCPP_INFO(this->get_logger(), "%s", ss.str().c_str());
      };
ResultCallback

当服务端的任务处理完毕,会向客户端发送结果。客户端就是通过这个回调来接收服务端的响应。

    send_goal_options.result_callback = [this](
      const GoalHandleFibonacci::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;
        }
        std::stringstream ss;
        ss << "Result received: ";
        for (auto number : result.result->sequence) {
          ss << number << " ";
        }
        RCLCPP_INFO(this->get_logger(), "%s", ss.str().c_str());
        rclcpp::shutdown();
      };

ResultCallback的参数WrappedResult 结构如下。它包含了Fibonacci::Result的智能指针,还有代表最终处理结果的ResultCode。

template<typename ActionT>
class ClientGoalHandle
{
public:
  RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(ClientGoalHandle)

  // A wrapper that defines the result of an action
  struct WrappedResult
  {
    /// The unique identifier of the goal
    GoalUUID goal_id;
    /// A status to indicate if the goal was canceled, aborted, or suceeded
    ResultCode code;
    /// User defined fields sent back with an action
    typename ActionT::Result::SharedPtr result;
  };

发送请求

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

至此,客户端的整个流程走完了。

后续的逻辑主要执行于上述的几个回调函数中。

完整代码

// Copyright 2019 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <memory>
#include <string>
#include <sstream>

#include "action_tutorials_interfaces/action/fibonacci.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "rclcpp_components/register_node_macro.hpp"

#include "action_tutorials_cpp/visibility_control.h"

namespace action_tutorials_cpp
{
class FibonacciActionClient : public rclcpp::Node
{
public:
  using Fibonacci = action_tutorials_interfaces::action::Fibonacci;
  using GoalHandleFibonacci = rclcpp_action::ClientGoalHandle<Fibonacci>;

  ACTION_TUTORIALS_CPP_PUBLIC
  explicit FibonacciActionClient(const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions())
  : Node("fibonacci_action_client", node_options)
  {
    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),
      [this]() {return this->send_goal();});
  }

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

    this->timer_->cancel();

    if (!this->client_ptr_->wait_for_action_server(std::chrono::seconds(10))) {
      RCLCPP_ERROR(this->get_logger(), "Action server not available after waiting");
      rclcpp::shutdown();
      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 = [this](
      const GoalHandleFibonacci::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");
        }
      };

    send_goal_options.feedback_callback = [this](
      GoalHandleFibonacci::SharedPtr,
      const std::shared_ptr<const Fibonacci::Feedback> feedback)
      {
        std::stringstream ss;
        ss << "Next number in sequence received: ";
        for (auto number : feedback->partial_sequence) {
          ss << number << " ";
        }
        RCLCPP_INFO(this->get_logger(), "%s", ss.str().c_str());
      };

    send_goal_options.result_callback = [this](
      const GoalHandleFibonacci::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;
        }
        std::stringstream ss;
        ss << "Result received: ";
        for (auto number : result.result->sequence) {
          ss << number << " ";
        }
        RCLCPP_INFO(this->get_logger(), "%s", ss.str().c_str());
        rclcpp::shutdown();
      };

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

private:
  rclcpp_action::Client<Fibonacci>::SharedPtr client_ptr_;
  rclcpp::TimerBase::SharedPtr timer_;
};  // class FibonacciActionClient

}  // namespace action_tutorials_cpp

RCLCPP_COMPONENTS_REGISTER_NODE(action_tutorials_cpp::FibonacciActionClient)
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

breaksoftware

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值