rosserial_arduino學習筆記14《NodeHandle和ArduinoHardware的高階配置》
rosserial_arduino軟體包對於使用者是為了work out-of-box ,但使用者可能需要更改ros.h和ArduinoHardware.h以更好地適應他們的需要。在本教程中,我們將更改兩個檔案以演示一些高階設定。
1 條件
1.1 硬體
-
FTDI分線板或類似的UART到USB轉換器
- 兩個裝置的USB電纜
- 一些跳線連線兩個裝置
1.2 目標
1.2 釋出者/訂閱者數量和輸入/輸出緩衝區
Arduino Mega有8 kB的SRAM,遠遠超過大多數其他Arduino板(Uno有2 kB,Leonardo有2.5 kB)。這使我們能夠擁有更多的釋出者/訂閱者並使用更大的訊息。雖然我們可能永遠不需要為Arduino Mega change those numbers,因為預設值足夠大,但對於SRAM有限的小型主機板,我們需要減少記憶體使用量。
1.2.2 更改串列埠
Arduino Mega總共有4個串列埠:
物件名稱 |
RX Pin |
TX Pin |
Serial |
0 |
1 |
SERIAL1 |
19 |
18 |
Serial2 |
17 |
16 |
Serial3 |
15 |
14 |
通常,我們使用Serial與Arduino Mega進行通訊,Serial連線到UART到USB橋接器,並顯示為我們在計算機上看到的埠。但是對於本教程,我們將使用Serial1。由於Serial1無法直接與計算機通訊,因此我們使用UART轉USB橋(FTDI分線板)。
1.2.3 改變Baudate
預設情況下,rosserial使用57600作為通訊的波特率。這個速率不是Arduino可以達到的最大速率,當有大量資訊需要傳送回ROS時,波特率可能成為瓶頸。
工作在16 Mhz的Arduino Mega可以通過高達每秒2M位(bps)的波特率進行通訊,其他板(如
在本教程中,我們將波特率從57.6 Kbps更改為500 Kbps。
2 程式
我們將為此示例提供3個原始檔。main sketch,ros.h和ArduinoHardware.h。因為我們的許多變化都在幕後並且不影響我們如何使用rosserial,所以使用hello world sketch能夠進行最少的修改。原始的ros.h和ArduinoHardware.h可以在rosocrial_arduino包的src / ros_lib /中找到,也可以在Arduino庫中生成的ros_lib中找到。您可以直接修改它們以達到相同的效果,但建議將它們新增到sketch資料夾中,以便每個sketch進行更改並持續重新生成ros_lib。
2.1 Main Sketch
我們將首先建立一個新草圖並將以下程式碼複製到它:
/* * rosserial Publisher Example * Prints "hello world!" */ #include "ros.h" #include <std_msgs/String.h> ros::NodeHandle nh; std_msgs::String str_msg; ros::Publisher chatter("chatter", &str_msg); char hello[13] = "hello world!"; void setup() { nh.initNode(); nh.advertise(chatter); } void loop() { str_msg.data = hello; chatter.publish( &str_msg ); nh.spinOnce(); delay(1000); }
2.2 ros.h
ros.h是對NodeHandle定義,我們將通過單擊Serial Monitor下面的向下箭頭圖示在Arduino中建立一個新選項卡,將其命名為ros.h,並將以下內容複製到它:
#ifndef _ROS_H_ #define _ROS_H_ #include "ros/node_handle.h" #include "ArduinoHardware.h" namespace ros { // default is 25, 25, 512, 512 typedef NodeHandle_<ArduinoHardware, 10, 15, 128, 256> NodeHandle; // This is legal too and will use the default 25, 25, 512, 512 //typedef NodeHandle_<ArduinoHardware> NodeHandle; } #endif
2.3 ArduinoHardware.h
ArduinoHardware.h,是Arduino平臺的硬體定義,與ros.h類似,我們將建立一個名為ArduinoHardware.h的新選項卡,並將以下程式碼複製到其中:
#ifndef ROS_ARDUINO_HARDWARE_H_ #define ROS_ARDUINO_HARDWARE_H_ #if ARDUINO>=100 #include <Arduino.h> #else #include <WProgram.h> #endif #include <HardwareSerial.h> #define SERIAL_CLASS HardwareSerial class ArduinoHardware { public: ArduinoHardware() { iostream = &Serial1; baud_ = 500000; } void setBaud(long baud) { this->baud_= baud; } int getBaud() { return baud_; } void init() { iostream->begin(baud_); } int read() { return iostream->read(); }; void write(uint8_t* data, int length) { for(int i=0; i<length; i++) { iostream->write(data[i]); } } unsigned long time() { return millis(); } protected: SERIAL_CLASS* iostream; long baud_; }; #endif
3 程式解釋
3.1 Main Sketch
#include "ros.h" #include <std_msgs/String.h>
我們發現它的主草圖唯一的區別是如何包括ros.h,括號<ros.h>在原來的Hello World是由引號替換“ros.h”。這告訴編譯器在本地路徑中查詢檔案,然後在其他庫中搜索它。其他一切都與你好世界的例子相同。
3.2 ros.h
// default is 25, 25, 512, 512 typedef NodeHandle_<ArduinoHardware, 10, 15, 128, 256> NodeHandle;
這使我們的NodeHandle有10個Publishers,15個Subscriber,128個位元組用於輸入緩衝區,256個位元組用於輸出緩衝區。
3.3 ArduinoHardware.h
#include <HardwareSerial.h> #define SERIAL_CLASS HardwareSerial
這裡我們包括與之通訊的序列物件的標頭。序列物件類必須擁有read(),write()和begin(baudrate)成員函式等實現。Serial和Serial1都是HardwareSerial物件。
ArduinoHardware() { iostream = &Serial1; baud_ = 500000; }
在這裡,我們為ArduinoHardware建立預設建構函式,並將我們使用的串列埠設定為Serial1,並將波特率設定為500 kbps。
4 編譯並上傳程式碼
程式碼是像往常一樣編譯和上傳的。 編譯後,您將能夠看到這樣的程式碼訊息
Sketch uses 9,552 bytes (3%) of program storage space. Maximum is 253,952 bytes. Global variables use 1,130 bytes (13%) of dynamic memory, leaving 7,062 bytes for local variables. Maximum is 8,192 bytes.
通過改變緩衝區大小和釋出者/訂閱者數量,動態記憶體使用量也將發生變化。
5 執行程式碼
我們現在將使用Serial1與ROS進行通訊。斷開USB電纜與Arduino的連線,將FTDI分線板連線到Arduino Mega,如下所示:
FTDI Arduino Mega VCC -> 5V TXO -> Pin 19 RXI -> Pin 18 GND -> GND
使用USB電纜將FTDI分線板連線到計算機。
現在,在新的終端視窗中啟動roscore:
roscore
接下來,執行rosserial客戶端應用程式,將Arduino訊息轉發給ROS的其餘部分。確保使用正確的串列埠:
rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0 _baud:=500000
最後,通過啟動新的終端視窗並輸入以下內容,觀看來自Arduino的問候:
rostopic echo chatter
6 附加功能
ros.h和ArduinoHardware.h許可證。
/* * Software License Agreement (BSD License) * * Copyright (c) 2011, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote prducts derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */