ROS 官网教程02-发布者订阅者-服务和客户端

ROS 官网教程02-发布者订阅者-服务和客户端

一、编写简单的发布者和订阅者(C++)

1.1 编写发布者节点

$ roscd beginner_tutorials
$ mkdir src
$ cd src

在 src 下,创建 talker.cpp,粘贴如下代码

#include "ros/ros.h" // ros/ros.h是一个很便利的include,它包括了使用ROS系统中最常见的公共部分所需的全部头文件。
#include "std_msgs/String.h"//位于std_msgs包里的std_msgs/String消息
#include <sstream>
/**
 * This tutorial demonstrates simple sending of messages over the ROS system.
 */
int main(int argc, char **argv)
{
  /**
   * The ros::init() function needs to see argc and argv so that it can perform
   * any ROS arguments and name remapping that were provided at the command line.
   * For programmatic remappings you can use a different version of init() which takes
   * remappings directly, but for most command-line programs, passing argc and argv is
   * the easiest way to do it.  The third argument to init() is the name of the node.
   *
   * You must call one of the versions of ros::init() before using any other
   * part of the ROS system.
   */
  // 指定节点名称为“talker”,不能包含“/”
  ros::init(argc, argv, "talker"); 

  /**
   * NodeHandle is the main access point to communications with the ROS system.
   * The first NodeHandle constructed will fully initialize this node, and the last
   * NodeHandle destructed will close down the node.
   */
  // 为进程创建句柄,第一句柄将执行节点初始化
  ros::NodeHandle n;

  /**
   * The advertise() function is how you tell ROS that you want to
   * publish on a given topic name. This invokes a call to the ROS
   * master node, which keeps a registry of who is publishing and who
   * is subscribing. After this advertise() call is made, the master
   * node will notify anyone who is trying to subscribe to this topic name,
   * and they will in turn negotiate a peer-to-peer connection with this
   * node.  advertise() returns a Publisher object which allows you to
   * publish messages on that topic through a call to publish().  Once
   * all copies of the returned Publisher object are destroyed, the topic
   * will be automatically unadvertised.
   *
   * The second parameter to advertise() is the size of the message queue
   * used for publishing messages.  If messages are published more quickly
   * than we can send them, the number here specifies how many messages to
   * buffer up before throwing some away.
   */
  // 告诉主节点会在chatter话题上发布一个类型为std_msgs/String的消息,主节点会通知正在监听 chatter 的节点。第二个参数是缓存队列大小
  // ros::Publisher 包含 publish 方法,在话题上发布消息
  ros::Publisher chatter_pub = n.advertise<std_msgs::String>("chatter", 1000);
  // 指定循环的频率,记录从上次调用Rate::sleep()到现在已经有多长时间,并休眠正确的时间
  ros::Rate loop_rate(10);

  /**
   * A count of how many messages we have sent. This is used to create
   * a unique string for each message.
   */
  int count = 0;
  /*安装一个SIGINT处理程序
    ros::ok()在以下情况会返回false:

    * 收到SIGINT信号(Ctrl+C)
    * 被另一个同名的节点踢出了网络
    * ros::shutdown()被程序的另一部分调用
    * 所有的ros::NodeHandles都已被销毁
    */
  while (ros::ok())
  {
    /**
     * This is a message object. You stuff it with data, and then publish it.
     */
    std_msgs::String msg;
    std::stringstream ss;
    ss << "hello world " << count;
    msg.data = ss.str();
    // ROS_INFO和它的朋友们可用来取代printf/cout
    ROS_INFO("%s", msg.data.c_str());
    /**
     * The publish() function is how you send messages. The parameter
     * is the message object. The type of this object must agree with the type
     * given as a template parameter to the advertise<>() call, as was done
     * in the constructor above.
     */
    // 信息广播给了任何已连接的节点
    chatter_pub.publish(msg);
    // 处理回调函数
    ros::spinOnce();
    //使用ros::Rate在剩下的时间内睡眠,以让我们达到10Hz的发布速率
    loop_rate.sleep();

    ++count;
  }


  return 0;
}

对上边的内容进行一下总结:

  • 初始化ROS系统
  • 向主节点宣告我们将要在chatter话题上发布std_msgs/String类型的消息
  • 以每秒10次的速率向chatter循环发布消息

1.2 编写订阅者节点

在 src 下创建 chatter.cpp,并粘贴如下代码

#include "ros/ros.h"
#include "std_msgs/String.h"

/**
  * This tutorial demonstrates simple receipt of messages over the ROS system.
 */
//一个回调函数,当有新消息到达chatter话题时它就会被调用
void chatterCallback(const std_msgs::String::ConstPtr& msg)
{
  ROS_INFO("I heard: [%s]", msg->data.c_str());
}

int main(int argc, char **argv)
{
  /**
   * The ros::init() function needs to see argc and argv so that it can perform
   * any ROS arguments and name remapping that were provided at the command line.
   * For programmatic remappings you can use a different version of init() which takes
   * remappings directly, but for most command-line programs, passing argc and argv is
   * the easiest way to do it.  The third argument to init() is the name of the node.
   *
   * You must call one of the versions of ros::init() before using any other
   * part of the ROS system.
   */
  ros::init(argc, argv, "listener");

  /**
   * NodeHandle is the main access point to communications with the ROS system.
   * The first NodeHandle constructed will fully initialize this node, and the last
   * NodeHandle destructed will close down the node.
   */
  ros::NodeHandle n;

  /**
   * The subscribe() call is how you tell ROS that you want to receive messages
   * on a given topic.  This invokes a call to the ROS
   * master node, which keeps a registry of who is publishing and who
   * is subscribing.  Messages are passed to a callback function, here
   * called chatterCallback.  subscribe() returns a Subscriber object that you
   * must hold on to until you want to unsubscribe.  When all copies of the Subscriber
   * object go out of scope, this callback will automatically be unsubscribed from
   * this topic.
   *
   * The second parameter to the subscribe() function is the size of the message
   * queue.  If messages are arriving faster than they are being processed, this
   * is the number of messages that will be buffered up before beginning to throw
   * away the oldest ones.
   */
  // 通过主节点订阅chatter话题。每当有新消息到达时,ROS将调用chatterCallback()函数。
  ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback);

  /**
   * ros::spin() will enter a loop, pumping callbacks.  With this version, all
   * callbacks will be called from within this thread (the main one).  ros::spin()
   * will exit when Ctrl-C is pressed, or the node is shutdown by the master.
   */
  // ros::spin()启动了一个自循环,它会尽可能快地调用消息回调函数。
  ros::spin();
    

  return 0;
}

同样地,我们来总结一下:

  • 初始化ROS系统
  • 订阅chatter话题
  • 开始spin自循环,等待消息的到达
  • 当消息到达后,调用chatterCallback()函数

1.3 构建节点

cmake_minimum_required(VERSION 2.8.3)
project(beginner_tutorials)

## Find catkin and any catkin packages
find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs genmsg)

## Declare ROS messages and services
add_message_files(FILES Num.msg)
add_service_files(FILES AddTwoInts.srv)

## Generate added messages and services
generate_messages(DEPENDENCIES std_msgs)

## Declare a catkin package
catkin_package()

## Build talker and listener
include_directories(include ${catkin_INCLUDE_DIRS})

add_executable(talker src/talker.cpp)
target_link_libraries(talker ${catkin_LIBRARIES})
add_dependencies(talker beginner_tutorials_generate_messages_cpp)

add_executable(listener src/listener.cpp)
target_link_libraries(listener ${catkin_LIBRARIES})
add_dependencies(listener beginner_tutorials_generate_messages_cpp)

1.4 测试发布者订阅者

$ roscore
# 在catkin工作空间中
$ cd ~/catkin_ws
$ source ./devel/setup.bash
# 运行 talker 发布者
$ rosrun beginner_tutorials talker      # (C++)
$ rosrun beginner_tutorials talker.py   # (Python)
# 运行 listener 订阅者
$ rosrun beginner_tutorials listener     # (C++)
$ rosrun beginner_tutorials listener.py  # (Python)

二、编写简单的服务和客户端(C++)

2.1 编写服务节点

在beginner_tutorials包中创建src/add_two_ints_server.cpp文件并粘贴以下内容进去:

#include "ros/ros.h"
// beginner_tutorials/AddTwoInts.h是从我们之前创建的srv文件中生成的头文件。
#include "beginner_tutorials/AddTwoInts.h" 

// 提供了AddTwoInts服务,它接受srv文件中定义的请求(request)和响应(response)类型,并返回一个布尔值。
bool add(beginner_tutorials::AddTwoInts::Request  &req,
         beginner_tutorials::AddTwoInts::Response &res)
{
  res.sum = req.a + req.b;
  ROS_INFO("request: x=%ld, y=%ld", (long int)req.a, (long int)req.b);
  ROS_INFO("sending back response: [%ld]", (long int)res.sum);
  return true;
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "add_two_ints_server");
  ros::NodeHandle n;
  // 创建服务
  ros::ServiceServer service = n.advertiseService("add_two_ints", add);
  ROS_INFO("Ready to add two ints.");
  ros::spin();

  return 0;
}

2.2 编写客户端节点

在beginner_tutorials包中创建src/add_two_ints_client.cpp文件并粘贴以下内容进去

#include "ros/ros.h"
#include "beginner_tutorials/AddTwoInts.h"
#include <cstdlib>

int main(int argc, char **argv)
{
  ros::init(argc, argv, "add_two_ints_client");
  if (argc != 3)
  {
    ROS_INFO("usage: add_two_ints_client X Y");
    return 1;
  }

  ros::NodeHandle n;
  // 为add_two_ints服务创建一个客户端。
  ros::ServiceClient client = n.serviceClient<beginner_tutorials::AddTwoInts>("add_two_ints");
  // 实例化一个自动生成的服务类,并为它的request成员赋值。一个服务类包括2个成员变量:request和response,以及2个类定义:Request和Response。
  beginner_tutorials::AddTwoInts srv;
  srv.request.a = atoll(argv[1]);
  srv.request.b = atoll(argv[2]);
  // 实际上调用了服务。由于服务调用被阻塞,它将在调用完成后返回。
  if (client.call(srv))
  {
    ROS_INFO("Sum: %ld", (long int)srv.response.sum);
  }
  else
  {
    ROS_ERROR("Failed to call service add_two_ints");
    return 1;
  }

  return 0;
}

2.3 构建节点

再来编辑一下beginner_tutorials里面的CMakeLists.txt文件,文件位于~/catkin_ws/src/beginner_tutorials/CMakeLists.txt,并将下面的代码添加在文件末尾:

add_executable(add_two_ints_server src/add_two_ints_server.cpp)
target_link_libraries(add_two_ints_server ${catkin_LIBRARIES})
add_dependencies(add_two_ints_server beginner_tutorials_gencpp)

add_executable(add_two_ints_client src/add_two_ints_client.cpp)
target_link_libraries(add_two_ints_client ${catkin_LIBRARIES})
add_dependencies(add_two_ints_client beginner_tutorials_gencpp)

现在可以运行catkin_make

# 在你的catkin工作空间下
cd ~/catkin_ws
catkin_make

2.4 测试服务和客户端

# 运行服务
$ rosrun beginner_tutorials add_two_ints_server     # (C++)
$ rosrun beginner_tutorials add_two_ints_server.py  # (Python)
#运行客户端
$ rosrun beginner_tutorials add_two_ints_client 1 3     # (C++)
$ rosrun beginner_tutorials add_two_ints_client.py 1 3  # (Python)
❯❯ catkin_ws  19:17 rosrun beginner_tutorials add_two_ints_server
[ INFO] [1659093578.679162016]: Ready to add two ints.
[ INFO] [1659093599.569586189]: request: x=3, y=1
[ INFO] [1659093599.569654088]: sending back response: [4]
[ INFO] [1659093609.078840971]: request: x=1, y=33
[ INFO] [1659093609.078888220]: sending back response: [34]

❯❯ catkin_ws  19:19 rosrun beginner_tutorials add_two_ints_client 1 33
[ INFO] [1659093609.079048726]: Sum: 34

posted @ 2022-07-31 11:37  Oddpage  阅读(227)  评论(0编辑  收藏  举报