文章目录
- 自定义action文件(类似msg和service)
- 服务端 action01_server.cpp
- 客户端 action02_client.cpp
- 服务端 action01_server_p.py
- 客户端 action02_client_p.py
应用场景:需要使用服务通信,但需要及时进行反馈。
在ROS中提供了actionlib功能包集,用于实现 action 通信。action 是一种类似于服务通信的实现,其实现模型也包含请求和响应,但是不同的是,在请求和响应的过程中,服务端还可以连续的反馈当前任务进度,客户端可以接收连续反馈并且还可以取消任务。
action通信接口
- goal:目标任务
- cacel:取消任务
- status:服务端状态
- result:最终执行结果(只会发布一次)
- feedback:连续反馈(可以发布多次)
自定义action文件(类似msg和service)
服务端 action01_server.cpp
#include"ros/ros.h"
#include"actionlib/server/simple_action_server.h"
#include"demo01_action/AddIntsAction.h"
typedef actionlib::SimpleActionServer<demo01_action::AddIntsAction> Server;
void cb(const demo01_action::AddIntsGoalConstPtr &goalPtr,Server* server){
int goal_num = goalPtr->num;
ROS_INFO("客户端提交的目标值是:%d",goal_num);
ros::Rate rate(10);
int result = 0;
ROS_INFO("开始连续反馈.....");
for(int i = 1; i <= goal_num; i++)
{
result += i;
rate.sleep();
demo01_action::AddIntsFeedback fb;
fb.progress_bar = i / (double)goal_num;
server->publishFeedback(fb);
}
ROS_INFO("最终响应结果:%d",result);
demo01_action::AddIntsResult r;
r.result = result;
server->setSucceeded(r);
}
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
ros::init(argc,argv,"addInts_server");
ros::NodeHandle nh;
Server server(nh,"addInts",boost::bind(&cb,_1,&server),false);
server.start();
ROS_INFO("服务启动......");
ros::spin();
return 0;
}
客户端 action02_client.cpp
#include "ros/ros.h"
#include "actionlib/client/simple_action_client.h"
#include "demo01_action/AddIntsAction.h"
typedef actionlib::SimpleActionClient<demo01_action::AddIntsAction> Client;
void done_cb(const actionlib::SimpleClientGoalState &state, const demo01_action::AddIntsResultConstPtr &result){
if (state.state_ == state.SUCCEEDED)
{
ROS_INFO("响应成功,最终结果 = %d",result->result);
} else {
ROS_INFO("请求失败!");
}
}
void active_cb(){
ROS_INFO("客户端与服务端连接建立....");
}
void feedback_cb(const demo01_action::AddIntsFeedbackConstPtr &feedback){
ROS_INFO("当前进度:%.2f",feedback->progress_bar);
}
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
ros::init(argc,argv,"addInts_client");
ros::NodeHandle nh;
actionlib::SimpleActionClient<demo01_action::AddIntsAction> client(nh,"addInts");
ROS_INFO("等待服务器启动.....");
client.waitForServer();
demo01_action::AddIntsGoal goal;
goal.num = 100;
client.sendGoal(goal,&done_cb,&active_cb,&feedback_cb);
ros::spin();
return 0;
}
服务端 action01_server_p.py
"""
需求:
创建两个ROS 节点,服务器和客户端,
客户端可以向服务器发送目标数据N(一个整型数据)服务器会计算 1 到 N 之间所有整数的和,
这是一个循环累加的过程,返回给客户端,这是基于请求响应模式的,
又已知服务器从接收到请求到产生响应是一个耗时操作,每累加一次耗时0.1s,
为了良好的用户体验,需要服务器在计算过程中,
每累加一次,就给客户端响应一次百分比格式的执行进度,使用 action实现。
流程:
1.导包
2.初始化 ROS 节点
3.单独使用类封装,
4.类中创建 action 服务端对象
5.处理请求(a.解析目标值 b. 发送连续反馈 c. 响应最终结果)--- 回调函数
6.spin()回旋
"""
import rospy
import actionlib
from demo01_action.msg import *
class MyAction:
def __init__(self):
self.server = actionlib.SimpleActionServer("addInts",AddIntsAction,self.cb,False)
self.server.start()
rospy.loginfo("服务端启动.....")
def cb(self,goal):
goal_num = goal.num
rospy.loginfo("目标值:%d",goal_num)
rate = rospy.Rate(10)
sum = 0
rospy.loginfo("请求处理中.....")
for i in range(1,goal_num + 1):
sum = sum + i
rate.sleep()
fb_obj = AddIntsFeedback()
fb_obj.progress_bar = i / goal_num
self.server.publish_feedback(fb_obj)
rospy.loginfo("响应结果:%d",sum)
result = AddIntsResult()
result.result = sum
self.server.set_succeeded(result)
if __name__ == "__main__":
rospy.init_node("action_server_p")
myAction = MyAction()
rospy.spin()
客户端 action02_client_p.py
"""
需求:
创建两个ROS 节点,服务器和客户端,
客户端可以向服务器发送目标数据N(一个整型数据)服务器会计算 1 到 N 之间所有整数的和,
这是一个循环累加的过程,返回给客户端,这是基于请求响应模式的,
又已知服务器从接收到请求到产生响应是一个耗时操作,每累加一次耗时0.1s,
为了良好的用户体验,需要服务器在计算过程中,
每累加一次,就给客户端响应一次百分比格式的执行进度,使用 action实现。
流程:
1.导包
2.初始化 ROS 节点
3.单独使用类封装,
4.类中创建 action 服务端对象
5.处理请求(a.解析目标值 b. 发送连续反馈 c. 响应最终结果)--- 回调函数
6.spin()回旋
"""
import rospy
import actionlib
from demo01_action.msg import *
class MyAction:
def __init__(self):
self.server = actionlib.SimpleActionServer("addInts",AddIntsAction,self.cb,False)
self.server.start()
rospy.loginfo("服务端启动.....")
def cb(self,goal):
goal_num = goal.num
rospy.loginfo("目标值:%d",goal_num)
rate = rospy.Rate(10)
sum = 0
rospy.loginfo("请求处理中.....")
for i in range(1,goal_num + 1):
sum = sum + i
rate.sleep()
fb_obj = AddIntsFeedback()
fb_obj.progress_bar = i / goal_num
self.server.publish_feedback(fb_obj)
rospy.loginfo("响应结果:%d",sum)
result = AddIntsResult()
result.result = sum
self.server.set_succeeded(result)
if __name__ == "__main__":
rospy.init_node("action_server_p")
myAction = MyAction()
rospy.spin()
本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)