sketch
Action message communication is very similar to service message communication. The service has goal s and result s corresponding to the request and response respectively. In addition, there is more feedback in the action. In some scenarios, when it takes a long time to respond after receiving a request and an intermediate value is required, you can use this feedback to send relevant data.
characteristic
Feedback performs asynchronous two-way message communication between the action client and the action server. The action client sets the action target, and the action server performs the specified work according to the target, and sends the action feedback and action results to the action client. Unlike services, actions are usually used to guide complex robot tasks. For example, after sending a target value, you can also send a command to cancel the target at any time.
Interactive process
The action communication uses the communication package set actionlib provided by ROS. Refer to http://wiki.ros.org/actionlib.
Interaction between action client and server application:
Message communication interface between action client and server:
Core element
- ROS Master (Manager)
It must first be run and use the XMLRPC server to manage the connection information in the message communication between nodes. - Server (server)
The server takes the request as the input and the response as the output. Both the request and response are messages. After receiving the service request, the server executes the specified service and sends the results to the client. The server is the node used to execute the specified command. - Client
The client takes the request as the output and the response as the input. Both the request and response are messages, and sends the service request to the server to receive the result. The client is the node used to convey the given command and receive the result value. - action specification
reference resources: http://wiki.ros.org/cn/actionlib/DetailedDescription.
The client node and the server node communicate through the ROS action protocol based on ROS messages, which include:
① Goal: used to send the target to the server. The goal topic uses the automatically generated ActionGoal message (for example, actionlib/TestActionGoal) to send a new target to the action server. In essence, the ActionGoal message wraps a goal message and binds it with the target ID;
② Cancel: used to send a cancellation request to the server. cancel topic use actionlib_msgs/GoalID message and allow the action client to send the cancel request to the action server. Each cancel message has a timestamp and goal ID;
③ Status: used to inform the client of the current status of each target in the system. The topic used by the status topic is called actionlib_msgs/GoalStatusArray, which provides the action client with status information about each target server currently being tracked by the action server;
④ Feedback: auxiliary information for periodic feedback target. The feedback topic uses the automatically generated ActionFeedback message and provides a method for server implementers to send periodic updates to the action client during the processing of the target;
⑤ Result: used to send the execution result of the task to the client. This topic will be published only once. The result topic uses the automatically generated ActionResult message (for example, actionlib/TestActionResult) and provides the server implementers with a method to send information to the client after completing the target.
Custom action file
The action data type of ROS can be here see.
The data in the action file is divided into three parts separated by "---". The above is the target definition, the middle is the result definition, and the following is the feedback definition.
Let's create an action file for laundry. First, in action_ Create the action folder in the test package, and then create the message file (Laundry.action) in the folder.
# goal, laundry type 1: start fast washing; 2: Start high temperature washing; 3: Start soaking and washing uint8 wash_type --- # result string wash_result --- # feedback, washing progress uint8 wash_percent
Code examples (server and client)
Requirement Description: write the server and client files to simulate the laundry process. The client starts laundry after entering the laundry mode. The service continuously feeds back the laundry progress and the results of laundry completion.
Continue in service_ In test, create server.cpp (server) and client.cpp (client) files respectively.
Server (action_server.cpp)
#include "ros/ros.h" #include "actionlib/server/simple_action_server.h" #include "action_test/LaundryAction.h" #include <iostream> typedef actionlib::SimpleActionServer<action_test::LaundryAction> ActionServer; // 4. callback function called after receiving goal of action void executeCb(const action_test::LaundryGoalConstPtr &goal, ActionServer *server) { // Get target value uint8_t wash_type = goal->wash_type; std::string wash_mode; switch (wash_type) { case 1: wash_mode = "Quick wash"; break; case 2: wash_mode = "High temperature washing"; break; case 3: wash_mode = "Immersion washing"; break; default: break; } ROS_INFO("The target value is%d,start%s!", wash_type, wash_mode.c_str()); // Response continuous feedback action_test::LaundryFeedback feedback; for (int i = 0; i <= 100; i++) { feedback.wash_percent = i; server->publishFeedback(feedback); ros::Duration(0.5).sleep(); } // Feedback results action_test::LaundryResult result; result.wash_result = wash_mode + "Done!"; server->setSucceeded(result); } int main(int argc, char **argv) { // Set encoding setlocale(LC_ALL, ""); // 1. Initialize ROS node ros::init(argc, argv, "action_server"); // 2. Instantiate ROS handle ros::NodeHandle nh; // 3. Instantiate the action server object // Parameter 2 is the name of the action server, parameter 3 is called in a separate thread when a new target is received, and parameter 4 is to tell the action server whether to start publishing immediately when it appears ActionServer server(nh, "laundry", boost::bind(&executeCb, _1, &server), false); server.start(); ros::spin(); return 0; }
Client (action_client.cpp)
#include "ros/ros.h" #include "actionlib/client/simple_action_client.h" #include "action_test/LaundryAction.h" typedef actionlib::SimpleActionClient<action_test::LaundryAction> ActionClient; void doneCb(const actionlib::SimpleClientGoalState &state, const action_test::LaundryResultConstPtr &result) { if (state.state_ == state.SUCCEEDED) { ROS_INFO("Feedback results:%s", result->wash_result.c_str()); } else { ROS_INFO("Task failed!"); } } void activeCb() { ROS_INFO("The action has been activated...."); } void feedbackCb(const action_test::LaundryFeedbackConstPtr &feedback) { ROS_INFO("Washing progress is:%d%s", feedback->wash_percent, "%"); } int main(int argc, char **argv) { // Set encoding setlocale(LC_ALL, ""); // 1. Initialize ROS node ros::init(argc, argv, "action_client"); // 2. Instantiate ROS handle ros::NodeHandle nh; // 3. Instantiate the action client object // Parameter 2 is the name of the action. Parameter 3 is true by default. There is no need to call ros::spin() again. If it is set to false, it needs to be called manually ActionClient client(nh, "laundry", true); // Wait for the server to start client.waitForServer(); // 4. Define action target data action_test::LaundryGoal goal; goal.wash_type = 1; // 5. Send the target, register the callback, process the feedback and the final result // Parameter 1 is the callback function processed when converting to Done, parameter 2 is the callback function processed when converting to Active, and parameter 3 is the callback function called whenever feedback from this target is received client.sendGoal(goal, &doneCb, &activeCb, &feedbackCb); ros::spin(); return 0; }
Configure CMakeLists.txt
# Component packages that catkin depends on when it is built find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs actionlib actionlib_msgs ) # Configure the action source file. FILES will reference the *. Action file in the action directory of the current function pack directory and automatically generate a header file (*. h) add_action_files( FILES Laundry.action ) # Rely on STD when generating messages_ msgs,actionlib_msgs generate_messages( DEPENDENCIES std_msgs actionlib_msgs ) # Runtime dependency describes the function packages of library, catkin build dependency and system dependency catkin_package( # INCLUDE_DIRS include # LIBRARIES action_test CATKIN_DEPENDS roscpp rospy std_msgs actionlib actionlib_msgs # DEPENDS system_lib ) # Node build options, configuring executables add_executable(action_client src/action_client.cpp) add_executable(action_server src/action_server.cpp) # Generate dependency messages in advance before building libraries and executables add_dependencies(action_client ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) add_dependencies(action_server ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) # Node build options to configure the target link library target_link_libraries(action_client ${catkin_LIBRARIES} ) target_link_libraries(action_server ${catkin_LIBRARIES} )
Compile and run
Use Ctrl+Shift+B to compile, and then use the roscore command to start the master node first. Under the environment variable of the new terminal source, then run the server and the client respectively. At this time, you can see that the server receives the client's request and constantly feeds back the intermediate state, and the final feedback result.
☝ ★★★ - return to the general directory of ROS robot development notes Summary - ★★★ ☝