ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

How to connect my arduino + esp01 to my PC via wifi to publish and subscribe data using ROS?

asked 2019-02-20 04:43:04 -0500

diogosilva0307 gravatar image

Hello everyone!

I really need to connect my arduino + esp01 via wifi to my PC because i need to send sensor data from the Arduino and send commands of speed from my PC to the arduino. I know that rosserial-arduino works but not for a WiFi connection. I also saw the ROS serial for ESP8266 over WiFi but i don't know if that works using my setup. Can anyone help me please?

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2021-03-13 15:28:23 -0500

mecb1407 gravatar image

Hello @VisoVa, my solution was modified ArduinoTcpHardware.h. Here I added my esp32. The file finish is:

#ifndef ROS_ARDUINO_TCP_HARDWARE_H_
#define ROS_ARDUINO_TCP_HARDWARE_H_

#include <Arduino.h>
#if defined(ESP8266)
  #include <ESP8266WiFi.h>
#elif defined(ESP32)
  #include <WiFi.h> // Using Espressif's WiFi.h
#else
  #include <SPI.h>
  #include <Ethernet.h>
#endif

class ArduinoHardware {
public:
  ArduinoHardware()
  {
  }

  void setConnection(IPAddress &server, int port = 11411)
  {
    server_ = server;
    serverPort_ = port;
  }

  IPAddress getLocalIP()
  {
#if defined(ESP8266) or defined(ESP32)
    return tcp_.localIP();
#else
    return Ethernet.localIP();
#endif
  }

  void init()
  {
    if(tcp_.connected())
    {
      tcp_.stop();
    }
    tcp_.connect(server_, serverPort_);
  }

  int read(){
    if (tcp_.connected())
    {
        return tcp_.read();
    }
    else
    {
      tcp_.stop();
      tcp_.connect(server_, serverPort_);
    }
    return -1;
  }

  void write(const uint8_t* data, int length)
  {
    tcp_.write(data, length);
  }

  unsigned long time()
  {
    return millis();
  }

  bool connected()
  {
    return tcp_.connected();
  }

protected:
#if defined(ESP8266) or defined(ESP32)
  WiFiClient tcp_;
#else
  EthernetClient tcp_;
#endif
  IPAddress server_;
  uint16_t serverPort_ = 11411;
};

#endif
edit flag offensive delete link more

Comments

Thank you very much! I have successfully created a publisher for the accelerations read by Arduino uno wifi rev2. I will put online the code in the question I have created.

VisoVa gravatar image VisoVa  ( 2021-03-14 13:12:31 -0500 )edit
0

answered 2020-03-12 00:37:25 -0500

tomarRobin gravatar image

hey there,

rosserial also works with wifi. you can establish a tcp connection between your esp and rosserial_python which is a part of rosserial package. you need to know the ip address of the device on which you are running ros and the port address. by default rosserial_python tcp socket listens to 11411 port.

this is for the server side, in the pc.

<node  pkg="rosserial_python" type="serial_node.py" args="tcp 11412" output="screen"/>

for esp arduino you need to provide ip and port no. to establish the connection. this code is from one of my projects you can have an idea from this

#include <ESP8266WiFi.h>
#include <ros.h>
#include <std_msgs/Int16.h>


// Init constants and global variables

#define DEBUG 1

// WiFi configuration. Replace '***' with your data

const char* ssid = "******";
const char* password = "*******";
IPAddress server(10,42,0,1);//192.168.43.94      // Set the rosserial socket ROSCORE SERVER IP address
const uint16_t serverPort = 11411;    // Set the rosserial socket server port


// Functions definitions //

void setupWiFi() {   
  WiFi.disconnect();// connect to ROS server as as a client
  WiFi.mode(WIFI_STA); 
  if(DEBUG){
    Serial.print("Connecting to ");
    Serial.println(ssid);
    WiFi.begin(ssid, password);

  }
  while (WiFi.status() != WL_CONNECTED) {
    delay(100);
  }
  if(DEBUG){
    Serial.println("");
    Serial.println("WiFi connected");
    Serial.println("IP address: ");
    Serial.println(WiFi.localIP());
  }
}
std_msgs::Int16 int_msg_1;
std_msgs::Int16 int_msg_2;
std_msgs::Int16 int_msg_3;
std_msgs::Int16 int_msg_4;
std_msgs::Int16 int_msg_5;
std_msgs::Int16 int_msg_6;
std_msgs::Int16 int_msg_7;


// ROS nodes //
ros::NodeHandle nh;

// ROS topics object definitions PUBLISHERS
ros::Publisher pub_value_1("sensor_1_value", &int_msg_1);
ros::Publisher pub_value_2("sensor_2_value", &int_msg_2);
ros::Publisher pub_value_3("sensor_3_value", &int_msg_3);
ros::Publisher pub_value_4("sensor_4_value", &int_msg_4);
ros::Publisher pub_value_5("sensor_5_value", &int_msg_5);
ros::Publisher pub_value_6("sensor_6_value", &int_msg_6);
ros::Publisher pub_value_7("sensor_7_value", &int_msg_7);


void (*resetFunc)(void)=0;
// ROS SUBSCRIBERS

void setup() {
  Serial.begin(115200);
  Serial.print("inside setup");
  if(DEBUG) Serial.begin(115200);
  Serial.print("setting up wifi");
  setupWiFi();
  delay(200);
//Ros objects constructors   
  nh.getHardware()->setConnection(server, serverPort);
  nh.initNode();
  nh.advertise(pub_value_1);
  nh.advertise(pub_value_2);
  nh.advertise(pub_value_3);
  nh.advertise(pub_value_4);
  nh.advertise(pub_value_5);
  nh.advertise(pub_value_6);
  nh.advertise(pub_value_7);




// configure GPIO's and Servo
  pinMode(D10, INPUT); // 1,2EN aka D1 pwm left
  pinMode(D11, INPUT); // 3,4EN aka D2 pwm right
  pinMode(D12, INPUT); // 1A,2A aka D3
  pinMode(D13, INPUT); // 3A,4A aka D4
  pinMode(D4, INPUT); //  Left encoder
  pinMode(A0, INPUT); //  Left encoder

 digitalWrite(D10,LOW);
 digitalWrite(D11,LOW);
 digitalWrite(D12,LOW);
 digitalWrite(D13,LOW);
 digitalWrite(D4,LOW);
}


void loop() {
  if ( WiFi.status() ==  WL_CONNECTED ) 
  {
    // WiFi is UP,  do what ever
     Serial.print(" wifi connected ");
  if (nh.connected()) 
  {

    Serial.println(" node connected ");
    int_msg_1.data = digitalRead(D13);
    pub_value_1.publish(&int_msg_1);
    int_msg_2.data= digitalRead(D12);
    pub_value_2.publish(&int_msg_2); 
    int_msg_3.data= digitalRead(D11);
    pub_value_3.publish(&int_msg_3);
    int_msg_4.data= digitalRead(D10); 
    pub_value_4.publish(&int_msg_4); 
    int_msg_5.data= digitalRead(D4);
    pub_value_5.publish(&int_msg_5);

    int_msg_7.data = analogRead(A0);
    pub_value_7.publish(&int_msg_7);   


  } 
  else {
    if(DEBUG) Serial.println("Node not Connected");
  }
  }
  else
  {
  Serial.println("calling reset function");
  resetFunc();
  }

  nh.spinOnce();
  delay(1000);  // milliseconds changed to 1000 from 300
}

hope it helps.

edit flag offensive delete link more

Comments

Hello, thank you very much for your help. I am currently working with the ESP32, I do all the steps you indicate, but I have the following result:

Waiting for socket connections on port 11411 waiting for socket connection

I run my program in arduino, but it does not connect with the card. I would greatly appreciate your help.

Greetings,

Manuel Contreras.

mecb1407 gravatar image mecb1407  ( 2020-10-29 13:17:01 -0500 )edit

I have the same problem, have you solved it? @tomarRobin, can you specify please the ROS, ubuntu and rosserial version you are using?

VisoVa gravatar image VisoVa  ( 2021-03-13 08:31:10 -0500 )edit

Question Tools

Stats

Asked: 2019-02-20 04:43:04 -0500

Seen: 2,047 times

Last updated: Mar 13 '21