在库中安装如下:     务必注意版本号,最好用0.7.8,其他版本均出现不正常状况!   这里记录两个重要的功能:
  • ESP8266WiFi.h
  • ros.h
  espros在github上下载,目前还是比较小众的,星星都没有过百呢!   两段代码简单测试一下:

chatter

 
#include <ESP8266WiFi.h>  
#include <ros.h>
#include <std_msgs/String.h>
#include <std_msgs/Int16.h>
#include <std_msgs/Float64.h>
 
ros::NodeHandle nh;
int led;
 
void messageCb(const std_msgs::Int16& msg) {
  if(msg.data > 0){
    led=abs(msg.data);
    digitalWrite(led, HIGH-digitalRead(led));   // blink the led
  }
}
 
std_msgs::String str_msg;
ros::Publisher chatter("chatter", &str_msg);
ros::Subscriber<std_msgs::Int16> sub("led", &messageCb);
 
char hello[15] = "ESP8266 alive!";
 
void setup()
{
  pinMode(2, OUTPUT);
  pinMode(12, OUTPUT);
  pinMode(13, OUTPUT);
  pinMode(15, OUTPUT);
  nh.initNode();
  nh.advertise(chatter);
  nh.subscribe(sub);
}
 
void loop()
{
  str_msg.data = hello;
  chatter.publish( &str_msg );
  nh.spinOnce();
  delay(1000);
}
  注意,2号可以开关wifi边上的小灯哦。  
Sketch uses 266816 bytes (25%) of program storage space. Maximum is 1044464 bytes.
Global variables use 28452 bytes (34%) of dynamic memory, leaving 53468 bytes for local variables. Maximum is 81920 bytes.
esptool.py v2.6
2.6
esptool.py v2.6
Serial port /dev/ttyUSB0
Connecting....
Chip is ESP8266EX
Features: WiFi
MAC: 2c:f4:32:2d:58:0a
Uploading stub...
Running stub...
Stub running...
Changing baud rate to 460800
Changed.
Configuring flash size...
Auto-detected Flash size: 4MB
Compressed 270976 bytes to 197513...
 
Writing at 0x00000000... (7 %)
Writing at 0x00004000... (15 %)
Writing at 0x00008000... (23 %)
Writing at 0x0000c000... (30 %)
Writing at 0x00010000... (38 %)
Writing at 0x00014000... (46 %)
Writing at 0x00018000... (53 %)
Writing at 0x0001c000... (61 %)
Writing at 0x00020000... (69 %)
Writing at 0x00024000... (76 %)
Writing at 0x00028000... (84 %)
Writing at 0x0002c000... (92 %)
Writing at 0x00030000... (100 %)
Wrote 270976 bytes (197513 compressed) at 0x00000000 in 4.6 seconds (effective 472.9 kbit/s)...
Hash of data verified.
 
Leaving...
Hard resetting via RTS pin...
  试下如下命令吧:   rosrun rosserial_arduino serial_node.py _port:=/dev/ttyUSB0     rostopic list rostopic pub /led std_msgs/Int16 "data: 2" rostopic echo /chatter    

esproswifi

 
#include <ESP8266WiFi.h>
#include <ros.h>
#include <std_msgs/String.h>
#include <std_msgs/Int16.h>
#include <std_msgs/Float64.h>
#include <Servo.h>
 
//
// WiFi Definitions //
//
const char* ssid = "HUAWEI_WiFi";
const char* password = "xxxxxxxx";
 
IPAddress server(192, 168, 3, 153); // ip of your ROS server
IPAddress ip_address;
int status = WL_IDLE_STATUS;
 
WiFiClient client;
 
class WiFiHardware {
 
  public:
  WiFiHardware() {};
 
  void init() {
    // do your initialization here. this probably includes TCP server/client setup
    client.connect(server, 11411);
  }
 
  // read a byte from the serial port. -1 = failure
  int read() {
    // implement this method so that it reads a byte from the TCP connection and returns it
    //  you may return -1 is there is an error; for example if the TCP connection is not open
    return client.read();         //will return -1 when it will works
  }
 
  // write data to the connection to ROS
  void write(uint8_t* data, int length) {
    // implement this so that it takes the arguments and writes or prints them to the TCP connection
    for(int i=0; i<length; i++)
      client.write(data[i]);
  }
 
  // returns milliseconds since start of program
  unsigned long time() {
     return millis(); // easy; did this one for you
  }
};
 
Servo s;
int i;
 
void chatterCallback(const std_msgs::String& msg) {
  i = atoi(msg.data);
  s.write(i);
}
 
ros::Subscriber<std_msgs::String> sub("message", &chatterCallback);
ros::NodeHandle_<WiFiHardware> nh;
 
void setupWiFi()
{
  WiFi.begin(ssid, password);
  Serial.print("\nConnecting to "); Serial.println(ssid);
  uint8_t i = 0;
  while (WiFi.status() != WL_CONNECTED && i++ < 20) delay(500);
  if(i == 21){
    Serial.print("Could not connect to"); Serial.println(ssid);
    while(1) delay(500);
  }
  Serial.print("Ready! Use ");
  Serial.print(WiFi.localIP());
  Serial.println(" to access client");
}
 
void setup() {
  Serial.begin(115200);
  setupWiFi();
  delay(2000);
  s.attach(2);  // PWM pin
  nh.initNode();
  nh.subscribe(sub);
}
 
void loop() {
  nh.spinOnce();
  delay(500);
}
  注意wifi名称和密码一定要正确!!!   然后就一切正常了:     使用如下命令: rosrun rosserial_python serial_node.py tcp  
#include <ESP8266WiFi.h>
#include <ros.h>
#include <std_msgs/String.h>
#include <std_msgs/Int16.h>
#include <std_msgs/Float64.h>
#include <Servo.h>
 
//
// WiFi Definitions //
//
const char* ssid = "HUAWEI_WiFi";
const char* password = "cslgcslg";
 
IPAddress server(192, 168, 3, 153); // ip of your ROS server
IPAddress ip_address;
int status = WL_IDLE_STATUS;
 
WiFiClient client;
 
class WiFiHardware {
 
  public:
  WiFiHardware() {};
 
  void init() {
    // do your initialization here. this probably includes TCP server/client setup
    client.connect(server, 11411);
  }
 
  // read a byte from the serial port. -1 = failure
  int read() {
    // implement this method so that it reads a byte from the TCP connection and returns it
    //  you may return -1 is there is an error; for example if the TCP connection is not open
    return client.read();         //will return -1 when it will works
  }
 
  // write data to the connection to ROS
  void write(uint8_t* data, int length) {
    // implement this so that it takes the arguments and writes or prints them to the TCP connection
    for(int i=0; i<length; i++)
      client.write(data[i]);
  }
 
  // returns milliseconds since start of program
  unsigned long time() {
     return millis(); // easy; did this one for you
  }
};
 
Servo s;
int i;
 
void chatterCallback(const std_msgs::String& msg) {
  i = atoi(msg.data);
  s.write(i);
}
 
 
std_msgs::String str_msg;
ros::Publisher chatter("chatter", &str_msg);
ros::Subscriber<std_msgs::String> sub("message", &chatterCallback);
ros::NodeHandle_<WiFiHardware> nh;
char hello[20] = "ESP8266 wifi alive!";
 
 
void setupWiFi()
{
  WiFi.begin(ssid, password);
  Serial.print("\nConnecting to "); Serial.println(ssid);
  uint8_t i = 0;
  while (WiFi.status() != WL_CONNECTED && i++ < 20) delay(500);
  if(i == 21){
    Serial.print("Could not connect to"); Serial.println(ssid);
    while(1) delay(500);
  }
  Serial.print("Ready! Use ");
  Serial.print(WiFi.localIP());
  Serial.println(" to access client");
}
 
void setup() {
  Serial.begin(115200);
  setupWiFi();
  delay(2000);
  s.attach(2);  // PWM pin
  nh.initNode();
  nh.advertise(chatter);
  nh.subscribe(sub);
}
 
void loop() {
  str_msg.data = hello;
  chatter.publish( &str_msg );
  nh.spinOnce();
  delay(500);
}