1. 程式人生 > >ROS 編寫一個簡單的釋出者和訂閱者(C++)

ROS 編寫一個簡單的釋出者和訂閱者(C++)

0 編寫釋出者節點

節點是在ROS裡面的一個專業術語,它可以被ROS的網路所連結。在這裡我們將建立一個名叫“talker”的釋出者節點,它將連續的廣播一個訊息。

改變你現在的位置到你之前在catkin 工作區域裡建立的beginner_tutorials 包。

0.1 程式碼

在beginner_tutorials包裡建立一個src資料夾:

這個目錄將包含我們所建立的beginner_tutorials的原始檔。

在beginner_tutorials裡面建立一個src/talker.cpp檔案,然後將下面的程式碼貼到裡面:

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

#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.
   */
  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.
   */
  ros::Publisher chatter_pub = n.advertise<std_msgs::String>("chatter", 1000);

  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;
  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("%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();

    loop_rate.sleep();
    ++count;
  }


  return 0;
}

0.2 程式碼的解釋

現在我們來分割程式碼.

#include "ros/ros.h"
ros/ros.h是一個十分方便的標頭檔案,它包含了打多數ROS系統裡使用公共共有部分的所有標頭檔案。
<pre name="code" class="cpp">#include "std_msgs/String.h"
這個標頭檔案存在於std_msgs包中,它是在這個包裡由String.msg檔案自動生成的。關於更多的對於訊息的定義,可以參考msg頁。
<pre name="code" class="cpp">ros::inti(argc  ,argv,  "talker");
這是安裝ROS,它允許ROS可以通過命令列對名稱進行重對映,但是現在不是特別重要。
它也允許我們對我們的節點進行專有名稱的指定。不過,節點的名稱必須是唯一的。這個名字必須是一個基本名稱,不能有/在裡面。
ros::NodeHandle n;
建立處理這一過程的節點。在第一個NodeHandle建立的時候將會初始化節點,在最後一個NodeHandle消失的時候將會清除所有節點
使用的資源。
ros::Publisher chatter_pub = n.advertise<std_msgs::String>("chatter",1000);
告訴master我們將要在chatter的話題中釋出一個std_msgs/String型別的訊息。它允許master告訴所有正在監聽chatter的節點,我們將
要在這話題裡面釋出資料了。第二個引數是我們釋出佇列的大小。通過這種方式,我們釋出的夠快的話,它將可以在開始清楚舊的數
據之前,快取最大1000個訊息。
NodeHandle::advertise() 返回一個 ros::Publisher物件,它為兩個目的服務:1)它包含了一個publish()方法,會讓你在你建立的話題裡
面釋出訊息;2)當它越界的話,它將不被通知。
<pre name="code" class="cpp">ros::Rate loop_rate(10);
一個 ros::Rate物件允許你制定一個回送的頻率。它將會記錄自從上一次Rate::sleep()到現在多長時間,並且在正確時間數的時候沉睡。
在這個例子裡我們希望在10hz的執行。
<pre name="code" class="cpp">int count  =  0;
while (ros::ok())
{
通過預設roscpp將會案子一個SIGINT handler,這個handler可以使用Ctrl-C來處理,如果觸發了話,它將會導致ros::ok()返回false。
ros::ok()將會返回false如果:
  • 一個SIGINT 被接受了(Ctrl-C)
  • 我們因為另外一個相同名字的節點被網路踢出去了
  • ros::shutdown()已經被應用的另外一個部分呼叫了
  • 所有的ros::NodeHandles被銷燬了

一旦ros::ok()返回false,所有的ROS 呼叫將會失敗。

std_msgs::String msg;;

std::stringstream ss;
ss<<"hello world" <<count;
msg.data =ss.str();

我們在ROS裡面使用一個訊息更新的類來廣播訊息,這個類通常在msg檔案裡形成。更加複雜的資料結構也是可能的,但我們這裡使用了一個標準的String訊息,它有一個成員:“data”。
chatter_pub.publish(msg);
我們實際上對所有連結它的都廣播了訊息。
ROS_INFO("%s",  msg.data.c_str());
ROS_INFO 和友類是我們對printf/count 的代替品。
ros::spinOnce();
對於這個簡單的程式,呼叫ros::spinOnce()不是必須的,因為我們沒有收到任何的回撥。然而,如果你在這個應用裡新增一個訂閱者
並且不使用ros::spinOnce(),你的回撥將不會被呼叫。所以最好的辦法是加上它。
loop_rate.sleep();
現在我們使用ros::Rate物件來設定沉睡,然後在10hz訂閱速度的時候提醒我們。
下面有一個精簡版的原理:
  • 初始化ROS系統;
  • 建議我們將在chatter話題裡對master釋出一個std_msgs/String 的訊息
  • 當在釋出訊息時一秒十次將會迴環(loop)

現在我們需要寫一個接受訊息的節點。

1 編寫接受訊息的節點

1.1 程式碼

在beginner_tutorials裡面建立一個src/listener.cpp檔案,複製下面的程式碼到裡面去:


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

/**
 * This tutorial demonstrates simple receipt of messages over the ROS system.
 */
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.
   */
  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();

  return 0;
}

1.1程式碼解釋

現在我們分開來進行,忽略一些之前解釋過的。

void chatterCallback(const std_msgs::String::ConstPtr& msg)
{
  ROS_INFO("I heard: [%s]", msg->data.c_str());
}
這是一個回撥函式,它將在一個新的訊息到達chatter話題的時候進行回撥。這個訊息在一個boost shared_ptr中被傳遞,這意味這你如
果想,可以將它儲存為off,不用擔心他在你的下層被刪除,不用負責潛在的資料。
ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback);
用master來對chatter話題進行訂閱。ROS每當一個新的訊息到達時會呼叫一個chatterCallback()函式。第二個引數是佇列的大小,以便
我們不能快速的處理訊息,通過這種方式,如果佇列到達了1000個訊息,我們將在下一個新的訊息到來的時候扔掉舊的。
NodeHandle::subscribe()返回一個ros::Subscriber物件,這個物件你必須一直存在除非你不希望訂閱了。當這個訂閱物件被銷燬時,它
將自動不被chatter話題訂閱。
這裡有一些版本的NodeHandle::subscribe()函式,它允許你知名一個類的成員函式,甚至是被一個Boost.Function object呼叫的任何東西。
這個roscpp overview 包含了更多的資訊。
ros::spin();
ros::spin()進入了一個迴環,這個迴環儘可能快的呼叫了訊息回撥。不用擔心,它不會使用過多的CPU。一旦ros::ok()返回false,ros::spin()
將會退出。這意味著ros::shutdown()已經被呼叫了,既不是通過預設的Ctrl-C handler讓master告訴我們要關閉,也不是手動呼叫了它。
和上面一樣,這裡有一個精簡的版本:
  • 初始化ROS系統
  • 訂閱chatter話題
  • 執行,等待訊息到達
  • 當一個訊息到達後,chatterCallback()函式被呼叫

3. 建立你自己的節點

你可以使用之前Catkin_create_pkg裡面建立的package.xml和CMakeList.txt檔案。

形成的CMakeList.txt應該像下面的:

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(DIRECTORY msg FILES Num.msg)
add_service_files(DIRECTORY srv FILES AddTwoInts.srv)

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

## Declare a catkin package
catkin_package()

不用擔心修改了註釋的例子,簡單的新增這寫行到你的CMakeList.txt的底部。
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)

你最後的CMakeList.txt應該像這樣:

它將會建立兩個可執行檔案——talker和listener,它們預設會到你的devel space裡面的包的資料夾下,資料夾預設在 ~/catkin_ws/devel/lib<package_name>。

記住你為可執行檔案目標必須新增依賴到訊息生成目標:

add_dependencies(talker beginner_tutorials_generate_messages_cpp)
這個確保這個包的訊息標頭檔案在被使用之前已經形成了。如果你從其他包裡使用的訊息在你catkin工作區裡,你也需要為他們各自形成的目標新增依賴,因為catkin建立是平行的建立所有的工程的。對於*Groovy*你可以使用下面的來決定所有的目標:
target_link_libraries(talker ${catkin_LIBRARIES})
你能直接呼叫或者你能使用rosrun來呼叫他們。它們不在'<prefix>/bin',因為當安裝你的包到系統裡去時將會汙染PATH。
如果你希望你的可執行檔案在安裝的時候在PATH裡面,你能設定一個安裝目標,可以參考:catkin/CMakeList.txt
現在執行 catkin_make:

如果出現了
The specified base path "/home/exbot/catkin_ws/src/beginner_tutorials" contains a package but "catkin_make"
 must be invoked in the root of workspace
的錯誤,是因為catkin_make這個命令只能在工作區頂層執行,它只會編譯~/catkin_ws/src下的原始碼。如果想要在編譯
其他資料夾下的原始碼可以這樣:

source後面的是你扔原始碼的路徑

或者



<pre name="code" class="cpp"><pre name="code" class="cpp">