micro-ROS / micro_ros_arduino

micro-ROS library for Arduino
Apache License 2.0
446 stars 116 forks source link

rclc_support_init() raises error in the micro-ros_publisher_wifi example - ESP32 #1223

Closed LucasR-GIT closed 1 year ago

LucasR-GIT commented 1 year ago

Hello !

I'm working with ESP32 with the Arduino IDE and I'm trying to create a simple publisher on it. My goal is to send data on my ROS master (ROS Noetic) then retrieve it with a subscriber in Matlab connected to this master.

I tried to run the "micro-ros_publisher_wifi" example (slightly modified, exact code bellow) but the rclc_support_init() function systematically goes into the error_loop() function. I double checked the WiFi SSID / password and the ROS Master IP / Port parameters and everything seem correct to me. Any Idea ?

Code :

#include <micro_ros_arduino.h>

#include <stdio.h>
#include <rcl/rcl.h>
#include <rcl/error_handling.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>

#include <std_msgs/msg/int32.h>

#if !defined(ESP32) && !defined(TARGET_PORTENTA_H7_M7) && !defined(ARDUINO_NANO_RP2040_CONNECT)
#error This example is only avaible for Arduino Portenta, Arduino Nano RP2040 Connect and ESP32 Dev module
#endif

rcl_publisher_t publisher;
std_msgs__msg__Int32 msg;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;

#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){error_loop();}}
#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){}}

void error_loop(){
  while(1){
    Serial.println("ERROR");
    delay(500);
    //break;
  }
}

void timer_callback(rcl_timer_t * timer, int64_t last_call_time)
{
  RCLC_UNUSED(last_call_time);
  if (timer != NULL) {
    RCSOFTCHECK(rcl_publish(&publisher, &msg, NULL));
    msg.data++;
  }
}

void setup() {
  Serial.begin(115200);
  set_microros_wifi_transports("WiFi_MoCap", "WiFi_MoCap@pwd", "192.168.0.100", 11311);
  Serial.println("Connected to WiFi");

  delay(2000);

  allocator = rcl_get_default_allocator();
  Serial.println("Allocator OK");

  delay(500);

  //create init_options
  RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
  Serial.println("Init options OK");

  delay(500);

  // create node
  RCCHECK(rclc_node_init_default(&node, "uwb_node", "", &support));
  Serial.println("Node OK");

  // create publisher
  RCCHECK(rclc_publisher_init_best_effort(&publisher, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "uwb_topic"));
  Serial.println("Publisher OK");

  msg.data = 0;
}

void loop() {
    RCSOFTCHECK(rcl_publish(&publisher, &msg, NULL));
    msg.data++;
    Serial.print("Sends to topic : uwb_topic - msg : ");
    Serial.println(msg.data);
}

Serial monitor output :

Connected to WiFi
Allocator OK
ERROR
ERROR
...

Thank you in advance !

pablogs9 commented 1 year ago

micro-ROS is compatible with ROS 2, not with ROS 1 (ROS Noetic): https://micro.ros.org/

GeorgeNegret commented 1 year ago

Hi @pablogs9 , I'm working with ESP32dev with the vs Code + Platformio , host computer : Ubuntu 22.04 + ros2 humble and I have the same error !

my platformio.ini code

[env:esp32dev]
platform =  https://github.com/platformio/platform-espressif32.git
framework = arduino
board = esp32dev
monitor_speed = 115200

lib_deps = 
  WiFi
    https://github.com/micro-ROS/micro_ros_arduino.git
build_flags = 
    -L ./.pio/libdeps/esp32dev/micro_ros_arduino/src/esp32/
    -l microros
        -D ESP32
platform_packages = 
  toolchain-xtensa32
  platformio/framework-arduinoespressif32  @ https://github.com/espressif/arduino-esp32.git

my main.cpp code

#include <micro_ros_arduino.h>
#include <stdio.h>
#include <rcl/rcl.h>
#include <rcl/error_handling.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <std_msgs/msg/int32.h>

rcl_publisher_t publisher;
std_msgs__msg__Int32 pub_msg;
// WiFi credentials
char ssid[] = "TP-LINK_E9E8";
char password[] = "2016****";

char agent_ip[] = "192.168.0.105";
uint agent_port = 8888;

#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){while(1){Serial.println("Failed at setup"); delay(1000);};}}
#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){}}

void setup() {
  Serial.begin(115200);
  Serial.println("setup start");
  set_microros_wifi_transports(ssid, password, agent_ip , agent_port);
  // set_microros_transports();
  delay(2000);

  rcl_allocator_t allocator = rcl_get_default_allocator();
  rclc_support_t support;
  RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
  Serial.println("setup done");
}
void loop() {
}