ROS 入门 —— 动作编程
ROS 入门 —— 动作编程
客户端发送一个运动目标,模拟机器人运动到目标位置的过程,包含服务端和客户端的代码实现,要求带有实时位置反馈
什么是动作?
机器人是一个复杂的智能系统,并不仅仅是键盘遥控运动、识别某个目标这么简单,我们需要实现的是送餐、送货、分拣等满足具体场景需求的机器人
在这些应用功能的实现中,另外一种 ROS 通信机制也会被常常用到——那就是动作。从这个名字上就可以很好理解这个概念的含义,这种通信机制的目的就是便于对机器人某一完整行为的流程进行管理
对于动作大概可以总结为以下四点:
-
一种问答通信机制
-
带有连续反馈
-
可以在任务过程中止运行
-
基于 ROS 的消息机制实现
通信模型
举个例子,比如我们想让机器人转个圈,这肯定不是一下就可以完成的,机器人得一点一点旋转,直到360度才能结束,假设机器人并不在我们眼前,发出指令后,我们根本不知道机器人到底有没有开始转圈,转到哪里了?
![](https://img2023.cnblogs.com/blog/2829072/202303/2829072-20230316184107138-860055745.png)
![](https://img2023.cnblogs.com/blog/2829072/202303/2829072-20230316184354178-2030418373.png)
OK,现在我们需要的是一个反馈,比如每隔1s,告诉我们当前转到多少度了,10 度、20 度、30 度,一段时间之后,到了360度,再发送一个信息,表示动作执行完成
这样一个需要执行一段时间的行为,使用动作的通信机制就更为合适,就像装了一个进度条,我们可以随时把控进度,如果运动过程当中,我们还可以随时发送一个取消运动的命令
如何定义动作消息?
这里我们创建一个新的功能包:
catkin_create_pkg learning_action roscpp rospy std_msgs geometry_msgs turtlesim message_generation actionlib_msgs actionlib
在功能包目录下创建一个新的文件夹,命名为 action,并在此文件夹中创建一个空文件 TurtleMove.action
在 Motion.action 文件中定义动作消息内容:
# 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 )通信接口提供了五种消息定义,分别为 goal、cancel、status、feedback 和 result
-
goal:发布任务目标
-
cancel: 请求取消任务
-
status: 通知客户端当前的状态
-
feedback: 周期反馈任务运行的监控数据
-
result: 向客户端发送任务的执行结果,只发布一次
而 .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 的部分:
修改如下部分:
![](https://img2023.cnblogs.com/blog/2829072/202303/2829072-20230316202143489-1849537368.png)
![](https://img2023.cnblogs.com/blog/2829072/202303/2829072-20230316201408599-1716886161.png)
添加如下内容:
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)
![](https://img2023.cnblogs.com/blog/2829072/202303/2829072-20230316201545332-2045922405.png)
编译运行
下面我们开始进行编译运行:
首先我们运行 ros-master 和小海龟节点,然后我们先运行 server 节点,这里由于我们并没有启动 client ,所以小海龟没有运动,而是循环输出当前的位置和方向:
![](https://img2023.cnblogs.com/blog/2829072/202303/2829072-20230316215309954-56686759.png)
然后启动 client ,这是我们的 server 端就已经成功的接收到了目标地址信息:
![](https://img2023.cnblogs.com/blog/2829072/202303/2829072-20230316215422653-1011845337.png)
![](https://img2023.cnblogs.com/blog/2829072/202303/2829072-20230316215445036-590098569.png)
当命令行提示运动结束,我们就可以看到小海龟已经运动到了我们目标位置,我们的位置输出就已经没有变化了:
![](https://img2023.cnblogs.com/blog/2829072/202303/2829072-20230316220100023-959646331.png)
小海龟整体运行过程如下:
![](https://img2023.cnblogs.com/blog/2829072/202303/2829072-20230316222857502-1321625833.gif)