一、Micro-ROS介绍与服务安装
1. 功能和体系结构
分层和模块化架构
Micro-ROS 遵循 ROS 2 架构,并利用其中间件可插拔性来使用 DDS-XRCE,该 DDS-XRCE 针对微控制器进行了优化。此外,它使用基于 POSIX 的 RTOS(FreeRTOS、Zephyr 或 NuttX)而不是 Linux。
深蓝色组件是专门为micro-ROS开发的。浅蓝色组件取自标准 ROS 2 堆栈。
2. Micro-ROS几大主要特点。
2.1 特点1:运行在微控制器上的ROS2
首先从名称看,Micro-ROS,Micro指的就是microcontrollers即微控制器。
核心作用就是上面这句话micro-ROS puts ROS 2 onto microcontrollers。既然是在微控制器上,因硬件资源受限,其功能肯定会有所裁剪,但核心的ROS2通信功能依然保有。
2.2 特点2:MicroROS支持多种通信协议并依赖Agent
所谓Agent其实就是一个代理,微控制器可以通过串口,蓝牙、以太网、Wifi等多种协议将数据传递给Agent,Agent再将其转换成ROS2的话题等数据,以此完成通信。
2.3. 特点3:通过RCLC-API调用MicroROS
因为MicroROS遵循RCLCAPI,所以和在上位机中使用Python或者C++调用MicroROS有所不同,最终代码风格如下面这段所示
#include <rcl/rcl.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
rcl_timer_t timer;
void setup() {
// Configure serial transport
Serial.begin(115200);
set_microros_serial_transports(Serial);
delay(2000);
allocator = rcl_get_default_allocator();
//create init_options
RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
// create node
RCCHECK(rclc_node_init_default(&node, "micro_ros_platformio_node", "", &support));
// create publisher
RCCHECK(rclc_publisher_init_default(
&publisher,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
"micro_ros_platformio_node_publisher"));
// create executor
RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));
RCCHECK(rclc_executor_add_timer(&executor, &timer));
msg.data = 0;
}
3. 在上位机上安装Agent
我们使用Docker来进行Agent的安装。
3.1 安装Docker
打开终端,复制粘贴输入下面代码
wget http://fishros.com/install -O fishros && . fishros
接着输入密码,在下面的界面输入8,一键安装Docker,完成后等待即可。
3.2 运行Agent
安装完成Docker后打开终端,输入下面的指令
sudo docker run -it --rm -v /dev:/dev -v /dev/shm:/dev/shm --privileged --net=host microros/micro-ros-agent:$ROS_DISTRO serial --dev /dev/ttyUSB0 -v6
稍微等待下载完成,看到如下界面表示成功启动。
上面的指令是使用串口通讯协议运行microros-agent,还可以通过UDP、TCP、CAN等协议运行,具体指令如下
# UDPv4 micro-ROS Agent
docker run -it --rm -v /dev:/dev -v /dev/shm:/dev/shm --privileged --net=host microros/micro-ros-agent:$ROS_DISTRO udp4 --port 8888 -v6
# Serial micro-ROS Agent
docker run -it --rm -v /dev:/dev -v /dev/shm:/dev/shm --privileged --net=host microros/micro-ros-agent:$ROS_DISTRO serial --dev [YOUR BOARD PORT] -v6
# TCPv4 micro-ROS Agent
docker run -it --rm -v /dev:/dev -v /dev/shm:/dev/shm --privileged --net=host microros/micro-ros-agent:$ROS_DISTRO tcp4 --port 8888 -v6
# CAN-FD micro-ROS Agent
docker run -it --rm -v /dev:/dev -v /dev/shm:/dev/shm --privileged --net=host microros/micro-ros-agent:$ROS_DISTRO canfd --dev [YOUR CAN INTERFACE] -v6
二、 你的第一个MicroROS节点
1. 新建工程添加依赖
1.1 新建工程
新建example03_hello_microros工程,这里需要更改下工程的位置,默认目录是在文档目录下,测试时发现目录定位上有bug,所以建议建议直接放到主目录或其下目录
1.2 添加依赖
打开platform.ini,接着我们添加MicroROS的依赖。
[env:esp32doit-devkit-v1]
platform = espressif32
board = esp32doit-devkit-v1
framework = arduino
lib_deps =
https://gitee.com/ohhuo/micro_ros_platformio.git
2. 编写代码-第一个节点
#include <Arduino.h>
#include <micro_ros_platformio.h>
#include <rcl/rcl.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
void setup()
{
Serial.begin(115200);
// 设置通过串口进行MicroROS通信
set_microros_serial_transports(Serial);
// 延时时一段时间,等待设置完成
delay(2000);
// 初始化内存分配器
allocator = rcl_get_default_allocator();
// 创建初始化选项
rclc_support_init(&support, 0, NULL, &allocator);
// 创建节点 hello_microros
rclc_node_init_default(&node, "hello_microros", "", &support);
// 创建执行器
rclc_executor_init(&executor, &support.context, 1, &allocator);
}
void loop()
{
delay(100);
// 循环处理数据
rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));
}
相比在上位机中开发ROS,这里多了几步
- 设置通信协议,因为可以通过多种方式连接,所以需要进行提前设置
- 初始化内存分配器,在微控制器上资源受限,内存的管理要很细致
- 创建初始化选项,用于初始化rcl并创建一些需要用到的数据结构体
关于rclc_support_init 的源码及参数介绍。
/**
* Initializes rcl and creates some support data structures.
* Initializes clock as RCL_STEADY_TIME.
* * <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | Yes (in RCL)
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | Yes
*
* \param[inout] support a zero-initialized rclc_support_t
* \param[in] argc number of args of main
* \param[in] argv array of arguments of main
* \param[in] allocator allocator for allocating memory
* \return `RCL_RET_OK` if RCL was initialized successfully
* \return `RCL_RET_INVALID_ARGUMENT` if any null pointer as argument
* \return `RCL_RET_ERROR` in case of failure
*/
RCLC_PUBLIC
rcl_ret_t
rclc_support_init(
rclc_support_t * support,
int argc,
char const * const * argv,
rcl_allocator_t * allocator);
3. 运行测试
连接开发板,编译下载,如果遇到端口被占用,多半是你的microros_agent没有关闭,Ctrl+C打断运行再次尝试。
接着打开Agent
然而并没有什么反应,重新点击一次RST或者EN,即可看到有数据发送和接收过来了。
接着打开新的终端,输入指令
ros2 node list
ros2 node info /hello_microros
可以看到,我们的第一个节点成功运行起来了。
本节我们成功的在微控制器平台上将MicroROS节点运行起来了,下一节我们开始正式进行ROS2通信的学习。
============================================================================
在嵌入式平台实现话题与服务通信
三、话题订阅-控制LED
1. 新建工程添加依赖
新建example04_microros_topic_sub工程
修改platformio.ini添加依赖
[env:esp32doit-devkit-v1]
platform = espressif32
board = esp32doit-devkit-v1
framework = arduino
lib_deps =
https://gitee.com/ohhuo/micro_ros_platformio.git
2.编写代码-实现订阅
编辑main.cpp,代码如下
#include <Arduino.h>
#include <micro_ros_platformio.h>
#include <rcl/rcl.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <std_msgs/msg/int32.h>
rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
// 声明话题订阅者
rcl_subscription_t subscriber;
// 声明消息文件
std_msgs__msg__Int32 sub_msg;
// 定义话题接收回调函数
void callback_subscription_(const void *msgin)
{
const std_msgs__msg__Int32 *msg = (const std_msgs__msg__Int32 *)msgin;
if (msg->data == 0)
{
digitalWrite(2, HIGH);
}
else
{
digitalWrite(2, LOW);
}
}
void setup()
{
Serial.begin(115200);
// 设置通过串口进行MicroROS通信
set_microros_serial_transports(Serial);
// 延时时一段时间,等待设置完成
delay(2000);
// 初始化内存分配器
allocator = rcl_get_default_allocator();
// 创建初始化选项
rclc_support_init(&support, 0, NULL, &allocator);
// 创建节点 topic_sub_test
rclc_node_init_default(&node, "topic_sub_test", "", &support);
// 订阅者初始化
rclc_subscription_init_default(
&subscriber,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
"led_control");
// 创建执行器
rclc_executor_init(&executor, &support.context, 1, &allocator);
// 为执行器添加一个订阅者
rclc_executor_add_subscription(&executor, &subscriber, &sub_msg, &callback_subscription_, ON_NEW_DATA);
// 初始化LED
pinMode(2, OUTPUT);
}
void loop()
{
delay(100);
// 循环处理数据
rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));
}
3. 代码注解
相比之前的节点代码这里主要多了这几行
#include <std_msgs/msg/int32.h>
添加消息类型头文件rcl_subscription_t subscriber;
声明话题订阅者std_msgs__msg__Int32 sub_msg;
声明消息文件,这一点和上位机不同,因为内存紧缺,所以提前定义、void callback_subscription_(const void *msgin)
接收到数据的回调函数rclc_subscription_init_default
初始化话题订阅者rclc_executor_add_subscription(&executor, &subscriber, &sub_msg, &callback_subscription_, ON_NEW_DATA);
,为执行器添加一个订阅者
4. 下载测试
连接开发板,编译下载。
4.1 启动Agent
打开终端启动agent
sudo docker run -it --rm -v /dev:/dev -v /dev/shm:/dev/shm --privileged --net=host microros/micro-ros-agent:$ROS_DISTRO serial --dev /dev/ttyUSB0 -v
点击下RST按钮,重启开发板,正常可以看到下图内容
4.2 测试控制
打开终端查看节点和话题
ros2 node list
ros2 topic list
关闭LED
ros2 topic pub /led_control std_msgs/msg/Int32 "{data: 0}" --once
打开LED
ros2 topic pub /led_control std_msgs/msg/Int32 "{data: 1}" --once
四、话题发布-上传电量信息
1. 新建工程添加依赖
新建example05_microros_topic_pub工程
修改platformio.ini添加依赖
[env:esp32doit-devkit-v1]
platform = espressif32
board = esp32doit-devkit-v1
framework = arduino
lib_deps =
https://gitee.com/ohhuo/micro_ros_platformio.git
2. 编写代码-实现订阅
编辑main.cpp,代码如下
#include <Arduino.h>
#include <micro_ros_platformio.h>
#include <rcl/rcl.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
// 添加头文件
#include <std_msgs/msg/float32.h>
rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
rcl_timer_t timer;
// 声明话题发布者
rcl_publisher_t publisher;
// 声明消息文件
std_msgs__msg__Float32 pub_msg;
// 定义定时器接收回调函数
void timer_callback(rcl_timer_t *timer, int64_t last_call_time)
{
RCLC_UNUSED(last_call_time);
if (timer != NULL)
{
rcl_publish(&publisher, &pub_msg, NULL);
}
}
void setup()
{
Serial.begin(115200);
// 设置通过串口进行MicroROS通信
set_microros_serial_transports(Serial);
// 延时时一段时间,等待设置完成
delay(2000);
// 初始化内存分配器
allocator = rcl_get_default_allocator();
// 创建初始化选项
rclc_support_init(&support, 0, NULL, &allocator);
// 创建节点 topic_sub_test
rclc_node_init_default(&node, "topic_pub_test", "", &support);
// 订阅者初始化
rclc_publisher_init_default(
&publisher,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float32),
"battery_voltage");
// 创建定时器,200ms发一次
const unsigned int timer_timeout = 200;
rclc_timer_init_default(
&timer,
&support,
RCL_MS_TO_NS(timer_timeout),
timer_callback);
// 创建执行器
rclc_executor_init(&executor, &support.context, 1, &allocator);
// 给执行器添加定时器
rclc_executor_add_timer(&executor, &timer);
// 初始化ADC
pinMode(34, INPUT);
analogSetAttenuation(ADC_11db);
}
void loop()
{
delay(100);
// 循环处理数据
rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));
// 通过ADC获取电压值
int analogValue = analogRead(34); // 读取原始值0-4096
int analogVolts = analogReadMilliVolts(34); // 读取模拟电压,单位毫伏
float realVolts = 5.02 * ((float)analogVolts * 1e-3); // 计算实际电压值
pub_msg.data = realVolts;
}
3. 代码注解
相比之前的节点代码这里主要多了这几行
#include <std_msgs/msg/float32.h>
包含flaot32类型头文件rcl_publisher_t publisher;
定义发布者std_msgs__msg__Float32 pub_msg;
定义发布消息,也需要提前定义void timer_callback(rcl_timer_t *timer, int64_t last_call_time)
定义定时器回调函数,当我们需要以某个频率做什么的时候定时器可以派上用场rclc_publisher_init_default
初始化发布者rclc_timer_init_default
初始化定时器rclc_executor_add_timer
给执行器添加一个定时器回调
4. 下载测试
连接开发板,编译下载。
4.1 启动Agent服务
打开终端启动agent
sudo docker run -it --rm -v /dev:/dev -v /dev/shm:/dev/shm --privileged --net=host microros/micro-ros-agent:$ROS_DISTRO serial --dev /dev/ttyUSB0 -v
点击下RST按钮,重启开发板,正常可以看到下图内容
4.2 测试是否连通
ros2 node list
ros2 topic list
4.3 查看话题数据
ros2 topic echo /battery_voltage
连接小车的电池后,VM电压代表电池电压,符合正常电压值范围。
同时可以使用下面指令测量话题频率
lll@lll:~/example05_microros_topic_pub$ ros2 topic hz /battery_voltage
average rate: 4.828
min: 0.207s max: 0.208s std dev: 0.00021s window: 6
average rate: 5.034
min: 0.106s max: 0.208s std dev: 0.02793s window: 12
average rate: 4.973
min: 0.106s max: 0.208s std dev: 0.02378s window: 17
average rate: 4.941
min: 0.106s max: 0.208s std dev: 0.02104s window: 22
average rate: 5.005
min: 0.106s max: 0.208s std dev: 0.02594s window: 28
average rate: 4.977
min: 0.106s max: 0.208s std dev: 0.02404s window: 33
average rate: 4.958
min: 0.106s max: 0.208s std dev: 0.02249s window: 38
average rate: 4.997
min: 0.106s max: 0.208s std dev: 0.02541s window: 44
五、服务实现-两数相加
1. 新建工程添加依赖
新建example06_microros_service_server工程
修改platformio.ini添加依赖
[env:esp32doit-devkit-v1]
platform = espressif32
board = esp32doit-devkit-v1
framework = arduino
lib_deps =
https://gitee.com/ohhuo/micro_ros_platformio.git
2. 编写代码-实现服务代码
编辑main.cpp,代码如下
#include <Arduino.h>
#include <micro_ros_platformio.h>
#include <rcl/rcl.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
// 添加接口
#include <example_interfaces/srv/add_two_ints.h>
rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
// 定义服务
rcl_service_t service;
// 服务请求和返回消息定义
example_interfaces__srv__AddTwoInts_Request req;
example_interfaces__srv__AddTwoInts_Response res;
// 服务回调函数
void service_callback(const void *req, void *res)
{
example_interfaces__srv__AddTwoInts_Request *req_in = (example_interfaces__srv__AddTwoInts_Request *)req;
example_interfaces__srv__AddTwoInts_Response *res_in = (example_interfaces__srv__AddTwoInts_Response *)res;
// 计算sum
res_in->sum = req_in->a + req_in->b;
}
void setup()
{
Serial.begin(115200);
// 设置通过串口进行MicroROS通信
set_microros_serial_transports(Serial);
// 延时时一段时间,等待设置完成
delay(2000);
// 初始化内存分配器
allocator = rcl_get_default_allocator();
// 创建初始化选项
rclc_support_init(&support, 0, NULL, &allocator);
// 创建节点 hello_microros
rclc_node_init_default(&node, "service_test", "", &support);
// 使用默认配置创建服务
rclc_service_init_default(&service, &node, ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, srv, AddTwoInts), "/addtwoints");
// 创建执行器
rclc_executor_init(&executor, &support.context, 1, &allocator);
// 执行器添加服务
rclc_executor_add_service(&executor, &service, &req, &res, service_callback);
}
void loop()
{
delay(100);
// 循环处理数据
rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));
}
3. 代码注解
相比之前的节点代码这里主要多了这几行
#include <example_interfaces/srv/add_two_ints.h>
添加接口头文件rcl_service_t service;
定义服务example_interfaces__srv__AddTwoInts_Request res;
定义请求数据存储位置example_interfaces__srv__AddTwoInts_Response req;
定义响应数据存储位置void service_callback(const void *req, void *res)
服务回调函数rclc_service_init_default(&service, &node, ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, srv, AddTwoInts), "/addtwoints");
使用默认配置初始化服务rclc_executor_add_service(&executor, &service, &req, &res, service_callback);
为执行器添加服务定义
4. 下载测试
连接开发板,编译下载。
4.1 启动Agent服务
打开终端启动agent
sudo docker run -it --rm -v /dev:/dev -v /dev/shm:/dev/shm --privileged --net=host microros/micro-ros-agent:$ROS_DISTRO serial --dev /dev/ttyUSB0 -v
击下RST按钮,重启开发板,正常可以看到下图内容
4.2 测试是否连通
ros2 node list
ros2 service list
测试服务
测试1+2,使用ROS2CLI
ros2 service call /addtwoints example_interfaces/srv/AddTwoInts "{a: 1, b: 2}"
成功的返回了3
=======================================================================================
MicroROS原理与使用进阶
六、无线通讯-了解传输原理
本节我们利用开发板上的WIFI功能尝试使用无线的方式连接Agent。
1. 新建工程并添加依赖
新建工程
新建example07_transport_wifi工程
添加依赖&修改配置
修改platformio.ini
[env:esp32doit-devkit-v1]
platform = espressif32
board = esp32doit-devkit-v1
framework = arduino
board_microros_transport = wifi
lib_deps =
https://gitee.com/ohhuo/micro_ros_platformio.git
注意这里的配置,我们多添加了一个board_microros_transport,这个配置值我们给的是wifi,表示无线传输。
除了WIFI还支持其他方式,比如蓝牙,但是需要们自定义协议
2. 编写代码
代码相对于串口通信只改变了三行,主要是设置wifi传输函数——set_microros_wifi_transports
,需要传入wifi名称,密码,电脑IP,端口号四个参数。电脑IP获取方式请参考第三部分。
#include <Arduino.h>
#include <micro_ros_platformio.h>
#include <WiFi.h>
#include <rcl/rcl.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
void setup()
{
Serial.begin(115200);
// 设置通过WIFI进行MicroROS通信
IPAddress agent_ip;
agent_ip.fromString("192.168.43.235");
// 设置wifi名称,密码,电脑IP,端口号
set_microros_wifi_transports("LLLLLL", "12345678", agent_ip, 8888);
// 延时时一段时间,等待设置完成
delay(2000);
// 初始化内存分配器
allocator = rcl_get_default_allocator();
// 创建初始化选项
rclc_support_init(&support, 0, NULL, &allocator);
// 创建节点 microros_wifi
rclc_node_init_default(&node, "microros_wifi", "", &support);
// 创建执行器
rclc_executor_init(&executor, &support.context, 1, &allocator);
}
void loop()
{
delay(100);
// 循环处理数据
rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));
}
3. 电脑IP获取
打开一个新的终端,输入ip -4 a | grep inet
看看电脑的ip地址,一般可以看到多个网卡的,此时可以忽略172(docker)和127(本地)开头的ip地址,剩下的一般就是我们要的ip地址,比如我这里的就是192.168.43.235
4. 下载测试
编译下载
启动Agent
打开终端输入指令,注意WIFI方式和之前的指令不太一样
docker run -it --rm -v /dev:/dev -v /dev/shm:/dev/shm --privileged --net=host microros/micro-ros-agent:$ROS_DISTRO udp4 --port 8888 -v6
点击RST,正确连接上可以看到
5. 测试是否连通
ros2 node list
本节开始,我们成功通过无线的方式将MicroROS连接到WIFI上来了,那问题来了,什么时候用串口模式,什么时候用WIFI模式呢?
- 串口模式,适合当我们用树莓派等主控板在机器人上时,直接串口连接树莓派即可
- WIFI模式,像FishBot一样,直接无线驱动机器人,WIFI此时就很合适了
七、 使用双核进行MicroROS
我们所使用的开发板单片机是ESP32 DEVKILTv1,搭载芯片为ESP32D0WDQ6,其双核是240M主频,但我们并没有真正的使用了双核,主频也是使用的默认160MHZ。
所以本节来提升主频并启动双核进行MicoROS的双核。
1. 双核与RTOS介绍
ESP32 系列命名规则
所谓双核指的是ESP32单片机有两个内核,所有的外设都通过一个总线连接到两个内核上,也就是说,程序无论在哪个核上运行都可以操作硬件。
官方开发平台ESP-IDF的核心其实是基于开源的FreeRTOS优化而来的,而ESP32-Arduino则是对ESP-IDF的进一步封装,所以毋庸置疑,ESP32-Ardunio也是支持FreeRTOS的。
2. 双核打印实验
接下来我们通过一个双核打印小实验来测试是否可以使用双核。
开始之前你需要了解两个函数
xPortGetCoreI()
获取当前程序所运行的内核ID,ID有0和1xTaskCreatePinnedToCore
启动一个TASK并将其绑定到指定ID的内核,ID有0和1
新建example08_micoros2core
修改platformio.ini
,提高主频
[env:esp32doit-devkit-v1]
platform = espressif32
board = esp32doit-devkit-v1
framework = arduino
board_build.f_cpu = 240000000L
board_microros_transport = wifi
lib_deps =
https://gitee.com/ohhuo/micro_ros_platformio.git
https//github.com/espressif/arduino-esp32.get
测试代码如下
#include <Arduino.h>
/**
* @brief MicroROSTASK,打印ID
*
* @param param
*/
void microros_task(void *param)
{
while (true)
{
delay(1000);
Serial.printf("microros_task on core:%d\n", xPortGetCoreID());
}
}
void setup()
{
Serial.begin(115200);
/**
* @brief 创建一个人物在Core 0 上
* microros_task 任务函数
* "microros_task" 任务名称
* 10240 任务占用内存大小
* NULL 任务参数,为空
* 1 任务优先级
* NULL 任务Handle可以为空
* 0 内核编号
*/
xTaskCreatePinnedToCore(microros_task, "microros_task", 10240, NULL, 1, NULL, 0);
}
void loop()
{
delay(1000);
Serial.printf("loop on core:%d\n", xPortGetCoreID());
}
测试结果
3. MicroROS双核实验
编写代码,在上节的代码稍微做些修改即可。
#include <Arduino.h>
#include <micro_ros_platformio.h>
#include <WiFi.h>
#include <rcl/rcl.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
/**
* @brief MicroROSTASK,打印ID
*
* @param param
*/
void microros_task(void *param)
{
// 设置通过WIFI进行MicroROS通信
IPAddress agent_ip;
agent_ip.fromString("192.168.43.235");
// 设置wifi名称,密码,电脑IP,端口号
set_microros_wifi_transports("LLLLLL", "12345678", agent_ip, 8888);
// 延时时一段时间,等待设置完成
delay(2000);
// 初始化内存分配器
allocator = rcl_get_default_allocator();
// 创建初始化选项
rclc_support_init(&support, 0, NULL, &allocator);
// 创建节点 microros_wifi
rclc_node_init_default(&node, "microros_wifi", "", &support);
// 创建执行器
rclc_executor_init(&executor, &support.context, 1, &allocator);
while (true)
{
delay(100);
Serial.printf("microros_task on core:%d\n", xPortGetCoreID());
// 循环处理数据
rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));
}
}
void setup()
{
Serial.begin(115200);
/**
* @brief 创建一个人物在Core 0 上
* microros_task 任务函数
* "microros_task" 任务名称
* 10240 任务占用内存大小
* NULL 任务参数,为空
* 1 任务优先级
* NULL 任务Handle可以为空
* 0 内核编号
*/
xTaskCreatePinnedToCore(microros_task, "microros_task", 10240, NULL, 1, NULL, 0);
}
void loop()
{
delay(1000);
Serial.printf("do some control on core:%d\n", xPortGetCoreID());
}
下载后,运行Agent即可测试
docker run -it --rm -v /dev:/dev -v /dev/shm:/dev/shm --privileged --net=host microros/micro-ros-agent:$ROS_DISTRO udp4 --port 8888 -v6
本节通过配置和启动新任务成功开启了另一内核并完成MicroROS相关的传输。你可能会问使用双核240M有什么坏处,坏处就是耗电