DOCUMENTATION
First micro-ROS Application on FreeRTOS
void subscription_callback(const void * msgin)
{
const std_msgs__msg__String * msg = (const std_msgs__msg__String *)msgin;
// Process message
printf("Received from HOST: %s\n\r", msg->data);
}
void microros_task(void *argument)
{
rmw_uros_set_custom_transport( true, (void *) &huart1, cubemx_transport_open, cubemx_transport_close, cubemx_transport_write, cubemx_transport_read);
rcl_allocator_t freeRTOS_allocator = rcutils_get_zero_initialized_allocator();
freeRTOS_allocator.allocate = microros_allocate;
freeRTOS_allocator.deallocate = microros_deallocate;
freeRTOS_allocator.reallocate = microros_reallocate;
freeRTOS_allocator.zero_allocate = microros_zero_allocate;
if (!rcutils_set_default_allocator(&freeRTOS_allocator)) {
printf("Error on default allocators (line %d)\n", __LINE__);
}
// micro-ROS app
rclc_support_t support;
rcl_allocator_t allocator;
allocator = rcl_get_default_allocator();
// create node
rcl_node_t node;
rcl_node_options_t node_ops = rcl_node_get_default_options();
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
rcl_init_options_init(&init_options, allocator);
rcl_init_options_set_domain_id(&init_options, ROS_DOMAIN_ID);
rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator);
rclc_node_init_default(&node, "STM32_Node","", &support);
// create publisher
rcl_publisher_t publisher;
std_msgs__msg__String sensor_dist_back_msg;
rclc_publisher_init_default(&publisher, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String),"/sensor/dist_back");
// create subscriber
rcl_subscription_t subscriber;
std_msgs__msg__String str_msg;
rclc_subscription_init_default(&subscriber,&node,ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String),"/command/move");
// Add subscription to the executor
rclc_executor_t executor;
rclc_executor_init(&executor, &support.context, 1, &allocator); // ! 'NUMBER OF HANDLES' A MODIFIER EN FONCTION DU NOMBRE DE TOPICS
rclc_executor_add_subscription(&executor, &subscriber, &str_msg, &subscription_callback, ON_NEW_DATA);
str_msg.data.data = (char * ) malloc(ARRAY_LEN * sizeof(char));
str_msg.data.size = 0;
str_msg.data.capacity = ARRAY_LEN;
for(;;)
{
sprintf(str_msg.data.data, "from STM32 : mes_vl53 : #%d", (int32_t)mes_vl53);
str_msg.data.size = strlen(str_msg.data.data);
rcl_ret_t ret = rcl_publish(&publisher, &str_msg, NULL);
if (ret != RCL_RET_OK)
{
printf("Error publishing (line %d)\n\r", __LINE__);
}
rclc_executor_spin_some(&executor, RCL_MS_TO_NS(10));
osDelay(10);
}
}
REMARQUE : Les types utilisés pour l’échange de messages ROS, de même que le nom des topics, ne sont qu’indicatifs.
Nous considérons un réseau wifi local sur lequel communiquent le PC et le RPI.
Afin de pouvoir utiliser le formalisme ROS2 sur la carte STM32, nous utilisons micro ROS .
La carte STM32 utilise alors un périphérique UART pour échanger des messages avec le RPI.
Côté RPI, il est nécéssaire de lancer micro_ros_agent :
Sources Compilées :
cd ~
wget https://web.enib.fr/~kerhoas/automatique-robotique/robot-mobile-rpi-ros2/ros2-et-micro-ros/microros_ws.zip
unzip microros_ws.zip
cd microros_ws/
source install/local_setup.bash
Sources à Compiler :
# COMPILE
# https://micro.ros.org/docs/tutorials/core/first_application_linux/
mkdir ~/microros_ws
cd ~/microros_ws
git clone -b $ROS_DISTRO https://github.com/micro-ROS/micro_ros_setup.git src/micro_ros_setup
rosdep install --from-paths src --ignore-src -y
colcon build
source install/local_setup.bash
# Create firmware step
ros2 run micro_ros_setup create_firmware_ws.sh host
ros2 run micro_ros_setup build_firmware.sh
source install/local_setup.bash
# Download micro-ROS-Agent packages
ros2 run micro_ros_setup create_agent_ws.sh
ros2 run micro_ros_setup build_agent.sh
source install/local_setup.bash
# LAUNCH
cd ~/microros_ws
. install/setup.bash
ros2 run micro_ros_agent micro_ros_agent serial --dev /dev/ttyUSB0 -b 115200
REMARQUES:
cd ~/microros_ws
pkill -9 micro_ros_agent
ros2 run micro_ros_agent micro_ros_agent serial --dev /dev/ttyUSB0 -b 115200
Pour écouter les messages en provenance de la STM32 :
ros2 topic echo /sensor/dist_back
Pour envoyer un message à la STM32 :
ros2 topic pub --rate 1 /command/move std_msgs/msg/String "data: f"
Analyse avec rqt :