Simple ROS publisher works with Arduino MEGA 2560 not ESP32

asked 2023-03-24 17:13:19 -0500

BigBadJohn gravatar image

updated 2023-03-24 17:14:40 -0500

I am having a problem getting a simple ROS publisher to run on an ESP32 Dev Board, when the same code works fine with the MEGA 2560.

I am running ROS1 Melodic on Jetson Nano with ubuntu 18.04 LTS and the Arduino IDE 1.8.10.

The sketch is from example at File/Example/ros_lib/Blink that turns an LED on/Off by publishing a std_msgs::Empty on topic "toggle_led" shown below:

/* 
 * rosserial Subscriber Example
 * Blinks an LED on callback
 */

#include <ros.h>
#include <std_msgs/Empty.h>

ros::NodeHandle  nh;

void messageCb( const std_msgs::Empty& toggle_msg){
  digitalWrite(LED_BUILTIN, HIGH-digitalRead(LED_BUILTIN));   // blink the led
}

ros::Subscriber<std_msgs::Empty> sub("toggle_led", &messageCb );

void setup()
{ 
  pinMode(LED_BUILTIN, OUTPUT);
  nh.getHardware()->setBaud(115200);
  nh.initNode();
  nh.subscribe(sub);
}

void loop()
{  
  nh.spinOnce();
  delay(1);
}

If I upload this to my MEGA 2560 and run ROS cmds: roscore rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0 _baud:=115200

it runs properly and I can see the message published to "toggle_led" and the LED ON/OFF. Note that it requires the "nh.getHardware()->setBaud(115200);" line in setup to work (not in original example). This addition was in a tutorial on the subject without explanation.

If I run the same code on ESP32, again with extra line in setup and using gpio22 instead of LED_BUILTIN (not supported), I get an error: exit status 1 'class ArduinoHardware' has no member named 'setBaud'

If I comment out the line it compiles but after running roscore and rosserial as above, it gives and error: I have tried to chase this down but have come up short and thus cannot run a publisher on the ESP32 Dev Board, which I really would like to do.

Any help is greatly appreciated.

edit retag flag offensive close merge delete