개발관련/ROS

rosserial esp8266 wifi통신(tcp)

Dol42 2021. 1. 28. 19:58

ROS와 ESP32 tcp 통신을 진행해 보았다.

 

우선 ESP32 또는 ESP8266 보드를 아두이노 IDE 환경에서 개발하고, 업로드 하기위해 

환경설정 - 추가적인보드 매니저 URLs 에 다음과 같이 두개의 URL을 추가한다. 

http://arduino.esp8266.com/stable/package_esp8266com_index.json
https://dl.espressif.com/dl/package_esp32_index.json

 

 

보드를 추가하기 위해 툴 -> 보드 -> 보드매니저 로 들어가서  esp32와 esp8266 보드를 설치해준다. 

 

 

소스코드

/// ROS-Esp WiFi(tcp)
/// doljokilab.tistory.com
/// dol42@kakao.com
/// made by. dol

#include <WiFi.h> // if use esp32
//#include <ESP8266WiFi.h> // if use esp8266
#include <ros.h>
#include <std_msgs/String.h>


const char* ssid     = "your_wifi_name"; //wifi name ex) iptime
const char* password = "your_ssid_pw"; //ssid passwd ex) 12345678!

IPAddress server(000, 000, 000, 000); //target ip address(roscore) ex) 192.111.111.111 -> 192,111,111,111
const uint16_t serverPort = 11411; //target port(roscore) 

ros::NodeHandle nh;
std_msgs::String str_msg;
ros::Publisher chatter("chatter", &str_msg);
char hello[13] = "doljokilab";


void setup() {
  Serial.begin(115200);
  Serial.println();
  Serial.print("Connecting to ");
  Serial.println(ssid);

  WiFi.mode(WIFI_STA);
  WiFi.begin(ssid, password);

  while (WiFi.status() != WL_CONNECTED) {
    delay(500);
    Serial.print(".");
  }

  Serial.println("");
  Serial.println("WiFi connected");
  Serial.println("IP address: ");
  Serial.println(WiFi.localIP());

  Serial.println("connection Start");

  nh.getHardware()->setConnection(server, serverPort);
  Serial.println(nh.getHardware()->getLocalIP());
  nh.initNode();
  nh.advertise(chatter);

  str_msg.data = hello;
}

void loop() {


  if (!nh.connected()) {
    Serial.println("connection failed");
  }

  else  {
    Serial.println("Connected");
    chatter.publish( &str_msg );
  }

    nh.spinOnce();
    delay(5000);


}

실행화면

ESP-32(LOLIN D32)에서 실행한 시리얼모니터 화면은 다음과 같다.

 

ROS

사전에 rosserial이 설치 되어있어야 한다. 

업로드 후 roscore 실행 후 다음과 같이 실행

rosrun rosserial_python serial_node.py tcp

 

실행결과

확인을 위해 다음을 입력하여 /chatter 토픽을 확인해본다. 

rostopic echo /chatter

실행결과

/chatter 토픽 data가 제대로 받아지는 것을 확인 가능하다. 

 

 

반응형