Dear all,
I am currently running an Arduino Uno* with an [ATWINC1500 WiFi ](https://www.adafruit.com/product/2999) breakout from Adafruit and can successfully publish topics over WiFi to a master using `rosrun rosserial_python serial_node.py tcp`. This has been achieved using code modified from [this previous ROS answer](https://answers.ros.org/question/232774/launch-a-ros-node-over-wifi/) supplied by [@ahendrix](https://answers.ros.org/users/1034/ahendrix/).
The trouble I run into is running two of these devices at the same time. They both have unique IP addresses and are connected to the network, running differently named topics, and individually can be successfully connected and publish topics.
The first device can be connected using `rosrun rosserial_python serial_node.py tcp`. Simply starting a second device does not lead to be being connected. If I run a second serial_node.py with a different node name to avoid conflicts (by using `rosrun rosserial_python serial_node.py tcp __name:=OtherNodeName`), I get an error `"socket.error: [Errno 98] Address already in use"`.
As the socket can't be given as an argument to serial_node.py, I tried using `rosrun rosserial_server socket_node` as rosserial_server in theory can handle multiple connections. Using default port 11411, I find the node displays:
`Listening for rosserial TCP connection on port 11411`
but never finds any devices, unlike rosserial_python serial_node.py which was successful.
Am I missing something for rosserial_server to be able to identify and connect to these devices?
Is there another way of connecting multiple TCP devices such as these arduinos with wifi simultaneously?
Thank you for your time,
Andy
Below is the code on the arduino for anyone who is interested:
#include
#include
#include
#include
//////////////////////
// WiFi Definitions //
//////////////////////
const char* ssid = SECRET_SSID;
const char* password = SECRET_PASS;
IPAddress server(192, 168, 0, 100); // ip of your ROS server
IPAddress ip; //Storage local 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 nh;
std_msgs::String msg;
ros::Publisher string("outString", &msg);
char hello[13] = "Hello World!";
void setupWiFi()
{
WiFi.begin(ssid, password);
//Print to serial to find out IP address and debugging
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 ");
ip = WiFi.localIP();
Serial.print(ip);
Serial.println(" to access client");
}
void setup() {
//Configure pins for adafruit ATWINC1500 breakout
WiFi.setPins(8,7,4);
Serial.begin(9600);
setupWiFi();
delay(2000);
nh.initNode();
nh.advertise(string);
}
void loop() {
msg.data = hello;
string.publish(&msg);
nh.spinOnce();
delay(1000);
}
**Actually a Teensy 3.2 because the Uno does not have enough memory, however it emulates and behaves like an Uno*
↧