Getting Started with ROS - Action Programming

Getting Started with ROS - Action Programming

The client sends a moving target to simulate the process of the robot moving to the target position, including the code implementation of the server and client, requiring real-time position feedback

What is an action?

A robot is a complex intelligent system. It is not just as simple as keyboard remote control movement and recognition of a certain target. What we need to realize is a robot that meets the needs of specific scenarios such as food delivery, delivery, and sorting.

In the realization of these application functions, another ROS communication mechanism is often used—that is, actions. The meaning of this concept can be well understood from the name. The purpose of this communication mechanism is to facilitate the management of the process of a complete behavior of the robot.

The actions can be roughly summarized in the following four points:

  • A question-and-answer communication mechanism

  • with continuous feedback

  • Can be aborted during a task

  • Implementation of message mechanism based on ROS

communication model

For example, if we want the robot to turn in a circle, this is definitely not something that can be done in one click. The robot has to rotate little by little until it ends at 360 degrees. Suppose the robot is not in front of our eyes. Do you know if the robot started to circle and where did it go?

OK, what we need now is a feedback. For example, every 1s, tell us how many degrees we have turned to, 10 degrees, 20 degrees, 30 degrees. After a while, when we reach 360 degrees, we will send another message to indicate that the action is completed

For such a behavior that needs to be executed for a period of time, it is more appropriate to use the communication mechanism of the action, just like installing a progress bar, we can control the progress at any time, and if the movement is in progress, we can also send a command to cancel the movement at any time

How to define action message?

Here we create a new function package:

catkin_create_pkg learning_action roscpp rospy std_msgs geometry_msgs turtlesim message_generation actionlib_msgs actionlib

Create a new folder under the function package directory, name it action, and create an empty file TurtleMove.action in this folder

Define the action message content in the Motion.action file:

# Define the goal
float64 turtle_target_x  # Specify Turtle's target position
float64 turtle_target_y
float64 turtle_target_theta
---
# Define the result
float64 turtle_final_x
float64 turtle_final_y
float64 turtle_final_theta
---
# Define a feedback message
float64 present_turtle_x
float64 present_turtle_y
float64 present_turtle_theta

Action (Action) communication interface provides five message definitions, namely goal, cancel, status, feedback and result

  • goal: release task goal

  • cancel: request to cancel the task

  • status: Notifies the client of the current status

  • feedback: Periodic feedback task running monitoring data

  • result: Send the execution result of the task to the client, only published once

而 .action 文件用来定义其中三种消息,按顺序分别为 goal、result 和f eedback,与 .srv 文件中的服务消息定义方式一样,使用“—”作为分隔符

这里我们直接修改功能包目录下的 package.xml 文件,添加如下内容

然后我们就需要进入到我们功能包目录下的 src 目录下,设计我们的代码文件,这里仅给出 c++ 代码:

点击查看完整代码:

TurtleMove_client.cpp
#include <actionlib/client/simple_action_client.h>
#include "learn_action/TurtleMoveAction.h"
#include <turtlesim/Pose.h> 
#include <turtlesim/Spawn.h>
#include <geometry_msgs/Twist.h>

typedef actionlib::SimpleActionClient<learn_action::TurtleMoveAction> Client;

struct Myturtle
{
    float x;
    float y;
    float theta;
}turtle_present_pose;

// 当action完成后会调用该回调函数一次
void doneCb(const actionlib::SimpleClientGoalState& state,
        const learn_action::TurtleMoveResultConstPtr& result)
{
    ROS_INFO("Yay! The TurtleMove is finished!");
    ros::shutdown();
}

// 当action激活后会调用该回调函数一次
void activeCb()
{
    ROS_INFO("Goal just went active");
}

// 收到feedback后调用该回调函数
void feedbackCb(const learn_action::TurtleMoveFeedbackConstPtr& feedback)
{
    ROS_INFO(" present_pose : %f  %f  %f", feedback->present_turtle_x,
                   feedback->present_turtle_y,feedback->present_turtle_theta);
}

int main(int argc, char** argv)
{
    ros::init(argc, argv, "TurtleMove_client");

    // 定义一个客户端
    Client client("TurtleMove", true);

    // 等待服务器端
    ROS_INFO("Waiting for action server to start.");
    client.waitForServer();
    ROS_INFO("Action server started, sending goal.");

    // 创建一个action的goal
    learn_action::TurtleMoveGoal goal;
    goal.turtle_target_x = 1;
    goal.turtle_target_y = 1;
    goal.turtle_target_theta = 0;

    // 发送action的goal给服务器端,并且设置回调函数
    client.sendGoal(goal,  &doneCb, &activeCb, &feedbackCb);

    ros::spin();

    return 0;
}
TurtleMove_server.cpp
/*
   此程序通过通过动作编程实现由client发布一个目标位置
   然后控制Turtle运动到目标位置的过程
 */
#include <ros/ros.h>
#include <actionlib/server/simple_action_server.h>
#include "learn_action/TurtleMoveAction.h"
#include <turtlesim/Pose.h> 
#include <turtlesim/Spawn.h>
#include <geometry_msgs/Twist.h>

typedef actionlib::SimpleActionServer<learn_action::TurtleMoveAction> Server;

struct Myturtle
{
    float x;
    float y;
    float theta;
}turtle_original_pose,turtle_target_pose;

ros::Publisher turtle_vel;

void posecallback(const turtlesim::PoseConstPtr& msg) 
{
  ROS_INFO("Turtle1_position:(%f,%f,%f)",msg->x,msg->y,msg->theta);
  turtle_original_pose.x=msg->x; 
  turtle_original_pose.y=msg->y;
  turtle_original_pose.theta=msg->theta;
 }

// 收到action的goal后调用该回调函数
void execute(const learn_action::TurtleMoveGoalConstPtr& goal, Server* as)
{
    learn_action::TurtleMoveFeedback feedback;

    ROS_INFO("TurtleMove is working.");
    turtle_target_pose.x=goal->turtle_target_x;
    turtle_target_pose.y=goal->turtle_target_y; 
    turtle_target_pose.theta=goal->turtle_target_theta;

    geometry_msgs::Twist vel_msgs;
    float break_flag;

    while(1)
    {
        ros::Rate r(10);

        vel_msgs.angular.z = 4.0 * (atan2(turtle_target_pose.y-turtle_original_pose.y,
                                   turtle_target_pose.x-turtle_original_pose.x)-turtle_original_pose.theta);
        vel_msgs.linear.x = 0.5 * sqrt(pow(turtle_target_pose.x-turtle_original_pose.x, 2) +
                                      pow(turtle_target_pose.y-turtle_original_pose.y, 2)); 
        break_flag=sqrt(pow(turtle_target_pose.x-turtle_original_pose.x, 2) +
                                        pow(turtle_target_pose.y-turtle_original_pose.y, 2));
        turtle_vel.publish(vel_msgs);

        feedback.present_turtle_x=turtle_original_pose.x;
        feedback.present_turtle_y=turtle_original_pose.y;
        feedback.present_turtle_theta=turtle_original_pose.theta;
        as->publishFeedback(feedback);
        ROS_INFO("break_flag=%f",break_flag);
        if(break_flag<0.1) break;
        r.sleep();
    }
        // 当action完成后,向客户端返回结果
        ROS_INFO("TurtleMove is finished.");
        as->setSucceeded();
}

int main(int argc, char** argv)
{
    ros::init(argc, argv, "TurtleMove_server");
    ros::NodeHandle n,turtle_node;
    //订阅小乌龟的位置信息
    ros::Subscriber sub = turtle_node.subscribe("turtle1/pose",10,&posecallback);
    //发布控制小乌龟运动的速度
    turtle_vel = turtle_node.advertise<geometry_msgs::Twist>("turtle1/cmd_vel",10);    
    // 定义一个服务器
    Server server(n, "TurtleMove", boost::bind(&execute, _1, &server), false);
    // 服务器开始运行
    server.start();
    ROS_INFO("server has started.");
    ros::spin();

    return 0;
}

这里我们的客户端调用回调函数进行接收消息,只有接收到客户端启用的消息,我们才能发送运动的目标终点,在 server 中同样使用 对应的回调函数,检测到 client 中发来的信息才能控制小海龟运行

下面就是我们最常见的修改 CMakeLists.txt 的部分:

修改如下部分:

添加如下内容:

add_executable(TurtleMove_client src/TurtleMove_client.cpp)
target_link_libraries(TurtleMove_client ${catkin_LIBRARIES})
add_dependencies(TurtleMove_client ${PROJECT_NAME}_gencpp)

add_executable(TurtleMove_server src/TurtleMove_server.cpp)
target_link_libraries(TurtleMove_server ${catkin_LIBRARIES})
add_dependencies(TurtleMove_server ${PROJECT_NAME}_gencpp)

编译运行

下面我们开始进行编译运行:

首先我们运行 ros-master 和小海龟节点,然后我们先运行 server 节点,这里由于我们并没有启动 client ,所以小海龟没有运动,而是循环输出当前的位置和方向:

然后启动 client ,这是我们的 server 端就已经成功的接收到了目标地址信息:

当命令行提示运动结束,我们就可以看到小海龟已经运动到了我们目标位置,我们的位置输出就已经没有变化了:

小海龟整体运行过程如下:

参考资料

ROS | 动作通信的编程实现

ROS动作编程之控制小乌龟运动到目标位置

Guess you like

Origin blog.csdn.net/m0_59161987/article/details/129610068