1 action介紹
ROS通信機制也會被常常用到——那就是動作。從這個名字上就可以很好理解這個概念的含義,這種通信機制的目的就是便于對機器人某一完整行為的流程進行管理。
1.1 客戶端/服務器模型
動作和服務類似,使用的也是客戶端和服務器模型,客戶端發送動作的目標,想讓機器人干什么,服務器端執行動作過程, 控制機器人達到運動的目標,同時周期反饋動作執行過程中的狀態。
客戶端發送一個運動的目標,想讓機器人動起來,服務器端收到之后,就開始控制機器人運動,一邊運動,一邊反饋當前的狀態,如果是一個導航動作,這個反饋可能是當前所處的坐標,如果是機械臂抓取,這個反饋可能又是機械臂的實時姿態。當運動執行結束后,服務器再反饋一個動作結束的信息。整個通信過程就此結束。
1.2 action通信特點
-
一對多通信
和服務一樣,動作通信中的客戶端可以有多個,大家都可以發送運動命令,但是服務器端只能有一個,畢竟只有一個機器人,先執行完成一個動作,才能執行下一個動作。 -
同步通信
既然有反饋,那動作也是一種同步通信機制,之前我們也介紹過,動作過程中的數據通信接口,使用.action文件進行定義。 -
由服務和話題合成
大家再仔細看下上邊的動圖,是不是還會發現一個隱藏的秘密。
動作的三個通信模塊,竟然有兩個是服務,一個是話題,當客戶端發送運動目標時,使用的是服務的請求調用,服務器端也會反饋一個應帶,表示收到命令。動作的反饋過程,其實就是一個話題的周期發布,服務器端是發布者,客戶端是訂閱者。
沒錯,動作是一種應用層的通信機制,其底層就是基于話題和服務來實現的。
2 action自定義通信接口
延續上一講[ROS2] — action,中創建的自定義接口功能包,在src目錄下創建action/Concatenate.action文件
Concatenate.action
int16 num_concatenations
---
string final_concatenation
---
string partial_concatenation
3 action編碼示例
這里創建功能包名為,learning04_action
3.1 class_action_client.cpp
/*** @file class_action_client.cpp** @brief A class defined ROS2 action client node that sends as goal the number of string* concatenation the action server should perform. * The server will send back feedbacks and the final result** @author Antonio Mauro Galiano* Contact: https://www.linkedin.com/in/antoniomaurogaliano/**/#include "custom_interface/action/concatenate.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"class ConcatenateActionClient : public rclcpp::Node
{
public:using Concatenate = custom_interface::action::Concatenate;using GoalHandleConcatenate = rclcpp_action::ClientGoalHandle<Concatenate>;explicit ConcatenateActionClient(const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions()): Node("class_action_client", node_options), goalDone_(false){this->clientPtr_ = rclcpp_action::create_client<Concatenate>(this->get_node_base_interface(),this->get_node_graph_interface(),this->get_node_logging_interface(),this->get_node_waitables_interface(),"concatenation");this->timer_ = this->create_wall_timer(std::chrono::milliseconds(500),std::bind(&ConcatenateActionClient::SendGoal, this));}bool GoalDone() const;void SendGoal();private:rclcpp_action::Client<Concatenate>::SharedPtr clientPtr_;rclcpp::TimerBase::SharedPtr timer_;bool goalDone_;void FeedbackCallback(GoalHandleConcatenate::SharedPtr,const std::shared_ptr<const Concatenate::Feedback> feedback);void ResultCallback(const GoalHandleConcatenate::WrappedResult & result);// be sure to define the parameter as it's here// more info at the declarationvoid GoalResponseCallback(const GoalHandleConcatenate::SharedPtr &goalHandle);
};bool ConcatenateActionClient::GoalDone() const
{return this->goalDone_;
}void ConcatenateActionClient::SendGoal()
{using namespace std::placeholders;this->timer_->cancel();this->goalDone_ = false;if (!this->clientPtr_){RCLCPP_ERROR(this->get_logger(), "Action client not initialized");}if (!this->clientPtr_->wait_for_action_server(std::chrono::seconds(10))){RCLCPP_ERROR(this->get_logger(), "!!ATTENTION!! Action server not available");this->goalDone_ = true;return;}auto goalMsg = Concatenate::Goal();goalMsg.num_concatenations = 9;RCLCPP_INFO(this->get_logger(), "Sending goal");auto send_goal_options = rclcpp_action::Client<Concatenate>::SendGoalOptions();send_goal_options.feedback_callback =std::bind(&ConcatenateActionClient::FeedbackCallback, this, _1, _2);send_goal_options.result_callback =std::bind(&ConcatenateActionClient::ResultCallback, this, _1);// send_goal_options.goal_response_callback =// std::bind(&ConcatenateActionClient::GoalResponseCallback, this, _1);auto goal_handle_future = this->clientPtr_->async_send_goal(goalMsg, send_goal_options);
}void ConcatenateActionClient::FeedbackCallback(rclcpp_action::ClientGoalHandle<Concatenate>::SharedPtr,const std::shared_ptr<const Concatenate::Feedback> feedback)
{RCLCPP_INFO(this->get_logger(),"Feedback received: %s",feedback->partial_concatenation.c_str());
}void ConcatenateActionClient::ResultCallback(const GoalHandleConcatenate::WrappedResult & result)
{this->goalDone_ = 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->final_concatenation){RCLCPP_INFO(this->get_logger(), "%d", number);}
}// defining the parameter directly as a GoalHandleConcatenate::SharedPtr goalHandle
// it's wrong for the send_goal_options.goal_response_callback
// so it doesnt compile
void ConcatenateActionClient::GoalResponseCallback(const GoalHandleConcatenate::SharedPtr &goalHandle){if (!goalHandle){RCLCPP_ERROR(this->get_logger(), "Goal was rejected by server");} else{RCLCPP_INFO(this->get_logger(), "Goal accepted by server, waiting for result");}}int main(int argc, char ** argv)
{rclcpp::init(argc, argv);auto action_client = std::make_shared<ConcatenateActionClient>();while (!action_client->GoalDone()){rclcpp::spin_some(action_client);}rclcpp::shutdown();return 0;
}
3.2 class_action_server.cpp
/*** @file class_action_server.cpp** @brief A class defined ROS2 action server node that concatenates a string * based on the number of string concatenation sent by a client within a goal request** @author Antonio Mauro Galiano* Contact: https://www.linkedin.com/in/antoniomaurogaliano/**/#include "custom_interface/action/concatenate.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"class ConcatenateActionServer : public rclcpp::Node
{
public:using Concatenate = custom_interface::action::Concatenate;using GoalHandleConcatenate = rclcpp_action::ServerGoalHandle<Concatenate>;explicit ConcatenateActionServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()): Node("class_action_server", options){using namespace std::placeholders;this->actionServer_ = rclcpp_action::create_server<Concatenate>(this->get_node_base_interface(),this->get_node_clock_interface(),this->get_node_logging_interface(),this->get_node_waitables_interface(),"concatenation",std::bind(&ConcatenateActionServer::HandleGoal, this, _1, _2),std::bind(&ConcatenateActionServer::HandleCancel, this, _1),std::bind(&ConcatenateActionServer::HandleAccepted, this, _1));}private:rclcpp_action::Server<Concatenate>::SharedPtr actionServer_;rclcpp_action::GoalResponse HandleGoal(const rclcpp_action::GoalUUID & uuid,std::shared_ptr<const Concatenate::Goal> goal);rclcpp_action::CancelResponse HandleCancel(const std::shared_ptr<GoalHandleConcatenate> goalHandle);void execute(const std::shared_ptr<GoalHandleConcatenate> goalHandle);void HandleAccepted(const std::shared_ptr<ConcatenateActionServer::GoalHandleConcatenate> goalHandle);
};rclcpp_action::GoalResponse ConcatenateActionServer::HandleGoal(const rclcpp_action::GoalUUID & uuid,std::shared_ptr<const Concatenate::Goal> goal)
{RCLCPP_INFO(rclcpp::get_logger("server"),"Got goal request with %d string concatenations",goal->num_concatenations);(void)uuid;// conditional to reject numbers of concatenationsif ((goal->num_concatenations > 10) && (goal->num_concatenations < 2)) {return rclcpp_action::GoalResponse::REJECT;}return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
}rclcpp_action::CancelResponse ConcatenateActionServer::HandleCancel(const std::shared_ptr<GoalHandleConcatenate> goalHandle)
{RCLCPP_INFO(rclcpp::get_logger("server"), "Got request to cancel goal");(void)goalHandle;return rclcpp_action::CancelResponse::ACCEPT;
}void ConcatenateActionServer::execute(const std::shared_ptr<GoalHandleConcatenate> goalHandle)
{RCLCPP_INFO(rclcpp::get_logger("server"), "Executing the concatenation");rclcpp::Rate loop_rate(1);const auto goal = goalHandle->get_goal();auto feedback = std::make_shared<Concatenate::Feedback>();std::string myString = "HELLOWORLD";auto &concatenation = feedback->partial_concatenation;concatenation = myString;concatenation = concatenation + " " + myString;auto result = std::make_shared<Concatenate::Result>();for (int i = 1; (i < goal->num_concatenations) && rclcpp::ok(); ++i){// check if there is a cancel requestif (goalHandle->is_canceling()){result->final_concatenation = concatenation;goalHandle->canceled(result);RCLCPP_INFO(rclcpp::get_logger("server"), "Goal Canceled");return;}// update the final concatenationconcatenation = concatenation + " " + myString;// update and publish feedback of the partial concatenationgoalHandle->publish_feedback(feedback);RCLCPP_INFO(rclcpp::get_logger("server"), "Publish Feedback");loop_rate.sleep();}// check if goal is doneif (rclcpp::ok()){result->final_concatenation = concatenation;goalHandle->succeed(result);RCLCPP_INFO(rclcpp::get_logger("server"), "Goal Succeeded");}
}void ConcatenateActionServer::HandleAccepted(const std::shared_ptr<GoalHandleConcatenate> goal_handle)
{using namespace std::placeholders;// this needs to return quickly to avoid blocking the executor, so spin up a new threadstd::thread{std::bind(&ConcatenateActionServer::execute, this, _1), goal_handle}.detach();
}int main(int argc, char ** argv)
{rclcpp::init(argc, argv);auto action_server = std::make_shared<ConcatenateActionServer>();rclcpp::spin(action_server);rclcpp::shutdown();return 0;
}
3.3 CMakeLists.txt
cmake_minimum_required(VERSION 3.5)
project(learning04_action)# 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(custom_interface REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_components REQUIRED)# add_executable(simple_action_server src/simple_action_server.cpp)
# ament_target_dependencies(simple_action_server
# "rclcpp"
# "rclcpp_action"
# "custom_interface")add_executable(class_action_server src/class_action_server.cpp)
ament_target_dependencies(class_action_server"rclcpp""rclcpp_action""custom_interface")# add_executable(simple_action_client src/simple_action_client.cpp)
# ament_target_dependencies(simple_action_client
# "rclcpp"
# "rclcpp_action"
# "custom_interface")add_executable(class_action_client src/class_action_client.cpp)
ament_target_dependencies(class_action_client"rclcpp""rclcpp_action""custom_interface")if(BUILD_TESTING)find_package(ament_lint_auto REQUIRED)ament_lint_auto_find_test_dependencies()
endif()install(TARGETS# simple_action_serverclass_action_server# simple_action_clientclass_action_clientDESTINATION lib/${PROJECT_NAME})ament_package()
3.4 package.xml
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3"><name>learning04_action</name><version>0.0.0</version><description>Action based tutorial</description><maintainer email="user@todo.todo">Antonio Mauro Galiano</maintainer><license>TODO: License declaration</license><buildtool_depend>ament_cmake</buildtool_depend><depend>custom_interface</depend><depend>rclcpp</depend><depend>rclcpp_action</depend><depend>rclcpp_components</depend><test_depend>ament_lint_auto</test_depend><test_depend>ament_lint_common</test_depend><export><build_type>ament_cmake</build_type></export>
</package>
4 編譯運行
# 編譯
colcon build# source環境變量
source install/setup.sh# 運行publisher
ros2 run learning04_action class_action_client# 運行subsriber
ros2 run learning04_action class_action_server
5 action常用指令
# 查看action信息
ros2 action info /turtle/roate_absolute# 設置action通信結構
ros2 interface show /turtle/roate_absolute# 發送action請求
ros2 action send_goal <action_name> <action_type> <values>
ros2 action send_goal /turtle/roate_absolute turtlesim/action/RotateAbsolute "{theta: 1.57}"
ros2 action send_goal /turtle/roate_absolute turtlesim/action/RotateAbsolute "{theta: 1.57}" --feedback