XR806-移植rosserial-串口通信
XR806简介
rosserial简介
移植:串口通信
rosserial源码获取
ROSserial移植核心
XR806 C++支持
串口
代码风格统一
配置文件`BUILD.gn`
测试
XR806端
编译程序
PC ROS 端
效果
总结和完善之处
XR806简介
板子来源于极术社区的试用,XR806的在线网址

其主要参数:
主控 | XR806AF2L |
---|---|
DDR | SIP 288KB SRAM |
存储 | SIP 160KB Code ROM. SIP 16Mbit Flash. |
天线 | 板载WiFi/BT双天线,可共存 |
按键 | reboot按键 1,功能按键 1 |
灯 | 红色电源指示灯 1,蓝色可调节LED 1 |
供电 | Type-C 5V |
引脚 | 插针引脚 *9 |
调试方式 | Type-C(已板载串口转USB芯片) |
晶振 | 外接40MHz晶振 |
rosserial简介
官网
rosserial是用于非ROS设备与ROS设备进行通信的一种协议。它为非ROS设备的应用程序提供了ROS节点和服务的发布/订阅功能,使在非ROS环境中运行的应用能够通过串口或网络能够轻松地与ROS应用进行数据交互。
rosserial分为客户端和服务器两部分。rosserial客户端运行在运行在没有安装ROS的环境的应用中,通过串口或网络与运行在ROS环境中的rosserial服务器连接,并通过服务器节点在ROS中发布/订阅话题。
本次这移植rosserial客户端到XR806上
移植:串口通信
rosserial源码获取
官方源码
该仓库中的代码需要编译才能获取源码,为了直接获取源码,使用以下仓库的源码做为基础
使用源码
该代码时属于RT-thread软件包就有较高的可信度。
clone下来的代码放在/ohosdemo/rosserial
中,文件结构:
tree -L 1
.
├── BUILD.gn
├── inc
├── port
└── src
- BUILD.gn :配置文件
- inc :rosserial源文件
- port:移植文件(为了和XR806适配的代码放在该文件下)
ROSserial移植核心
根据官网的移植介绍,只需要填写完以下模板即可:
class Hardware
{
Hardware();
// any initialization code necessary to use the serial port
void init();
// read a byte from the serial port. -1 = failure
int read()
// write data to the connection to ROS
void write(uint8_t* data, int length);
// returns milliseconds since start of program
unsigned long time();
};
init()
:提供初始化函数,初始化串口或者TCP网络read()
:读取一个字节write(uint8_t* data, int length)
:写字符time()
:提供时间基准
另外,代码为c++,需要XR806支持C++编译
XR806 C++支持
/device/xradio/xr806/liteos_m/config.gni
文件,添加以下内容:board_cxx_flags = []
board_cxx_flags += SDK_cflags
board_cxx_flags += [
"-includelog/log.h",
"-DVIRTUAL_HCI",
"-DCONFIG_ARM",
#"-DNULL=((void*)0)",
#"-std=c++17",
"-lstdc++",
"-fno-rtti",
"-fno-exceptions"
]
大部分和board_cflags
的配置一样,添加的编译项"-lstdc++",-fno-rtti,-fno-exception
是为了解决以下错误:
undefined reference to `vtable for __cxxabiv1::__si_class_type_info'
该错误的原因是C++在链接时会有相关库链接不上
/ohosdemo/rosserial/BUILD.gn
中添加以下代码:cflags_cc = board_cxx_flags
串口
和串口相关的代码放在rosserial/port/UartHaedware.h
关键代码:
串口初始化:init()
函数
void init()
{
// HAL_Status status = HAL_ERROR;
UART_InitParam param;
param.baudRate = this->baudRate;
param.dataBits = UART_DATA_BITS_8;
param.stopBits = UART_STOP_BITS_1;
param.parity = UART_PARITY_NONE;
param.isAutoHwFlowCtrl = 0;
HAL_UART_Init(UARTID, ¶m);
}
串口读取一个字节:read()
函数
int read()
{
uint8_t rx_data;
int32_t len=0;
len = HAL_UART_Receive_IT(UARTID,&rx_data,1,1000);
if(len>0)
{
return rx_data;
}
else return -1;
}
串口写字节:write(uint8_t* data, int length)
// write data to the connection to ROS
void write(uint8_t* data, int length)
{
HAL_UART_Transmit_IT(UARTID, data, length);
}
时间基准:time()
函数
// returns milliseconds since start of program
unsigned long time()
{
unsigned long temp = (unsigned long)OS_GetTime() * 1000;
return temp;
}
代码风格统一
为了保持ROS代码的编写风格一致,添加``rosserial/port/ros.h`
关键代码:
#define ROS_USE_TCP 0
#define ROS_USE_UART 1
namespace ros
{
#if ROS_USE_TCP == 1
typedef NodeHandle_<TCPHardware> NodeHandle;
#endif
#if ROS_USE_UART == 1
typedef NodeHandle_<Hardware> NodeHandle;
#endif
}
#endif
配置文件BUILD.gn
# 必须,config中定义了头文件路径和关键宏定义
import("//device/xradio/xr806/liteos_m/config.gni")
# 必须,所有应用工程必须是app_打头
static_library("app_rosserial")
{
configs = []
sources = [
"src/ros_helloworld.cpp",
"inc/duration.cpp",
"inc/time.cpp",
]
#必须,board_cflags是在config.gni中定义的关键宏定义
cflags = board_cflags
# c++
cflags_cc = board_cxx_flags
#必须,board_include_dirs是在config.gni中定义的文件路径
include_dirs = board_include_dirs
# 根据实际情况添加头文件路径
include_dirs += [
"//kernel/liteos_m/kernel/arch/include",
"./../wlan_demo/",
"inc",
"port" ,
"//base/iot_hardware/peripheral/interfaces/kits",
"//foundation/communication/wifi_lite/interfaces/wifiservice",
]
}
测试
XR806端
- 编写一个发布话题:XR806_to_ROS
发布的内容为“hello world!”,时间间隔为1s
- 编写一个接收话题:ROS_to_XR860
接收的内容通过串口显示出来
测试代码在/rosserial/src/ros_helloworld.cpp
#include <ros.h>
#include <std_msgs/String.h>
#include <stdio.h>
#include "ohos_init.h"
#include <stdlib.h>
//信号量的声明
// #include "wlan_demo/test_case.h"
static OS_Thread_t g_main_thread;
extern OS_Semaphore_t ros_sem;
static ros::NodeHandle nh;
static std_msgs::String str_msg;
static ros::Publisher chatter("XR806_to_ROS", &str_msg);
static char hello_msg[25] = "hello world!";
// 回调函数
static void message_callback(const std_msgs::String& msgs)
{
printf("\r\nresive:%s\r\n", msgs.data);
}
static ros::Subscriber<std_msgs::String> sub("ROS_to_XR860", &message_callback);
static void ROSThread(void *arg)
{
//等待信号量有效
// if (OS_SemaphoreWait(&ros_sem, OS_WAIT_FOREVER) == OS_OK)
// {
printf("\r\n--------- star ROS----------------\r\n");
nh.initNode();
nh.advertise(chatter);
nh.subscribe(sub);
while (1)
{
if (nh.connected())
{
str_msg.data = hello_msg;
chatter.publish(&str_msg);
}
nh.spinOnce();
OS_MSleep(1000);
}
// }
}
void ROSMain(void)
{
printf("\r\nROSserial Start\r\n");
if (OS_ThreadCreate(&g_main_thread, "ROSThread", ROSThread, NULL,
OS_THREAD_PRIO_APP, 4 * 1024) != OS_OK) {
printf("[ERR] Create MainThread Failed\n");
}
}
SYS_RUN(ROSMain);
编译程序
hb build -f
可能会遇到下面问题:
这个flash分配的分配有问题:
cd 到 device/xradio/xr806/xr_skylark/project/demo/audio_demo/image/xr806
用文件image_auto_cal.cfg
中的内容覆盖image_wlan_ble.cfg
中的内容。
PC ROS 端
Ubuntu版本:20版(18版也可以使用)
mkdir -p rosworkspace/src
cd rosworkspace
catkin_make
文件名:test_pub.py
import rospy
from std_msgs.msg import String
if __name__ == "__main__":
#2.初始化 ROS 节点:命名(唯一)
rospy.init_node("talker_p")
#3.实例化 发布者 对象
pub = rospy.Publisher("ROS_to_XR860",String,queue_size=10)
#4.组织被发布的数据,并编写逻辑发布数据
msg = String() #创建 msg 对象
msg_front = "hello XR806 "
count = 0 #计数器
# 设置循环频率
rate = rospy.Rate(1)
while not rospy.is_shutdown():
#拼接字符串
msg.data = msg_front + str(count)
pub.publish(msg)
rate.sleep()
#rospy.loginfo("写出的数据:%s",msg.data)
count += 1
CMakeLists.txt
支持python代码:
catkin_install_python(PROGRAMS
scripts/test_pub.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
效果
操作
PC端
roscore
source ./devel/setup.bash
rosrun ros_test test_pub.py
rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0 _baud:=115200
如果串口连接成功,终端显示:
INFO] [1640087588.757505]: ROS Serial Python Node
[INFO] [1640087588.762633]: Connecting to /dev/ttyUSB0 at 115200 baud
[INFO] [1640087591.079099]: Requesting topics...
[INFO] [1640087591.131236]: Note: publish buffer size is 512 bytes
[INFO] [1640087591.134777]: Setup publisher on XR806_to_ROS [std_msgs/String]
[INFO] [1640087591.142147]: Note: subscribe buffer size is 512 bytes
[INFO] [1640087591.144610]: Setup subscriber on ROS_to_XR860 [std_msgs/String]
可见话题的提示。
注意查看串口的权限,如果权限不足,先开启权限:
# 查看权限
ll /dev/ttyUSB*
#开启权限
sudo chmod 777 /dev/ttyUSB*
XR806端
直接下载代码,复位:
结果
haijun@ubuntu:~$ rostopic list
/ROS_to_XR860
/XR806_to_ROS
/diagnostics
/rosout
/rosout_agg
可见 /ROS_to_XR860和/XR806_to_ROS两个话题
rostopic echo /ROS_to_XR860
data: "hello world!"
---
data: "hello world!"
---
data: "hello world!"
---
data: "hello world!"
---
data: "hello world!"
---
-------- star ROS----------------
hiview init success.led main锛?IoTGpioInit port0, pin21
console init success
resive:hello XR806 1
resive:hello XR806 2
resive:hello XR806 3
resive:hello XR806 4
resive:hello XR806 5
resive:hello XR806 6
resive:hello XR806 7
resive:hello XR806 8
resive:hello XR806 9
resive:hello XR806 10
resive:hello XR806 11
resive:hello XR806 12
总结和完善之处
目前rosserial的串口通信没有问题,TCP客户端一直连不上TCP服务器。等大神们开放了tcp通信的相关代码后再把TCP通信移植过来。
等以后移植了TCP通信的代码再把代码放出来(目前代码有TCP通信部分,但是不好用,分离又有点麻烦)