MANIFOLD 2-G开发笔记
本博客内容将记录MANIFOLD 2-G 开发过程中遇到的问题及解决方案,用于与大家交流。
MANIFOLD 2-G(秒算2-G) 是大疆推出的高性能计算平台,其主要用于DJI行业无人机的开发,但因其小巧的体积,强大的计算力,也可对其他单片机进行开发。
1 项目描述
利用 MANIFOLD 2-G(秒算2-G) 中ROS通信编程,实现对 Arduino Mega 单片机的控制。(该方法应该也适用于其他类似单片机)
最近的一个项目需要利用 MANIFOLD 2-G(秒算2-G) 实现对 Arduino Mega 单片机的控制。具体来说就是:MANIFOLD 2-G(秒算2-G) 作为上位机发布指令, Arduino Mega 单片机作为下位机接收。Arduino 系列单片机最简单的通讯方式就是TTL串口通讯 ,可通过USB转串口或直接接入TX、RX引脚进行。而 MANIFOLD 2-G(秒算2-G) 带有USB接口,于是考虑通过USB转串口进行。
在进行 MANIFOLD 2-G(秒算2-G) 调试前, Arduino Mega 的程序已经调试完毕,通信协议如下:串口数据接受到字符 “1”,“2”,“3”,“4” ,“0”后,会作出相应响应,控制Hybrid_bot机器人chassis部分进行前、后、左、右( “1”,“2”,“3”,“4” )的运动,以及停止(“0”)。
本文将只讨论MANIFOLD 2-G(秒算2-G) 对 Arduino Mega 的控制。
2 遇到的问题
将 Arduino Mega 利用USB线接入 MANIFOLD 2-G(秒算2-G),在终端输入:
ls /dev | grep tty*
发现找不到对应的串口设备,又搜集了一些资料,发现MANIFOLD 2-G(秒算2-G) 不带USB转串口的驱动,搜索各类资源也无法成功安装,邮件联系了DJI技术支持,至今还没得到有价值的信息,问题也一直没有解决。
也请DJI技术人员看到这篇博文能给我提供一点技术支持。
3 解决方案
既然无法使用USB转串口,能不能直接使用串口呢?带着这个疑问,进行了新的尝试。
MANIFOLD 2-G(秒算2-G) 自带两个UART串口,理论上是可以进行通讯的,其官方提供的使用说明如下:
这里,我们使用UART1接口,对应的设备名称是ttyTHS2,这个名称后边程序会用到。
(P.S. 我尝试过UART0接口,但不好用。可能UART0是默认调试接口,还得改设置。但UART1插上就可以用。)
接线也十分简单,使用MANIFOLD 2-G(秒算2-G) 自带UART转3P杜邦线,注意MANIFOLD 2-G(秒算2-G) 的TXD与 Arduino Mega的RX相接,RXD与TX相接,GND相接即可。
4 示例代码
这里写了两个带注释cpp文件:(1) chassis_cmd.cpp 和 (2) chassis_driver.cpp,供参考。
代码实现功能如下:开启两个ROS节点,进行ROS话题编程。Publisher用于接收来自键盘的指令,发布给Subscriber。Subscriber判断消息内容,并根据对应内容向串口设备发出命令。
(1) chassis_cmd.cpp
/*
此程序作为Hybrid_bot机器人chassis命令的Publisher
用于发布名为chassis_cmd的topic
ROS节点名为:chassis_cmd
*/
#include <ros/ros.h>
#include <std_msgs/Int16.h>
int main(int argc, char **argv)
{
ros::init(argc, argv, "chassis_cmd");//创建ROS节点,名为:chassis_cmd
ros::NodeHandle n;//创建节点句柄
ros::Publisher chassis_cmd_pub = n.advertise<std_msgs::Int16>("chassis_cmd", 1000);//创建一个名为chassis_cmd_pub的Publisher,发布名为chassis_cmd的topic,消息类型为std_msgs::Int16,暂存队列长度为1000
ros::Rate loop_rate(10);//设置循环频率为10Hz(100ms/次)
while (ros::ok())
{
std_msgs::Int16 cmd;//初始化std_msgs::Int16类型的消息变量cmd
std::cout << "input cmd:" << std::endl;//打印一条提示性语句
std::cin >> cmd.data;//等待键盘输入为cmd.data赋值
chassis_cmd_pub.publish(cmd);//发布消息cmd
ros::spinOnce();//循环等待回调函数
loop_rate.sleep();//按照循环频率延时
}
return 0;
}
代码小结:
这段代码通用性较强,可作为用于接收来自键盘指令的Publisher的例程。
(2) chassis_driver.cpp
/*
此程序作为Hybrid_bot机器人chassis命令的Subscriber
用于接收名为chassis_cmd的topic并利用回调函数sub_CB将对应命令发布到串口设备
ROS节点名为:chassis_driver
*/
#include <ros/ros.h>
#include <std_msgs/Int16.h>
#include <serial/serial.h>//MANIFOLD2不带这个库文件,需要自己下载安装一下
serial::Serial ser; //声明串口对象
void sub_CB(const std_msgs::Int16 &flag_tmp)//消息回调函数,收到消息后会进入。这里的&flag_tmp与chassis_cmd.cpp中cmd变量的类型需一致,均需要为std_msgs::Int16
{
if(flag_tmp.data == 1)
{
ser.write("1"); //前进
ROS_INFO("chassis go forward");
}
else if(flag_tmp.data == 2)
{
ser.write("2"); //后退
ROS_INFO("chassis go back");
}
else if(flag_tmp.data == 3)
{
ser.write("3"); //左转
ROS_INFO("chassis turn left");
}
else if(flag_tmp.data == 4)
{
ser.write("4"); //右转
ROS_INFO("chassis turn right");
}
else
{
ser.write("0"); //停止
ROS_INFO("chassis stop");
}
}
int main (int argc, char **argv)
{
ros::init(argc, argv, "chassis_driver");//创建名为chassis_driver的ROS节点
ros::NodeHandle n;//创建节点句柄
ros::Subscriber sub=n.subscribe("chassis_cmd",1,sub_CB);//创建一个名为sub的Subscriber,订阅名为chassis_cmd的topic,注册回调函数sub_CB
try
{
//设置串口属性,并打开串口
ser.setPort("/dev/ttyTHS2"); //MANIFOLD2 UART1 串口名称
ser.setBaudrate(9600); //设置波特率
serial::Timeout to = serial::Timeout::simpleTimeout(1000);
ser.setTimeout(to);
ser.open();
}
catch (serial::IOException& e)
{
ROS_ERROR("Unable to open the chassis port ");
return -1;
}
//检测串口是否已经打开,并给出提示信息
if(ser.isOpen())
{
ROS_INFO("chassis serial port initialized");
}
else
{
return -1;
}
ros::Rate loop_rate(10);//循环频率10ms
ros::spin();//循环等待回调函数
//exit
return 0;
}
代码小结:
这段代码在本项目中作为Subscriber,接受来自Publisher的指令后控制Hybrid_bot机器人chassis部分的Arduino Mega 单片机,主函数可作为Subscriber和串口通讯的例程。 sub_CB函数中的内容可稍作修改应用在自己的串口设备上。
5 注意事项
1、别忘了 配置CMakeLists.txt 和 package.xml,这应该是ROS基础,就不加赘述了,如果和笔者使用同样的设备又不想自己配置,可以直接下载提供的资源。
2、 MANIFOLD2不带<serial/serial.h>库文件,需要自己下载安装一下,使用如下命令。
sudo apt-get install ros-kinetic-serial #ros为Kinect版本,其他版本对应修改
P.S. 如果说使用此命令报404错误,可能是软件源的问题,可以上网查教程折腾,这里我直接找到404上不去的那个网站链接,直接下载deb文件,如serial库http://packages.ros.org/ros/ubuntu/pool/main/r/ros-kinetic-serial/
注意对应好自己设备的版本,比如MANIFOLD2-C就是amd64的,而MANIFOLD2-G就是arm64的。
如果不想自己下载,可以直接下载提供的资源。
6 资源附件
附件下载地址:
下载地址
https://download.youkuaiyun.com/download/weixin_44037313/12691728
附件清单:
1、Manifold_2_User_Guide_v1.0_CHS.pdf
2、下载好的<serial/serial.h>库文件安装包 ros-kinetic-serial_1.2.1-0xenial-20191214-125614+0000_arm64.deb,可在文件保存目录下启动终端,使用如下命令进行安装。(只适用于MANIFOLD2-G)
sudo dpkg -i xxx.deb //是安装包的准确名称
3、功能包hybrid_bot,包含chassis_cmd.cpp、chassis_driver.cpp及适用于Manifold2-G的CMakeLists.txt 和 package.xml配置文件。
6 运行与调试
将功能包hybrid_bot放置在工作空间中,在工作空间根目录下使用命令:
catkin_make
进行编译,可在工作空间的/devel/lib/hybrid_bot文件夹下生成两个可执行文件chassis_driver和chassis_cmd。
在桌面启动终端,启动ROS:
roscore
接入设备后,另起终端,启动Subscriber节点:
rosrun hybrid_bot chassis_driver
再另起终端,启动Publisher节点
rosrun hybrid_bot chassis_cmd
至此,可以实现键盘控制。
通过在Publisher节点终端键盘输入 1 2 3 4 等字符,即可在Subscriber节点终端收到反馈,同时Arduino Mega 将被控制。