在ROS 2(Robot Operating System 2)中,Action是一种强大的通信机制,特别适用于需要长时间运行且需要定期反馈的任务。Action结合了话题(Topic)和服务(Service)的特性,提供了一个更加灵活和强大的方式来控制和管理机器人的复杂行为。
Action由三个主要部分组成:
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的组成。
class FibonacciActionClient : public rclcpp::Node { public: using Fibonacci = action_tutorials_interfaces::action::Fibonacci; using GoalHandleFibonacci = rclcpp_action::ClientGoalHandle; 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( 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::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 sequence; }; struct Fibonacci_Feedback { sequence 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文件构建。
auto send_goal_options = rclcpp_action::Client::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; }; 我们看下这三个回调的实现
当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"); } }; 在任务处理的过程中,服务端不断向客户端发送Feedback,用于告知任务处理的当前状态。客户端就会通过该回调来接收服务端的响应。
FeedbackCallback有两个参数:
本例中它返回了当前服务端计算出来的斐波那契数列的值。
send_goal_options.feedback_callback = [this]( GoalHandleFibonacci::SharedPtr, const std::shared_ptr 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(); }; ResultCallback的参数WrappedResult 结构如下。它包含了Fibonacci::Result的智能指针,还有代表最终处理结果的ResultCode。
template 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 #include #include #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; 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( 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::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 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::SharedPtr client_ptr_; rclcpp::TimerBase::SharedPtr timer_; }; // class FibonacciActionClient } // namespace action_tutorials_cpp RCLCPP_COMPONENTS_REGISTER_NODE(action_tutorials_cpp::FibonacciActionClient)