ROS中的订阅模式、服务模式、action模式

2023-05-16

在ROS的通信方式中存在订阅-发布模式,服务模式,动作服务模式。

1、订阅-发布模式

使用订阅-发布模式进行通信,首先要知道主题的存在。发布者向主题发布消息,订阅者订阅主题获取消息。其中订阅者不知道消息的来源,发布者不知道谁在接收。 如下图所示:
在这里插入图片描述

1.1、简单案例

  • 发布者
#include <ros/ros.h>

#include "example_ros_msg/VecOfDoubles.h"

int main(int argc, char * argv[])
{
    ros::init(argc, argv, "vec_plu");
    ros::NodeHandle n;
    ros::Publisher pub = n.advertise<example_ros_msg::VecOfDoubles>("vec_topic",1);
    example_ros_msg::VecOfDoubles msg;
    double counter=0;
    ros::Rate naptime(1.0);
    msg.dbl_vec.resize(3);
    msg.dbl_vec[0] = 1.414;
    msg.dbl_vec[1] = 2.71828;
    msg.dbl_vec[2] = 3.1416;
    msg.dbl_vec.push_back(counter);
    while (ros::ok())
    {
        counter+=1;
        msg.dbl_vec.push_back(counter);
        pub.publish(msg);
        naptime.sleep();
    }
    
    // ros::spin();
    // ros::shutdown();
    return 0;
}

  • 订阅者
#include <ros/ros.h>
#include "example_ros_msg/VecOfDoubles.h"

void callBack(const example_ros_msg::VecOfDoubles&masg)
{
    std::vector<double> vec = masg.dbl_vec;
    int si = vec.size();
    for(int i=0;i<si;i++ )
    {
        ROS_INFO("vec[%d] = %f",i,vec[i]);
    }
    ROS_INFO("\n");
}

int main(int argc, char * argv[])
{
    ros::init(argc, argv, "vec_sub");
    ros::NodeHandle n;
    ros::Subscriber sub = n.subscribe("vec_topic",1,callBack);
    // ros::spin();
    // ros::shutdown();
    ros::spin();
    return 0;
}

  • 修改CMakeLists进行编译
add_executable(vec_mag_plu src/vector_push.cpp)
add_executable(vec_mag_sub src/vec_size_sub.cpp)
target_link_libraries(vec_mag_plu
  ${catkin_LIBRARIES}
)
target_link_libraries(vec_mag_sub
  ${catkin_LIBRARIES}
)
#并且修改相对应的引用文件

2、服务模式

服务模式是一种请求应答模式,在进行请求之前需要定义服务的消息类型进行规范请求

2.1、服务消息

服务消息是一种包含请求内容以及应答内心的消息包,需要按照一定的流程进行创建。格式类型如下图所示
在这里插入图片描述

  • 服务消息创建
    1、在功能包创建srv文件目录
    2、在srv中创建examsrv.srv文件并按照上图方式组建消息
    3、修改CMakeLists,Package.xml进行生成
find_package(catkin REQUIRED COMPONENTS
  roscpp
  std_msgs
  message_generation
)
add_service_files(
  FILES
  examsrv.srv
  # Service2.srv
)

========package.xml
  <build_depend>message_generation</build_depend>
  <exec_depend>message_runtime</exec_depend>

编译后会在devel/include/包名 中生成examsrv.h,examsrvRequest.h,examsrvResponse.h

2.2、简单的服务模式案例

  • 服务
#include <ros/ros.h>

#include "example_ros_msg/examsrv.h"
#include<iostream>
#include<string>
using namespace std;

bool callBack(example_ros_msg::examsrvRequest&request,example_ros_msg::examsrvResponse&response)
{
    ROS_INFO("callback activated");
    string in_name(request.name);
    response.on_the_list = false;
    if(in_name.compare("Bob")==0)
    {
        ROS_INFO("asked about Bob");
        response.age=32;
        response.good_guy = false;
        response.on_the_list = true;
        response.nickname="BobTherrible";
    }
    if(in_name.compare("Ted")==0)
    {
        ROS_INFO("asked about Ted");
        response.age=22;
        response.good_guy = true;
        response.on_the_list = true;
        response.nickname="TedTherrible";
    }
    return true;
}

int main(int argc, char * argv[])
{
    ros::init(argc, argv, "srv_node");
    ros::NodeHandle n;
    ros::ServiceServer ser = n.advertiseService("lookup_by_name",callBack);
    ROS_INFO("Ready to look up names");
    ros::spin();
    // ros::shutdown();
    return 0;
}

  • 请求
#include <ros/ros.h>
#include "example_ros_msg/examsrv.h"
#include<iostream>
#include<string>
using namespace std;

int main(int argc, char * argv[])
{
    ros::init(argc, argv, "exam_client");
    ros::NodeHandle n;
    ros::ServiceClient sc = n.serviceClient<example_ros_msg::examsrv>("lookup_by_name");
    example_ros_msg::examsrv srvmasg;
    bool on_the_list = false;
    string in_name;
    while (ros::ok())
    {
       cin>>in_name;
       if(in_name.compare("x")==0)
       {
           return 0;
       }
        srvmasg.request.name = in_name;
        if(sc.call(srvmasg))
        {
            if(srvmasg.response.on_the_list){
                cout<<srvmasg.request.name<<" is know as "<<srvmasg.response.nickname<<endl;
                if(srvmasg.response.good_guy)
                {
                    cout<<"good"<<endl;
                }
                else{
                    cout<<"bad"<<endl;
                }
            }
            else
            {
                cout<<srvmasg.request.name<<" is not know  "<<endl;
            }
        }else
        {
            ROS_ERROR("failed to call service lookup_by_name");
            return 1;
        }
    }
    
    // ros::spin();
    // ros::shutdown();
    return 0;
}

  • 修改CMakeLists
add_executable(name_srv src/examsrv.cpp)
add_executable(name_cli src/examsrvclient.cpp)
target_link_libraries(name_srv
  ${catkin_LIBRARIES}
)
target_link_libraries(name_cli
  ${catkin_LIBRARIES}
)

3、action服务

与服务模式相比action服务增加了反馈机制,可以在获得请求目标后,对目标的执行过程进行反馈。通信模型如图所示
在这里插入图片描述
当服务接收到目标以后会为每一个目标创建一个状态机,跟踪目标状态。状态机如下
在这里插入图片描述

状态机的命令有

  • setAccepted - 在检查一个目标之后,开始处理

  • setRejected - 在检查一个目标后,决定永远不处理它,因为它是一个无效的请求(超出界限,资源不可用,无效等)

  • setSucceeded -通知目标已成功处理

  • setAborted - 通知目标在处理过程中遇到错误,必须中止

  • setCanceled - 通知目标由于取消请求而不再被处理

中间状态有

  • Pending - 目标还没有被操作服务器处理

  • Active - 目标当前正在由操作服务器处理

  • Recalling - 目标尚未被处理,并且已从操作客户端接收到取消请求,但操作服务器尚未确认目标已被取消

  • Preempting - 目标正在处理中,并且从操作客户端收到了一个取消请求,但操作服务器尚未确认目标已被取消

最终状态

  • Rejected - 目标被操作服务器拒绝,没有进行处理,也没有来自操作客户机的取消请求

  • Succeeded - 动作服务器成功地实现了目标

  • Aborted - 目标由操作服务器终止,而没有来自操作客户机的取消外部请求

  • Recalled - 在操作服务器开始处理目标之前,目标被另一个目标或取消请求取消

  • Preempted - 目标的处理被另一个目标或发送到操作服务器的取消请求取消

3.1、消息创建

像服务模式一样需要创建服务消息,其消息类型如下图所示
在这里插入图片描述

  • 在功能包创建action目录,在目录中创建demo.action并按照上方填写消息
  • 修改CMackLists
add_action_files(
  FILES
  demo.action
  # Action2.action
)
其他的同上方的服务信息

3.2、简单案例

  • action服务
#include<actionlib/server/simple_action_server.h>
#include<example_action_server/demoAction.h>
int g_count = 0;
bool g_count_failure = false;
class ExampleActionSever{
    private:
    ros::NodeHandle nh_;
    actionlib::SimpleActionServer<example_action_server::demoAction> as_;
    example_action_server::demoGoal goal;
    example_action_server::demoResult result_;
    example_action_server::demoFeedback feedback_;
    int countdown_val_;
    public:
    ExampleActionSever();
    ~ExampleActionSever(){

    }

    void executeCB(const actionlib::SimpleActionServer<example_action_server::demoAction>::GoalConstPtr&goal);
};

ExampleActionSever::ExampleActionSever():as_(nh_,"time_action",boost::bind(&ExampleActionSever::executeCB,this,_1),false)
{
    ROS_INFO("in construction of exampleActon....");
    as_.start();
}

void ExampleActionSever::executeCB(const actionlib::SimpleActionServer<example_action_server::demoAction>::GoalConstPtr&goal)
{
    ROS_INFO("in executeCB");
    ROS_INFO("goal input is:%d",goal->input);

    ros::Rate timer(1.0);
    countdown_val_ = goal->input;
    while (countdown_val_>0)
    {
        ROS_INFO("countdown=%d",countdown_val_);
        if(as_.isPreemptRequested()){
            ROS_INFO("goal cancelled!");
            as_.setAborted(result_);
            return;
        }
        feedback_.fdbk = countdown_val_;
        as_.publishFeedback(feedback_);
        countdown_val_--;
        timer.sleep();
    }
    result_.output  = countdown_val_;
    as_.setSucceeded(result_);
    
    
}

int main(int argc ,char*argv[])
{
    ros::init(argc,argv,"examatciontime");
    ExampleActionSever ex;
    ROS_INFO("go spin.....");
    while (!g_count_failure)
    {
        ros::spinOnce();
    }
    return 0;
}
  • action 客户端
#include<ros/ros.h>
#include<actionlib/client/simple_action_client.h>
#include<example_action_server/demoAction.h>

using namespace std;
bool g_goal_action = false;
int g_result_output = -1;
int g_fdbk = -1;

void doneCb(const actionlib::SimpleClientGoalState& state,const example_action_server::demoResultConstPtr& result)
{
    ROS_INFO("doneCb: server responded with state [%s]",state.toString().c_str());
    ROS_INFO("got result output=%d",result->output);
    g_result_output = result->output;
    g_goal_action = false;
}
void feedbackCB(const example_action_server::demoFeedbackConstPtr& fdbk_msg)
{
    ROS_INFO("feedback status = %d",fdbk_msg->fdbk);
    g_fdbk = fdbk_msg->fdbk;
}

void activeCB()
{
    ROS_INFO("Goal just went active");
    g_goal_action = true;
}

int main(int argc,char*argv[])
{
    ros::init(argc,argv,"exampleactionclienttime");
    ros::NodeHandle n;
    ros::Rate main_timer(1.0);
    example_action_server::demoGoal goal;
    actionlib::SimpleActionClient<example_action_server::demoAction> actionClient("time_action",true);
    ROS_INFO("waiting for server");
    bool server_exists = actionClient.waitForServer(ros::Duration(1.0));
    if(!server_exists)
    {
        ROS_WARN("not wait for server");
        server_exists = actionClient.waitForServer(ros::Duration(1.0));
    }

    ROS_INFO("connnect to action server");

    int countdown_goal=1;
    while (countdown_goal>=0)
    {
        cout<<"enter a desired timer value,in seconds(0 to abort,<0 to quit):";
        cin>>countdown_goal;
        if(countdown_goal==0)
        {
            ROS_INFO("cancelling goal");
            actionClient.cancelGoal();
        }
        if(countdown_goal<0)
        {
            ROS_INFO("this client is quitting");
            return 0;
        }
        ROS_INFO("send timer goal = %d seconds to timer action server",countdown_goal);
        goal.input = countdown_goal;
        actionClient.sendGoal(goal,&doneCb,&activeCB,&feedbackCB);
    }

    return 0;
    
}
  • 修改CMakeLists
add_executable(exampletimeActionClient src/example_action_w_clent.cpp)
add_executable(exampletimeAction src/example_action_w_fdbk.cpp)
target_link_libraries(exampletimeActionClient
  ${catkin_LIBRARIES}
)
target_link_libraries(exampletimeAction
  ${catkin_LIBRARIES}
)

记录为了让自己在回忆
参考
1
2
3

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

ROS中的订阅模式、服务模式、action模式 的相关文章

随机推荐

  • MFC C++ Cstring与string互转

    CString 转换成string 我试了很多的方法 xff0c 都不行 xff0c 我用的vs2010 解决方案 unicode CString sz1 61 L 34 abc 34 std string sz2 61 CT2A sz1
  • MFC+opencv 显示mat图像

    VS2015 43 opencv3 0 MFC显示图片中方法三在使用时 xff0c 只能显示彩色图像 xff0c 灰度图像显示有问题 xff0c 经查找 xff0c 是没有设置图像调色板的原因图片控件宽度不为4的倍数 显示错误 xff0c
  • 怎么去掉SVN前面的标签,如感叹号!

    1 问题陈述 xff1a 有时不小心将整个目录都检入 xff0c 导致整个页面的文件与目录都有svn的标签 xff0c 感叹号什么的 2 解决方法 xff1a 打开 所有程序 xff0c 找到TortoiseSVN gt Setting 修
  • 人工智能6.1 -- 机器学习算法篇(一)数据清洗、回归(含实践)

    人工智能 python xff0c 大数据 xff0c 机器学习 xff0c 深度学习 xff0c 计算机视觉 六 机器学习算法篇 xff08 一 xff09 数据清洗 回归 xff08 含实践 xff09 前言 目录算法热身结论 xff1
  • Tesseract-ocr 3.0.2源码 + VS2010项目工程 + 简单测试代码

    编译环境 Visual Studio 2010 所用类库版本 zlib 1 2 7 lpng1514 jpegsr9 tiff 4 0 3 giflib 5 0 4 leptonica 1 69 tesseract ocr3 0 2 下载地
  • Asprise OCR SDK 15.3试用版破解

    1 序言 之前因同事需要 xff0c 破解过Asprise OCR 4 0试用版本 xff0c 对这个库比较有印象 目前最新版本为15 3 xff0c 网上已经能下载到它的试用破解版本 xff0c 但似乎没有看到此版本的破解文章 Aspri
  • 内存中绘图 Memdc

    内存中绘图 Memdc CDC MemDC 首先定义一个显示设备对象 xff0c 所有的绘制首先绘制到这块内存中 CBitmap MemBitmap 定义一个位图对象 随后建立与屏幕显示兼容的内存显示设备 MemDC CreateCompa
  • MFC中char*,string和CString之间的转换

    string是使用STL时必不可少的类型 xff0c 所以是做工程时必须熟练掌握的 xff1b char 是从学习C语言开始就已经和我们形影不离的了 xff0c 有许多API都是以char 作为参数输入的 所以熟练掌握三者之间的转换十分必要
  • C++ 创建文件夹的四种方式

    在开头不得不吐槽一下 xff0c 我要的是简单明了的创建文件夹的方式 xff0c 看得那些文章给的都是复杂吧唧的一大坨代码 xff0c 不仔细看鬼知道写的是啥 因此 xff0c 为了方便以后自己阅读 xff0c 这里自己写一下 C 43 4
  • c++ 多线程:线程句柄可以提前关闭,但是线程并没有关闭

    很多程序在创建线程都这样写的 xff1a ThreadHandle 61 CreateThread NULL 0 CloseHandel ThreadHandle 1 xff0c 线程和线程句柄 xff08 Handle xff09 不是一
  • MFC的GDI绘制坐标问题

    MoveWindow和CDC的位置不一样 xff0c MoveWindow 起点坐标 xff0c 宽 xff0c 高 xff0c CDC xff1a 起点坐标 xff0c 终点坐标
  • C#线程同步(1)- 临界区&Lock

    文章原始出处 http xxinside blogbus com logs 46441956 html 预备知识 xff1a 线程的相关概念和知识 xff0c 有多线程编码的初步经验 一个机会 xff0c 索性把线程同步的问题在C 里面的东
  • 线程锁的概念函数EnterCriticalSection和LeaveCriticalSection的用法

    线程锁的概念函数EnterCriticalSection和LeaveCriticalSection的用法 注 xff1a 使用结构CRITICAL SECTION 需加入头文件 include afxmt h 定义一个全局的锁 CRITIC
  • C# 获取鼠标相对当前窗口坐标的方法

    编写客户端应用程序时 xff0c 经常要用到鼠标当前的位置 在C 的winform开发中 xff0c 可以用Control MousePosition获得当前鼠标的坐标 xff0c 使用PointToClient计算鼠标相对于某个控件的坐标
  • 【Linux】Rocky Linux 9.0 Podman服务无法正常启动

    Rocky Linux 9 0发布后 xff0c 我在本地虚拟机对该版本进行了安装和测试 xff0c 发现Podman服务在某些情况下 xff0c 无法正常启动 当 etc selinux config配置中 xff0c SELINUX 6
  • 如何在C#控件中画点并获得指定点的像素颜色

    画点的方法 方法一 用picGraphics FillRectangle new SolidBrush fillColor p X p Y 1 1 即用一个像素填充方法 方法二 用gdi32 dll库中的SetPixel方法 DllImpo
  • LinearLayout(线性布局)

    本节引言 本节开始讲Android中的布局 xff0c Android中有六大布局 分别是 LinearLayout 线性布局 xff0c RelativeLayout 相对布局 xff0c TableLayout 表格布局 FrameLa
  • 使用DockerFile创建ROS环境(带有xfce和vnc可以访问桌面查看ROS的图形工具)

    基于 consol ubuntu xfce vnc的DockerFile FROM consol ubuntu xfce vnc 切换到root xff0c root才有权限进行安装软件等操作 USER 0 替换桌面背景 xff08 Doc
  • ROS自定义消息类型与使用

    1 创建消息文件 在功能包中创建msg文件夹并在文件夹中创建消息文件exmsage msg Header header int32 demo int float64 demo double 2 修改package xml lt build
  • ROS中的订阅模式、服务模式、action模式

    在ROS的通信方式中存在订阅 发布模式 xff0c 服务模式 xff0c 动作服务模式 1 订阅 发布模式 使用订阅 发布模式进行通信 xff0c 首先要知道主题的存在 发布者向主题发布消息 xff0c 订阅者订阅主题获取消息 其中订阅者不