赞
踩
总体来说,ROS更偏重软件,其涉及的控制、算法都是偏策略或复杂的,但机器人是要和现实世界打交道的,必须有相应的执行机构,使ROS所能做的那些“高、大、上”的工作落地。真正能够和执行硬件打交道、操控起来得心应手的还是MCU,所以如何将MCU控制的硬件和ROS系统相连,可以基于ROS的信息交互机制实现控制和反馈,是学习ROS、基于ROS完成一些任务必须首先化解的问题。
很早我就做了一个4轮全向小车平台,可以将笔记本放置在上面,作为上位机,设计了一个STM32的控制板,驱动4个舵机和4个轮式驱动单元(带反馈的直流电机),通过串口即可控制小车运转:
当时就想在笔记本上运行ROS,控制小车运动,相当于那个经典的ROS底盘。可一直没有沉下心来实现ROSSerial,惭愧!希望这次可以借此顺势完成^_^
先从简单的做起吧!
上一篇做了一个STM32的Arduino控制板,并且成功替换了原来的Arduino Nano控制板,将原来的程序移植到STM32平台上,实现了原有的功能。编译后发现资源还富裕很多,在上面应该可以做很多文章,比如PID转速控制;原来那个基于Mega328的Nano有点勉强,不光是资源问题,对AVR的底层也太不熟悉,完全基于Arduino库有点困难。
不过这个先放一下,重点是打通和ROS的通讯,将ROSSerial功能用起来。
ROS的官方教学示例都是以虚拟的小海龟为控制对象,消息、服务均是以控制小海龟作为示例。但小海龟毕竟是虚拟的,而Robot对于很多人而言,是现实存在的。
所以,第一步打算用前文所述的那个小车作为实体的小海龟,尝试一下,可否通过ROS消息控制这个现实世界的小海龟。
作为测试,将geometry_msgs/Twist 中的 linear X 作为 PWM,angular Z 作为舵机转角,每次收到消息走 3 秒。
以上一篇的程序为基础,修改了以下几个部分:
…….
#include<ros.h> // 190519
#include<geometry_msgs/Twist.h> // 190519
…….
//-----------190519 ---------------
boolean g_bReceived_Msgs;
int gc_iRunTimeCnt;
ros::NodeHandle nh;
//------------- 190519 ----------------
voidoneWheel_cb( const geometry_msgs::Twist& cmd_msg)
{
int temp;
if(cmd_msg.linear.x == 0.0)
{
g_ucPara1= BRAKE;
g_ucPara2= 0;
}
else
{
if(cmd_msg.linear.x > 0.0)
{
g_ucPara1 = FORWARD;
g_ucPara2 =byte(cmd_msg.linear.x);
}
else
{
g_ucPara1 = BACKWARD;
g_ucPara2 = byte(0 -cmd_msg.linear.x);
}
}
temp = int(cmd_msg.angular.z);
if(temp <0)
{
temp = 0;
}
if(temp >180)
{
temp = 180;
}
g_ucServoVal = byte(temp);
g_bReceived_Msgs = true;
gc_iRunTimeCnt = 3000;
digitalWrite(LED_BUILTIN, HIGH); // led
}
ros::Subscriber<geometry_msgs::Twist>sub("turtle_cmd_Vel", oneWheel_cb);
…….
voidsetup()
{
………..
nh.initNode();
nh.subscribe(sub);
}
voidloop()
{
……
nh.spinOnce(); // 190519
if(g_bReceived_Msgs)
{
g_bReceived_Msgs= false;
driveMotor(g_ucPara1,g_ucPara2);
myServo.writeMicroseconds(correctServo(g_ucServoVal));
}
if(gc_iRunTimeCnt!=0)
{
gc_iRunTimeCnt--;
if(gc_iRunTimeCnt==0)
{
driveMotor(BRAKE,0);
digitalWrite(LED_BUILTIN,LOW);
}
}
}
}
增加了上述语句后,编译通过(在ubuntu环境下,因为只在那里面安装了ROS):
可以看出对于STM32F103C8而言,64K FLASH 只占用了25k(38%),20K RAM只占用了2.7k(13%),在此基础上,可以有很大的发挥空间。
用USB转TTL电平串口模块连接STM32duino控制板:
使用消息发布测试:
现实世界中的小海龟动起来了!
感觉不错。不过尝试用无线适配器代替USB转TTL电平串口,失败了:(
好像 ROSSerial 协议在通讯过程中不断在用时间同步,经过两个无线模块转发后,可能通讯帧不连贯了,导致通讯只能偶尔成功,多数情况下失败。
看来如果要让这个小海龟无拘无束的跑起来,只能用TK-1之类的小主板放置在小车上了,或者使用树莓派3B+ 放置在小车上,作为中继,通过Wifi实现远程。
这一步的目标算是实现了,证明 ROSSerial可用,而且还比较方便,ROS.lib封装的不错。
下一步要尝试:如果程序框架基于 FreeRTOS编写,是否还可以可靠的使用ROS.lib?通过ROSSerial和ROS主机通讯。
因为我以往的小车控制程序都是基于 uCOS编写的,要移植到Arduino环境下,如果放弃RTOS框架,改写的内容太多,关键是需要自己写调度部分,有些麻烦。感觉移植到FreeRTOS上会方便些,STM32Duino有现成的 FreeRTOS库。
注:程序附在 QQ 群 32438885 的共享文件夹中,供参考。
Copyright © 2003-2013 www.wpsshop.cn 版权所有,并保留所有权利。