
引言 这篇文档主要介绍 RT-Thread 如何使用串口或者无线和 ROS 连接,会包含这么些内容: 第一部分:ROS 环境搭建 第二部分:RT-Thread rosserial 软件包 第二部分:RT-Thread 添加 USART2 和 PWM 第三部分:RT-Thread 使用 ESP8266 AT 固件联网 ]( }; E; @# c9 |/ b8 [( B 这里先介绍一下什么是 ROS?为什么要和 ROS 连接? 机器人操作系统 ROS (Robots Operating System) 最早是斯坦福大学的一个软件框架,现在不管是工业机器人,还是娱乐用的机器人都运行着 ROS。![]() 图片来源网络,如有侵权请联系删除 一个机器人通常有很多个部件、传感器,为了保证机器人不会因为某一个传感器故障,导致整个系统瘫痪,所以采用了分布式的节点,利用不同节点之间的通讯收集传感器数据和控制指令,这篇文档后面会使用到的通讯协议就是 rosserial。和 ROS 连接的好处在于,一方面由 ROS 管理各个机器人节点更稳定,另一方面 ROS 现在已经有了非常多成熟的软件包,使用 ROS 就可以非常方便的为自己的机器人添加摄像头图像识别、激光雷达建图导航等高级功能。不过这篇文档只会涉及 RT-Thread 和 ROS 建立基本的连接,实现小车的运动控制,之后可能会有后续文档介绍如何连接激光雷达建图,并进行全局路径规划。这篇文章假定大家都已经会用 RT-Thread 的 env 工具下载软件包,生成项目上传固件到 stm32 上,并且熟悉 Ubuntu 的基本使用。 这里的开发环境搭建其实是需要搭建 2 份,一份是小车上的 ARM 开发板 (树莓派,NanoPi 什么的),另一个则是自己的电脑,因为我们希望把电脑作为 ROS 从节点,连接到小车上的 ROS 主节点,不过开发板和电脑的 ROS 安装是一模一样的。 ! P% W/ b( |2 @6 }5 d5 { 既然要和 ROS 连接,那么首先就得要有一个正常运行的 ROS。安装 ROS 其实非常简单,这里推荐使用 Ubuntu 18 (开发板推荐系统用 Armbian),因为官方对 Ubuntu 的支持优先级是最高的,安装教程也可以参照 官网:http://wiki.ros.org/melodic/Installation/UbuntuO3 H$ x/ ?& r( b2 | { 只需要输入下面的 4 行命令,就在 Ubuntu 上装好了 ROS。2 @) q/ o* M% @; r* q7 f 1 sudo sh -c 'echo "deb http://mirror.tuna.tsinghua.edu.cn/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' 3 e! t: p4 B8 S 2 sudo apt-key adv --keyserver 'hkp://keyserver.ubuntu.com:80' --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C6545 v6 r' P5 G9 T 3 sudo apt update 4 sudo apt install ros-melodic-ros-base 上面我使用了清华大学的镜像源,这样从国内下载 ROS 会快很多,而且我只安装了 ROS 的基本软件包,没有安装图形化软件包 gviz,gazebo 什么的,因为后面也没有用到。 - f7 @% N- G# q5 Y* s; i8 G I) z; v 1.2 ROS 环境初始化 / J8 u D5 x' Y# g5 s' j) _ ; L$ I7 r# ?8 f# d+ \4 v- z ` ROS 安装好之后还需要进行初始化,不过也是只有短短几行命令: 1 sudo rosdep init : t6 E' M- R, p8 ^& v) P R 2 rosdep update 3% |. M$ ~/ R+ i7 h3 n 4 echo "source /opt/ros/melodic/setup.bash" >> ~/.bashrc 5 source ~/.bashrc2 O6 G) b3 a, u0 A 1.3 启动 ROS Z1 E2 E3 ^* [9 G" j 7 d$ ^$ s1 m6 R4 H4 F 启动 ROS 的话我们需要确保它是常驻后台运行的,所以我们可以使用 tmux:8 f# I" U2 [* `7 t- H 1 roscore, V1 B- {, j1 R& ]1 U, n6 F$ R* N: x 在 tmux 里启动了 ROS 主节点后,我们就可以 Ctrl + B D 退出了,而 ROS 主节点依旧在后台运行。 : U& G9 m' Y9 H& V( R 1.4 参考文献
这一部分会介绍如何使用串口将运行着 RT-Thread 的 STM32 开发板和运行着 ROS 的 ARM 开发板连接,看起来差不多就是这样。 ![]() 2.1 RT-Thread 配置- o. W* }2 R, H . i# U3 K7 O2 Q D, I 首先我们需要打开 usart2,因为 usart1 被 msh 使用了,保留作为调试还是挺方便的。 ![]() 6 e; f5 n- x6 |7 j c$ Z3 b, K 在 CubeMX 里我打开了 USART2,另外还打开了 4 路 PWM,因为我后面使用了 2 个电机,每个电机需要 2 路 PWM 分别控制前进和后退。接下来还需要在 menuconfig 里面打开对应的选项,考虑到有的开发板默认的 bsp 可能没有这些选项,可以修改 board/Kconfig 添加下面的内容。 4 ~. M" b* p) C1 }2 A 串口的配置: 1 menuconfig BSP_USING_UART 2 bool "Enable UART"2 G* c+ C0 Q0 J 3 default y 4 select RT_USING_SERIAL 5 if BSP_USING_UART/ W3 E4 y4 u: G4 r" G4 ]0 @" ?& e 6 config BSP_USING_UART1# u8 d8 ]6 e3 t" @' z, G% D3 K 7 bool "Enable UART1" 8 default y. P) | m& D% E6 y* x- I 9 10 config BSP_UART1_RX_USING_DMA& y% O6 w6 `, e* H5 n 11 bool "Enable UART1 RX DMA"0 C1 z7 U% s3 j+ z 12 depends on BSP_USING_UART1 && RT_SERIAL_USING_DMA 13 default n- z+ J5 o+ C5 V% N; o9 D+ Z& l 145 s& s* M" u& ~6 _) R 15 config BSP_USING_UART2 16 bool "Enable UART2"& ? \% ?5 y- O$ U# I; \! H9 ~ m 17 default y' l. O; `/ u; y: v; W 18 19 config BSP_UART2_RX_USING_DMA 20 bool "Enable UART2 RX DMA" 21 depends on BSP_USING_UART2 && RT_SERIAL_USING_DMA 22 default n+ ~0 q4 J# X" `* P. ?5 r/ ~' e. w) } 23 endif: z! H# ^" z0 A- F PWM 的配置: 8 ]3 J. i( c) C 1 menuconfig BSP_USING_PWM 0 X/ K4 W7 R' s( H- M) J2 g 2 bool "Enable pwm" 3 default n 4 select RT_USING_PWM2 w6 ^0 C( E1 T 5 if BSP_USING_PWM) W ]! R \2 |5 e7 C 6 menuconfig BSP_USING_PWM38 g; I0 A0 H: k7 Z9 @ 7 bool "Enable timer3 output pwm". _3 O4 o9 C k7 z6 S 8 default n 9 if BSP_USING_PWM3 10 config BSP_USING_PWM3_CH17 b7 f7 ~5 @3 a/ \9 v2 l 11 bool "Enable PWM3 channel1"" i+ h# m' v; F2 N* [4 ` 12 default n' D: u/ b9 c8 A- _ 13 config BSP_USING_PWM3_CH2 14 bool "Enable PWM3 channel2" 15 default n 16 config BSP_USING_PWM3_CH3 17 bool "Enable PWM3 channel3"/ G, T/ u% L: t4 c- Q( T2 m 18 default n 19 config BSP_USING_PWM3_CH4 20 bool "Enable PWM3 channel4" 21 default n4 w; n8 b6 h8 | 22 endif- `) i- ^8 K) c9 ^ 23 endif ! Z% O: w& g0 [* } 这样我们在 env 下就可以看到有对应的配置了, ![]() ![]() ![]() ) J5 E1 h# C3 d1 a/ ] 可以看到上面默认的串口就是 USART2,这样我们就可以生成对应的工程了: Y) y' c$ s2 D, V+ C% v, P 1pkgs --update2scons --target=mdk5 -s. s( k2 M2 c3 t" A# \ 4 c R- Y* e- u9 t1 J4 p 如果我们打开 Keil 项目,首先需要把 main.c 修改为 main.cpp,因为 rosserial 很多数据格式的定义都是用 C++ 写的,所以如果要使用 rosserial 库,我们先得把后缀改为 cpp,这样 Keil 就会用 C++ 编译器编译。" r! y+ `8 N/ J ![]() 6 Q$ T: b# n/ G 3 u4 @, }% B/ ` 代码不是特别长,我也添加了一些注释,所以这里就不一行行分析了。 1 #include <rtthread.h> 2 k: n0 \3 `$ u' J 2 #include <rtdevice.h>& Y5 k% }1 l( C: R8 d. ` 3 #include <board.h> 4 5 #include <ros.h>1 N+ e4 ^; o" R* u+ u 6 #include <std_msgs/Float64.h> 7 #include <geometry_msgs/Twist.h>: i8 H% r7 ~; g$ I& m7 F. N. C 8 #include "motors.h". Q$ m1 u" H# |9 ~+ f7 S1 x 9; k3 r. C; g7 N) r2 u! N; j- r 10 ros::NodeHandle nh; 11 MotorControl mtr(1, 2, 3, 4); //Motor 126 K8 X( Q1 K8 P6 }8 q+ X0 Y 13 bool msgRecieved = false; 14 float velX = 0, turnBias = 0; 15 char stat_log[200];: v; Y4 @3 J6 [ 16% q% F" e: I$ e2 `8 p 17 // 接收到命令时的回调函数4 A% p- e# z5 I4 ~% S 18 void velCB( const geometry_msgs::Twist& twist_msg) 19 {9 I+ d' g' o' Q; {7 c! f2 P 20 velX = twist_msg.linear.x;* J( K! p% C" M7 y* R. ~ w 21 turnBias = twist_msg.angular.z;( f6 m0 V$ v) y2 h" f" x 22 msgRecieved = true;1 e% x) i' F/ ]$ A 23 }0 j! ]" F" i# u; S: @5 H& r 24 s( o* z! P! _( G 25 //Subscriber+ w4 o! A4 D" R; z9 P2 C' K6 j) \' { 26 ros::Subscriber<geometry_msgs::Twist> sub("cmd_vel", velCB ); 27' i9 r+ E0 A: ?* \ 28 //Publisher+ @# |9 n, M0 I# Z; x 29 std_msgs::Float64 velX_tmp; 30 std_msgs::Float64 turnBias_tmp; 31 ros: ![]() 32 ros: ![]() 33 34 static void rosserial_thread_entry(void *parameter) 35 {: t! T0 D+ T. E* u& J 36 //Init motors, specif>y the respective motor pins 37 mtr.initMotors(); 38: ?, ]. P1 s8 G: D7 N 39 //Init node> 40 nh.initNode();8 z) @9 p( S# g& K# p: M1 F 412 K# L6 S$ y4 i- @3 r( t8 ^4 K 42 // 订阅了一个话题 /cmd_vel 接收控制指令 43 nh.subscribe(sub); 448 k' W; i$ q: N 45 // 发布了一个话题 /vel_x 告诉 ROS 小车速度" o3 t8 l( {; {$ k 46 nh.advertise(xv); 47) }) k0 v4 P0 [0 S 48 // 发布了一个话题 /turn_bias 告诉 ROS 小车的旋转角速度1 e9 u5 M) Z7 c7 o5 h p: v; v; Z 49 nh.advertise(xt);" B$ l0 T$ R! B4 C 50 51 mtr.stopMotors();+ r9 }, E0 C, ? 52 53 while (1)% d t8 @# _2 j 54 {! n& j# U4 H7 H0 I, Y* ?9 R1 ?5 r 55 // 如果接收到了控制指令 [2 \- S; b+ ?( v; H* o8 V 56 if (msgRecieved) 8 S7 z4 @8 J: l9 y* ~8 X) B8 L0 b ^ 57 { l$ f8 [' q" W) q# `9 K 58 velX *= mtr.maxSpd; 59 mtr.moveBot(velX, turnBias); 60 msgRecieved = false;0 A$ p [ _0 X" e8 t& ?4 j 61 }8 M3 n$ o( K& y, a 62 63 velX_tmp.data = velX; 64 turnBias_tmp.data = turnBias/mtr.turnFactor; 656 z7 a, p5 G* @" G 66 // 更新话题内容 67 xv.publish( &velX_tmp ); 68 xt.publish( &turnBias_tmp );- B! s8 ?% d' b8 Q/ @ 692 A6 X7 H( M" U) D- D. {5 B 70 nh.spinOnce(); 71 }; K R \) N: u7 F2 P 72 } 73; k" R0 w( l4 ]( U+ S" Z6 V8 v$ h 74 int main(void) 75 { 76 // 启动一个线程用来和 ROS 通信3 l5 W- A" e4 ` 77 rt_thread_t thread = rt_thread_create("rosserial", rosserial_thread_entry, RT_NULL, 2048, 8, 10); 78 if(thread != RT_NULL) 79 {9 ~- i9 k9 J& T" t# i* T% A 80 rt_thread_startup(thread);7 ^( w t8 Y1 _; M0 t! ~) c 81 rt_kprintf("[rosserial] New thread rosserial\n");, h3 P2 P1 M, S9 M 82 } 83 else6 a4 m$ g! I* H6 |$ g } 84 { 85 rt_kprintf("[rosserial] Failed to create thread rosserial\n"); 86 } 87 return RT_EOK; 88 } ( ^3 d( M+ L0 j 另外还有对应的电机控制的代码,不过这个大家的小车不同,驱动应当也不一样,我这里由于小车电机上没有编码器,所以全部是开环控制的。 1#include <rtthread.h>! v+ C; Y2 U+ U! |+ |. s" D : L d7 \# r. A0 M! o9 ]- l 2 3class MotorControl {6 S r: L" A% B. r 4 public: 5 //Var0 L8 q o5 ~9 e! x) Q: [1 y 6 rt_uint32_t maxSpd; 7 float moveFactor;9 {+ K" f: H: m, N& S& `+ N 8 float turnFactor; 9; H- Z7 t N" P 10 MotorControl(int fl_for, int fl_back, 11 int fr_for, int fr_back);+ b/ s0 ^5 e# c9 ^. C 12 void initMotors();/ c. f0 A. O7 Y# v: ^7 h 13 void rotateBot(int dir, float spd);6 H4 T4 j- u; p( A7 q6 \ 14 void moveBot(float spd, float bias);: j: f- a% W. a, c( {( q 15 void stopMotors();, ]5 A; j$ x1 E 16 private:4 d& Y$ Q, ]2 J! [ a4 w 17 struct rt_device_pwm *pwm_dev; 18 //The pins0 p6 P9 L" w) M+ @3 d 19 int fl_for;% L% M5 W2 {) G3 r }* B 20 int fl_back; 21 int fr_for; 22 int fr_back; 23 int bl_for;0 J( l9 S+ N9 o7 ~, B( Z 24 int bl_back;! q# o+ ^. z8 l z' ^& ^4 Z9 S 25 int br_for; 26 int br_back;1 E$ ^ R0 P* n8 [: U, x 27}; motors.c 1#include <rtthread.h> - G5 L: ?5 k2 h/ v i! ~ 2#include <rtdevice.h> 3#include "motors.h"# e$ U1 o2 {8 ^3 c* a 4 5#define PWM_DEV_NAME "pwm3" 6 7MotorControl::MotorControl(int fl_for, int fl_back," T) ^0 O6 q/ O5 Q5 \5 H 8 int fr_for, int fr_back) ; q) ?- f+ u" Q6 T 9{. Y* Y; v, j I" V' M$ v5 _ 10 this->maxSpd = 500000;) q1 L0 F7 w: b& Q% o3 h2 `+ n; W 11 this->moveFactor = 1.0; 12 this->turnFactor = 3.0;. ^- {" K' a: Q9 C% o. i 131 Y& Z$ c) O! L) z$ x 14 this->fl_for = fl_for; 15 this->fl_back = fl_back;. z, H6 Y1 H; o. G$ e 16 17 this->fr_for = fr_for;1 ?# M6 W$ L: O0 |+ u' s5 x 18 this->fr_back = fr_back; 19}2 a$ J1 L) c: k 20 21void MotorControl::initMotors() { 22 /* 查找设备 */1 p" j- a4 [6 L: q" O1 q! Y 23 this->pwm_dev = (struct rt_device_pwm *)rt_device_find(PWM_DEV_NAME);0 c/ k( b" Y' w 24 if (pwm_dev == RT_NULL) 25 { 26 rt_kprintf("pwm sample run failed! can't find %s device!\n", PWM_DEV_NAME); 27 }: m# A* ~7 f: k. o# n2 r4 P& f 28 rt_kprintf("pwm found %s device!\n", PWM_DEV_NAME); 29 rt_pwm_set(pwm_dev, fl_for, maxSpd, 0);6 r2 j7 _+ o$ ? n% n+ E! l+ f 30 rt_pwm_enable(pwm_dev, fl_for); 31$ i3 `" L, s6 g9 H d 32 rt_pwm_set(pwm_dev, fl_back, maxSpd, 0); 33 rt_pwm_enable(pwm_dev, fl_back);% `# |2 Y1 I* [/ T- x" R 34 35 rt_pwm_set(pwm_dev, fr_for, maxSpd, 0); 36 rt_pwm_enable(pwm_dev, fr_for); 37' [) R: |4 A, {. N D8 v2 K% ?* D 38 rt_pwm_set(pwm_dev, fr_back, maxSpd, 0); 39 rt_pwm_enable(pwm_dev, fr_back);. q$ h" p3 _6 S1 l 40}& m. _' a- P* j% t. u1 i& n! ~. { 41! U0 X2 [: C* i& h) z9 T& X8 c 42// 小车运动! h) |9 e/ O9 G6 u% K$ U 43void MotorControl::moveBot(float spd, float bias) {& k. Q" \9 Q! _5 K) S 44 float sL = spd * maxSpd;: \5 }7 w2 E9 x9 B7 h& x- ~9 j. ` 45 float sR = spd * maxSpd; 46 int dir = (spd > 0) ? 1 : 0;! C3 l @/ W1 \$ o9 U3 p2 I 47- p4 d7 G4 c* F 48 if(bias != 0) 49 { 50 rotateBot((bias > 0) ? 1 : 0, bias); 51 return;+ W$ Y! w, S x; { 52 }& i' D9 X" n# B$ c9 o+ R+ x6 G 53 54 if( sL < -moveFactor * maxSpd)+ n: P7 L7 F$ Z" Z 55 { 56 sL = -moveFactor * maxSpd; 57 } 58 if( sL > moveFactor * maxSpd)! W+ g. |# c- l0 D- ^5 a2 z 59 { 60 sL = moveFactor * maxSpd; 61 }: V( }, S. Q- O L! e' W 62 63 if( sR < -moveFactor * maxSpd) 64 { 65 sR = -moveFactor * maxSpd; 66 }6 z- [! g0 |. y+ z* h- L 67 if( sR > moveFactor * maxSpd) 68 { 69 sR = moveFactor * maxSpd;/ c$ T# U$ s1 y$ e& a! N0 V) ~ 70 }) b9 z" t2 F) Z1 G; N/ q# S 71 72 if (sL < 0) 9 L* S* @) p' |8 K+ x 73 {! e2 B- Y; u- v% d6 r) G% \; i 74 sL *= -1;* O) g0 r( @, E, a/ m 75 } 76 77 if (sR < 0) ' j" _( g) a5 U2 _1 |* ]0 u 78 {, u2 v2 W1 q( B( e) R3 ~/ Q1 q 79 sR *= -1;4 |: p% |; l) ~( B 80 } 81 82 rt_kprintf("Speed Left: %ld\n", (rt_int32_t)sL); 83 rt_kprintf("Speed Right: %ld\n", (rt_int32_t)sR);/ H) C% H; k' d 84 85 if(dir)9 r5 F0 L' ^6 a5 M 86 {3 B! h) I* U( v( n" | 87 rt_pwm_set(pwm_dev, fl_for, maxSpd, (rt_int32_t)sL); 88 rt_pwm_set(pwm_dev, fl_back, maxSpd, 0);% g# @+ ~( h1 O 89 rt_pwm_set(pwm_dev, fr_for, maxSpd, (rt_int32_t)sR); 90 rt_pwm_set(pwm_dev, fr_back, maxSpd, 0);' L9 P) o/ z7 v1 f 91 } 92 else; X4 `, e' ]2 B; v$ j/ t; N 93 {8 e% \' `9 y7 m+ M- X; o 94 rt_pwm_set(pwm_dev, fl_for, maxSpd, 0);! d0 u2 A4 h' A3 O; P5 U! K 95 rt_pwm_set(pwm_dev, fl_back, maxSpd, (rt_int32_t)sL); 96 rt_pwm_set(pwm_dev, fr_for, maxSpd, 0);3 a n1 Z! f# ~+ a/ q0 h* k 97 rt_pwm_set(pwm_dev, fr_back, maxSpd, (rt_int32_t)sR); 98 } 993 Y9 F4 E( G4 u8 A 100 rt_thread_mdelay(1);# _: W/ R! C2 e! b. Y. z& U3 i! d 101} 1027 \3 B$ M$ o' p2 m Z4 G. [ 103& Y3 l% u/ _* V/ I 104// 小车旋转 105void MotorControl::rotateBot(int dir, float spd) {4 J8 p. _( X- X6 ] 106 float s = spd * maxSpd;1 _3 s7 [& W; X 107 if (dir < 0) 108 { 109 s *= -1;9 O+ { o% u' w/ {2 b$ m2 n 110 } 111 if(dir)" X1 T3 n* r4 J 112 {0 H$ `! ^$ t# `. O 113 // Clockwise 114 rt_pwm_set(pwm_dev, fl_for, maxSpd, (rt_int32_t)s); 115 rt_pwm_set(pwm_dev, fl_back, maxSpd, 0);& z6 c9 D3 d4 R 116 rt_pwm_set(pwm_dev, fr_for, maxSpd, 0); 117 rt_pwm_set(pwm_dev, fr_back, maxSpd, (rt_int32_t)s);$ z+ t. o1 U7 x! x( [) \* n3 Q6 h 118 } 119 else 120 { 121 // Counter Clockwise 122 rt_pwm_set(pwm_dev, fl_for, maxSpd, 0); 123 rt_pwm_set(pwm_dev, fl_back, maxSpd, (rt_int32_t)s); 124 rt_pwm_set(pwm_dev, fr_for, maxSpd, (rt_int32_t)s); 125 rt_pwm_set(pwm_dev, fr_back, maxSpd, 0);$ O& R$ W5 u2 V! G 126 }/ o8 z1 A2 }5 P& r9 i 127 rt_thread_mdelay(1); 128} 129 130//Turn off both motors 131void MotorControl::stopMotors() 132{ 133 rt_pwm_set(pwm_dev, fl_for, maxSpd, 0); 134 rt_pwm_set(pwm_dev, fl_back, maxSpd, 0);7 _/ d7 q+ c u4 S" z$ K 135 rt_pwm_set(pwm_dev, fr_for, maxSpd, 0); 136 rt_pwm_set(pwm_dev, fr_back, maxSpd, 0); 137}- h3 X% j, v1 P) y9 \ 一共只需要这么一点代码就可以实现和 ROS 的连接了,所以其实 ROS 也不是那么神秘,它就是因为简单好用所以才这么受欢迎的。既然 RT-Thread 已经配置好了,下一步就是 ROS 的配置了。3 {) N6 v3 _- E; F! L 2.2 ROS 配置 3 V1 t1 `6 j. u: w/ g0 M" ~ 我们把上面 RT-Thread 的固件传到板子上以后,可以用一个 USB-TTL 一边和 STM32 控制板的 USART2 连接,另一边插到 ARM 控制板的 USB 口,接下来就可以建立连接了,在 ARM 板上输入命令: 1 $ rosrun rosserial_python serial_node.py /dev/ttyUSB0 , R9 @8 P) _& L; @! U 如果看到下面的输出,那就成功建立连接了:8 l' f9 s+ M4 U6 a0 h9 C 1 tpl@nanopineoplus2:~$ rosrun rosserial_python serial_node.py /dev/ttyUSB09 O8 Z0 Q6 O9 [ / j5 S( s! U/ e$ w* I4 \ 2 [INFO] [1567239474.258919]: ROS Serial Python Node 3 [INFO] [1567239474.288435]: Connecting to /dev/ttyUSB0 at 57600 baud2 h/ q9 W2 n7 |( I/ {+ @ 4 [INFO] [1567239476.425646]: Requesting topics... 5 [INFO] [1567239476.464336]: Note: publish buffer size is 512 bytes 6 [INFO] [1567239476.471349]: Setup publisher on vel_x [std_msgs/Float64]! W: ~. N. `3 M. O& X 7 [INFO] [1567239476.489881]: Setup publisher on turn_bias [std_msgs/Float64] 8 [INFO] [1567239476.777573]: Note: subscribe buffer size is 512 bytes 9 [INFO] [1567239476.785032]: Setup subscriber on cmd_vel [geometry_msgs/Twist]. m! j3 w. H/ p3 C1 F% E 2.3 ROS 控制小车 , q4 F% q" i# D* \ e) x 既然已经成功建立连接了,下一步就是写小车控制的代码了。 H9 q, ]; L/ C' X. u, a( g ) Z$ N9 X" ]8 A& P$ P$ d$ s4 a 我们先初始化一个工作区间: 1 $ mkdir catkin_workspace && cd catkin_workspace2 ?$ V0 r% S7 N7 M# f1 f# n' N % } d- @3 u2 E$ a2 Y/ ` Q 2 $ catkin_init_workspace" B* p8 E- l, X" x6 a) h& o # Q8 t5 {5 T) i- Z$ i7 y: Q$ H 接下来创建一个软件包:1$ cd src" h& }7 Y" w+ N. n2$ catkin_create_pkg my_first_pkg rospy 这样就会自动在 src 目录创建一个 ROS 软件包了。 V2 m7 L* k( I6 K2 p1 _5 _ 我们在 catkin_workspace/src/my_first_pkg/src 目录下新建一个文件 ros_cmd_vel_pub.py: - x _+ B% \6 F; [1 [3 \ 1#!/usr/bin/python+ x ?- P, f/ Z A - u/ z- V- _% p3 T0 ]$ L# d$ p 2; I+ U/ C4 _4 Z) X0 l+ ? 3import rospy 4from geometry_msgs.msg import Twist 5from pynput.keyboard import Key, Listener 6 7vel = Twist() 8vel.linear.x = 0 9 10def on_press(key): 11 12 try: 13 if(key.char == 'w'):5 v+ M' F, z5 L. |: ]* e: R 14 print("Forward") 15 vel.linear.x = 0.8 16 vel.angular.z = 0. H q" t. _* h0 \ 17 18 if(key.char == 's'):! _3 I: U7 d% t 19 print("Backward"): u( T) g* \* x3 Q 20 vel.linear.x = -0.83 s/ A6 e4 ]) k9 ~ 21 vel.angular.z = 0 22 23 if(key.char == 'a'):7 R* O, X4 t* e 24 print("Counter Clockwise")5 |% ~3 G8 a& h 25 vel.linear.x = 0/ [% b3 Z/ M7 e" j* d- J 26 vel.angular.z = -0.8 27 28 if(key.char == 'd'):$ K2 D% x8 @- W6 R 29 print("Clockwise") 30 vel.linear.x = 0 31 vel.angular.z = 0.8 322 [" x" o3 p, D% a 33 return False$ P+ c3 _2 a; O 34 35 except AttributeError: 36 print('special key {0} pressed'.format(key)) 37 return False& w3 Z8 j8 x" d; B+ g+ X; R 38+ v& d F) D7 f, j# S i# i" v* ^ 39def on_release(key): 40 vel.linear.x = 0 41 vel.angular.z = 07 V, ^( H0 L9 ~/ o/ T: D 42, ^4 k& g7 I1 v 43 return False 44" `# ^$ g. s/ u6 \& f4 B0 C/ U 45# Init Node 46rospy.init_node('my_cmd_vel_publisher') 47pub = rospy.Publisher('cmd_vel', Twist, queue_size=10)/ \; ^, c _9 d4 v4 \6 X 48 49# Set rate 50rate = rospy.Rate(10) 51 52listener = Listener(on_release=on_release, on_press = on_press) 53 54while not rospy.is_shutdown():$ O; g/ c6 T5 h0 D$ c1 G 55 print(vel.linear.x). v" L) ~ z3 u3 v/ Y 56 pub.publish(vel)/ s/ I2 G% F2 Z7 U9 N+ G5 D 57 vel.linear.x = 0* K) j7 }# _: e2 w" x7 r$ A 58 vel.angular.z = 06 t/ Y7 K- N/ }" d. e 59 rate.sleep() 60 61 if not listener.running: u: ^. j2 T- W. Z( M' h 62 listener = Listener(on_release=on_release, on_press = on_press)9 C% R, W7 O: f. i6 ] 63 listener.start(), R8 X' t. f; H( F' @( \ 这就是我们的 python 控制程序了,可以使用键盘的 wasd 控制小车前进后退,顺时针、逆时针旋转。我们需要给它添加可执行权限:4 Y! r% L9 _$ M) b3 K i2 M. A2 G 1 $ chmod u+x ./ros_cmd_vel_pub.py# u5 d5 N2 ?7 [# `7 ~ - }' Q2 x5 K/ T! l2 s 这样就可以编译软件包了,在 catkin_worspace 目录下。 1 $ catkin_make2 $ source devel/setup.bash 1 rosrun my_first_pkg ros_cmd_vel_pub.py 1 U9 X, O. y, ~' x# }" r, C 可以看到用 ROS 实现小车控制其实代码量并不算多,只需要在自己小车原有的代码上发布一些话题,告诉 ROS 小车当前的状态,并且订阅一个话题接收 ROS 的控制指令就可以了。 - O. \) a- F$ Q4 L1 L8 N# ]; f& j ) ]( o: T& I( X 2.4 参考文献
3.1 rosserial 配置 , P$ i( k' t2 f o. s- r 其实无线连接和有线连接几乎是一模一样的,只不过是先用 ESP8266 使自己的控制板能连上网,然后用 tcp 连接和 ROS 通信,关于 RT-Thread 使用 ESP8266 上网的教程可以参照 官网:http://www.rt-thread.org/document/site/application-note/components/at/an0014-at-client/,非常详细了,我这里就不重复了。 确保开发板有网络连接后,我们就可以在 rosserial 里面配置为使用 tcp 连接: ![]() 我们只需要在上一部分的 main.cpp 里添加一行代码:+ w7 Y0 U$ E3 v 1// 设置 ROS 的 IP 端口号2nh.getHardware()->setConnection("192.168.1.210", 11411); 3 4// 添加在节点初始化之前 5nh.initNode(); ! Y; q$ k3 s0 B9 g+ L! D$ W 开发板就能通过 tcp 连接和 ROS 通信了,非常方便。 1 h) `# V7 q( q- ^ 3.2 ROS 配置% A' F% p( E" D / v% ]4 S. @" W# x# L! c 由于我们使用了 tcp 连接,所以 ROS 上自然也要开启一个服务器了,之前是使用的串口建立连接,现在就是使用 tcp 了: 1 $ rosrun rosserial_python serial_node.py tcp( |% V8 q/ j- q- Y. O% G/ m 其他的代码完全不需要改变,这样我们就实现了一个 ROS 无线控制的小车了。 ' o* w: E/ l8 o 3.3 参考文献
( c% D8 H0 T# X0 U( A 这里再总结一下,其实 RT-Thread 使用 rosserial 软件包和 ROS 建立连接非常简单,只需要在自己小车原有代码的基础上发布一些消息,告诉 ROS 小车当前的状态,以及订阅来自 ROS 的控制指令就可以了。 |
厉害 |
大佬门路挺广的哈1 P' k) t, k+ F |