PS:再之前完成了环境的布置之后 继续开发Microros与CAN的网关 遇到了一些问题
(1)接收can数据与ROS_topic数据无法并存的问题
(2)发布的topic 没办法使用自定义的msg消息
(3)发布的topic 数据包没有达到设定的50hz
问题1---解决方式:
压榨ESP32--(使用双核 一个负责处理执行器任务 一个负责接收can数据并解析(车端的CAN报文较多--个人认为压力较大&&优先级较高))
// 创建并固定 MicroRosTask 到核心 0,任务堆栈大小为 10000 字节,优先级为 1,任务参数为 NULL,不需要任务句柄
xTaskCreatePinnedToCore(MicroRos, "MicroRosTask", 10000, NULL, 2, NULL, 0);
// 创建并固定 CanTask 到核心 1,任务堆栈大小为
// 10000字节,优先级为2(高于MicroRosTask),任务参数为NULL,不需要任务句柄
xTaskCreatePinnedToCore(Receive_CAN, "CanTask", 10000, NULL, 1, NULL, 1);
void MicroRos(void* pvParameters)
{
while (1)
{
rclc_executor_spin_some(&executor, RCL_MS_TO_NS(20));
}
}
void Receive_CAN(void* pvParameters)
{
while (1)
{
if (xQueueReceive(CAN_cfg.rx_queue, &rx_frame, portMAX_DELAY))
{
switch (rx_frame.MsgID)
{
case 0x221:
Parse221_CAN(rx_frame.data.u8, rx_frame.FIR.B.DLC);
break;
case 0x361:
Parse361_CAN(rx_frame.data.u8, rx_frame.FIR.B.DLC);
break;
case 0x131:
Parse131_CAN(rx_frame.data.u8, rx_frame.FIR.B.DLC);
break;
}
}
}
}
问题2:发布的topic 数据包没有达到设定的50hz
暴力解决:提高串口的波特率-由 115200 提升至 230400(PS 可能会存在问题 还是需要修改topic的数量 优化一下)
Serial.begin(230400);
set_microros_serial_transports(Serial);
delay(2000);
问题3:无法使用自定义的msg包
这个问题困扰了挺久的:
首先gpt推荐的方式就说的不清不楚。。
推荐的方式基本都是标准ROS2 创建 msg 的方式 然后修改CMakeList...
个人测试----不行 直接编译报错
然后还有问题:
build_flags =
-I${PROJECT_DIR}/include/microros_msgs/msg
-L${PROJECT_DIR}/lib
-lmicroros_msgs__rosidl_generator_c
-lmicroros_msgs__rosidl_typesupport_c
-lmicroros_msgs__rosidl_typesupport_introspection_c
-lmicroros_msgs__rosidl_typesupport_microxrcedds_c
在platformio.ini添加配置的时候好像一定要按照上述的格式------y以msg结尾??不然就给我报错
不知道是不是我的问题。。。。
解决方式:(个人做法 先通过freertos 创建自定义的msg包 然后将其复制到platformio的项目工程中)
First micro-ROS Application on FreeRTOS | micro-ROS
Microros 官方推荐的使用自定义msg包的方式
步骤:
(1)在自己的电脑上创建一个工作空间--(Microros_WorkSpace)
(2)执行上述图片中的步骤--
这时候工作空间应该是这样的:注意:没有firmware!!!!!!
(3)执行下述命令--(最后一条代表开发板 我使用的ESP32-WROOM-32)
官方命令:
ros2 run micro_ros_setup create_firmware_ws.sh freertos olimex-stm32-e407
我执行的命令:
ros2 run micro_ros_setup create_firmware_ws.sh freertos esp32
然后工作空间就多了firmware!!
然后:
cd firmware/mcu_ws
ros2 pkg create --build-type ament_cmake microros_msgs
cd microros_msgs
mkdir msg
touch msg/ControlCar.msg
然后在.msg文件中添加自定义的msg消息
继续按照这个步骤走:
How to include a custom ROS message in micro-ROS | micro-ROS
(1)修改CMakeList && package.xml
CMakeList 添加:
...
find_package(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/MyCustomMessage.msg"
)
...
package.xml 添加:
...
<build_depend>rosidl_default_generators</build_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
...
然后 退出到 Microros_WorkSpace
source install/setup.bash
ros2 run micro_ros_setup build_firmware.sh
最后将生成的msg包复制到PlatformIO的项目工程中:
然后就看到 我们自定义的msg消息发布成功了: