上期回顾:
第一部分:ROS 环境搭建
第二部分:RT-Thread rosserial 软件包
第二部分:RT-Thread 添加 USART2 和 PWM
第三部分:RT-Thread 使用 ESP8266 AT 固件联网
这里先介绍一下什么是 ROS?为什么要和 ROS 连接?
图片来源网络,如有侵权请联系删除
这篇文章假定大家都已经会用 RT-Thread 的 env 工具下载软件包,生成项目上传固件到 stm32 上,并且熟悉 Ubuntu 的基本使用。
这里的开发环境搭建其实是需要搭建 2 份,一份是小车上的 ARM 开发板 (树莓派,NanoPi 什么的),另一个则是自己的电脑,因为我们希望把电脑作为 ROS 从节点,连接到小车上的 ROS 主节点,不过开发板和电脑的 ROS 安装是一模一样的。
1sudo sh -c 'echo "deb https://mirror.tuna.tsinghua.edu.cn/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
2sudo apt-key adv --keyserver 'hkp://keyserver.ubuntu.com:80' --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654
3sudo apt update
4sudo apt install ros-melodic-ros-base
1sudo rosdep init
2rosdep update
3
4echo "source /opt/ros/melodic/setup.bash" >> ~/.bashrc
5source ~/.bashrc
1roscore
在 tmux 里启动了 ROS 主节点后,我们就可以 Ctrl + B D 退出了,而 ROS 主节点依旧在后台运行。
1menuconfig BSP_USING_UART
2 bool "Enable UART"
3 default y
4 select RT_USING_SERIAL
5 if BSP_USING_UART
6 config BSP_USING_UART1
7 bool "Enable UART1"
8 default y
9
10 config BSP_UART1_RX_USING_DMA
11 bool "Enable UART1 RX DMA"
12 depends on BSP_USING_UART1 && RT_SERIAL_USING_DMA
13 default n
14
15 config BSP_USING_UART2
16 bool "Enable UART2"
17 default y
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
23 endif
1menuconfig BSP_USING_PWM
2 bool "Enable pwm"
3 default n
4 select RT_USING_PWM
5 if BSP_USING_PWM
6 menuconfig BSP_USING_PWM3
7 bool "Enable timer3 output pwm"
8 default n
9 if BSP_USING_PWM3
10 config BSP_USING_PWM3_CH1
11 bool "Enable PWM3 channel1"
12 default n
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"
18 default n
19 config BSP_USING_PWM3_CH4
20 bool "Enable PWM3 channel4"
21 default n
22 endif
23 endif
这样我们在 env 下就可以看到有对应的配置了,
可以看到上面默认的串口就是 USART2,这样我们就可以生成对应的工程了:
1pkgs --update
2scons --target=mdk5 -s
1#include
2#include
3#include
4
5#include
6#include
7#include
8#include "motors.h"
9
10ros::NodeHandle nh;
11MotorControl mtr(1, 2, 3, 4); //Motor
12
13bool msgRecieved = false;
14float velX = 0, turnBias = 0;
15char stat_log[200];
16
17// 接收到命令时的回调函数
18void velCB( const geometry_msgs::Twist& twist_msg)
19{
20 velX = twist_msg.linear.x;
21 turnBias = twist_msg.angular.z;
22 msgRecieved = true;
23}
24
25//Subscriber
26ros::Subscriber sub("cmd_vel", velCB );
27
28//Publisher
29std_msgs::Float64 velX_tmp;
30std_msgs::Float64 turnBias_tmp;
31ros::Publisher xv("vel_x", &velX_tmp);
32ros::Publisher xt("turn_bias", &turnBias_tmp);
33
34static void rosserial_thread_entry(void *parameter)
35{
36 //Init motors, specif>y the respective motor pins
37 mtr.initMotors();
38
39 //Init node>
40 nh.initNode();
41
42 // 订阅了一个话题 /cmd_vel 接收控制指令
43 nh.subscribe(sub);
44
45 // 发布了一个话题 /vel_x 告诉 ROS 小车速度
46 nh.advertise(xv);
47
48 // 发布了一个话题 /turn_bias 告诉 ROS 小车的旋转角速度
49 nh.advertise(xt);
50
51 mtr.stopMotors();
52
53 while (1)
54 {
55 // 如果接收到了控制指令
56 if (msgRecieved)
57 {
58 velX *= mtr.maxSpd;
59 mtr.moveBot(velX, turnBias);
60 msgRecieved = false;
61 }
62
63 velX_tmp.data = velX;
64 turnBias_tmp.data = turnBias/mtr.turnFactor;
65
66 // 更新话题内容
67 xv.publish( &velX_tmp );
68 xt.publish( &turnBias_tmp );
69
70 nh.spinOnce();
71 }
72}
73
74int main(void)
75{
76 // 启动一个线程用来和 ROS 通信
77 rt_thread_t thread = rt_thread_create("rosserial", rosserial_thread_entry, RT_NULL, 2048, 8, 10);
78 if(thread != RT_NULL)
79 {
80 rt_thread_startup(thread);
81 rt_kprintf("[rosserial] New thread rosserial\n");
82 }
83 else
84 {
85 rt_kprintf("[rosserial] Failed to create thread rosserial\n");
86 }
87 return RT_EOK;
88}
另外还有对应的电机控制的代码,不过这个大家的小车不同,驱动应当也不一样,我这里由于小车电机上没有编码器,所以全部是开环控制的。
1#include
2
3class MotorControl {
4 public:
5 //Var
6 rt_uint32_t maxSpd;
7 float moveFactor;
8 float turnFactor;
9
10 MotorControl(int fl_for, int fl_back,
11 int fr_for, int fr_back);
12 void initMotors();
13 void rotateBot(int dir, float spd);
14 void moveBot(float spd, float bias);
15 void stopMotors();
16 private:
17 struct rt_device_pwm *pwm_dev;
18 //The pins
19 int fl_for;
20 int fl_back;
21 int fr_for;
22 int fr_back;
23 int bl_for;
24 int bl_back;
25 int br_for;
26 int br_back;
27};
1#include
2#include
3#include "motors.h"
4
5#define PWM_DEV_NAME "pwm3"
6
7MotorControl::MotorControl(int fl_for, int fl_back,
8 int fr_for, int fr_back)
9{
10 this->maxSpd = 500000;
11 this->moveFactor = 1.0;
12 this->turnFactor = 3.0;
13
14 this->fl_for = fl_for;
15 this->fl_back = fl_back;
16
17 this->fr_for = fr_for;
18 this->fr_back = fr_back;
19}
20
21void MotorControl::initMotors() {
22 /* 查找设备 */
23 this->pwm_dev = (struct rt_device_pwm *)rt_device_find(PWM_DEV_NAME);
24 if (pwm_dev == RT_NULL)
25 {
26 rt_kprintf("pwm sample run failed! can't find %s device!\n", PWM_DEV_NAME);
27 }
28 rt_kprintf("pwm found %s device!\n", PWM_DEV_NAME);
29 rt_pwm_set(pwm_dev, fl_for, maxSpd, 0);
30 rt_pwm_enable(pwm_dev, fl_for);
31
32 rt_pwm_set(pwm_dev, fl_back, maxSpd, 0);
33 rt_pwm_enable(pwm_dev, fl_back);
34
35 rt_pwm_set(pwm_dev, fr_for, maxSpd, 0);
36 rt_pwm_enable(pwm_dev, fr_for);
37
38 rt_pwm_set(pwm_dev, fr_back, maxSpd, 0);
39 rt_pwm_enable(pwm_dev, fr_back);
40}
41
42// 小车运动
43void MotorControl::moveBot(float spd, float bias) {
44 float sL = spd * maxSpd;
45 float sR = spd * maxSpd;
46 int dir = (spd > 0) ? 1 : 0;
47
48 if(bias != 0)
49 {
50 rotateBot((bias > 0) ? 1 : 0, bias);
51 return;
52 }
53
54 if( sL < -moveFactor * maxSpd)
55 {
56 sL = -moveFactor * maxSpd;
57 }
58 if( sL > moveFactor * maxSpd)
59 {
60 sL = moveFactor * maxSpd;
61 }
62
63 if( sR < -moveFactor * maxSpd)
64 {
65 sR = -moveFactor * maxSpd;
66 }
67 if( sR > moveFactor * maxSpd)
68 {
69 sR = moveFactor * maxSpd;
70 }
71
72 if (sL < 0)
73 {
74 sL *= -1;
75 }
76
77 if (sR < 0)
78 {
79 sR *= -1;
80 }
81
82 rt_kprintf("Speed Left: %ld\n", (rt_int32_t)sL);
83 rt_kprintf("Speed Right: %ld\n", (rt_int32_t)sR);
84
85 if(dir)
86 {
87 rt_pwm_set(pwm_dev, fl_for, maxSpd, (rt_int32_t)sL);
88 rt_pwm_set(pwm_dev, fl_back, maxSpd, 0);
89 rt_pwm_set(pwm_dev, fr_for, maxSpd, (rt_int32_t)sR);
90 rt_pwm_set(pwm_dev, fr_back, maxSpd, 0);
91 }
92 else
93 {
94 rt_pwm_set(pwm_dev, fl_for, maxSpd, 0);
95 rt_pwm_set(pwm_dev, fl_back, maxSpd, (rt_int32_t)sL);
96 rt_pwm_set(pwm_dev, fr_for, maxSpd, 0);
97 rt_pwm_set(pwm_dev, fr_back, maxSpd, (rt_int32_t)sR);
98 }
99
100 rt_thread_mdelay(1);
101}
102
103
104// 小车旋转
105void MotorControl::rotateBot(int dir, float spd) {
106 float s = spd * maxSpd;
107 if (dir < 0)
108 {
109 s *= -1;
110 }
111 if(dir)
112 {
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);
116 rt_pwm_set(pwm_dev, fr_for, maxSpd, 0);
117 rt_pwm_set(pwm_dev, fr_back, maxSpd, (rt_int32_t)s);
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);
126 }
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);
135 rt_pwm_set(pwm_dev, fr_for, maxSpd, 0);
136 rt_pwm_set(pwm_dev, fr_back, maxSpd, 0);
137}
1$ rosrun rosserial_python serial_node.py /dev/ttyUSB0
1tpl@nanopineoplus2:~$ rosrun rosserial_python serial_node.py /dev/ttyUSB0
2[INFO] [1567239474.258919]: ROS Serial Python Node
3[INFO] [1567239474.288435]: Connecting to /dev/ttyUSB0 at 57600 baud
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]
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]
1$ mkdir catkin_workspace && cd catkin_workspace
2$ catkin_init_workspace
1$ cd src
2$ catkin_create_pkg my_first_pkg rospy
1#!/usr/bin/python
2
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'):
14 print("Forward")
15 vel.linear.x = 0.8
16 vel.angular.z = 0
17
18 if(key.char == 's'):
19 print("Backward")
20 vel.linear.x = -0.8
21 vel.angular.z = 0
22
23 if(key.char == 'a'):
24 print("Counter Clockwise")
25 vel.linear.x = 0
26 vel.angular.z = -0.8
27
28 if(key.char == 'd'):
29 print("Clockwise")
30 vel.linear.x = 0
31 vel.angular.z = 0.8
32
33 return False
34
35 except AttributeError:
36 print('special key {0} pressed'.format(key))
37 return False
38
39def on_release(key):
40 vel.linear.x = 0
41 vel.angular.z = 0
42
43 return False
44
45# Init Node
46rospy.init_node('my_cmd_vel_publisher')
47pub = rospy.Publisher('cmd_vel', Twist, queue_size=10)
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():
55 print(vel.linear.x)
56 pub.publish(vel)
57 vel.linear.x = 0
58 vel.angular.z = 0
59 rate.sleep()
60
61 if not listener.running:
62 listener = Listener(on_release=on_release, on_press = on_press)
63 listener.start()
1$ chmod u+x ./ros_cmd_vel_pub.py
这样就可以编译软件包了,在 catkin_worspace 目录下。
1$ catkin_make
2$ source devel/setup.bash
1rosrun my_first_pkg ros_cmd_vel_pub.py
我们只需要在上一部分的 main.cpp 里添加一行代码:
1// 设置 ROS 的 IP 端口号
2nh.getHardware()->setConnection("192.168.1.210", 11411);
3
4// 添加在节点初始化之前
5nh.initNode();
1$ rosrun rosserial_python serial_node.py tcp
其他的代码完全不需要改变,这样我们就实现了一个 ROS 无线控制的小车了。
RT-Thread 使用 ESP8266 上网:
https://www.rt-thread.org/document/site/application-note/components/at/an0014-at-client/
END
RT-Thread线上活动
1、【RT-Thread软件包应用开发赛】本次大赛的唯一要求就是在作品中使用RT-Thread及软件包开发相关应用,不限定硬件平台,自备硬件,代码和文档开源。共设18名奖励,一等奖还可获得价值3499元的RoboMaster S1一台!报名参赛请先仔细阅读以下参赛须知(点击即可跳转):
立即报名
2、RT-Thread能力认证考前线上培训,将于2019年10月21号正式开始,如果您有晋升、求职、寻找更好机会的需要,有深入学习和掌握RT-Thread的需求,请尽快垂询/报考!学生优惠价:168/人
学生专属报名通道
能力认证官网链接:https://www.rt-thread.org/page/rac.html(在外部浏览器打开)
立即报名(非学生)
#题外话# 喜欢RT-Thread不要忘了在GitHub上留下你的STAR哦,你的star对我们来说非常重要!链接地址:https://github.com/RT-Thread/rt-thread
你可以添加微信17775983565为好友,注明:公司+姓名,拉进 RT-Thread 官方微信交流群
RT-Thread
长按二维码,关注我们