Skip to content

Commit 12d1951

Browse files
author
josh
committed
Updated to ROS Serial version 0.9.1
1 parent eb59e10 commit 12d1951

File tree

248 files changed

+2533
-5908
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

248 files changed

+2533
-5908
lines changed

examples/Blink/Blink.pde

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -9,14 +9,14 @@
99
ros::NodeHandle nh;
1010

1111
void messageCb( const std_msgs::Empty& toggle_msg){
12-
digitalWrite(13, HIGH-digitalRead(13)); // blink the led
12+
digitalWrite(LED_BUILTIN, HIGH-digitalRead(LED_BUILTIN)); // blink the led
1313
}
1414

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

1717
void setup()
1818
{
19-
pinMode(13, OUTPUT);
19+
pinMode(LED_BUILTIN, OUTPUT);
2020
nh.initNode();
2121
nh.subscribe(sub);
2222
}
Lines changed: 70 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,70 @@
1+
#include <ros.h>
2+
#include <std_srvs/SetBool.h>
3+
#include <std_msgs/UInt16.h>
4+
5+
ros::NodeHandle nh;
6+
7+
class Blinker
8+
{
9+
public:
10+
Blinker(byte pin, uint16_t period)
11+
: pin_(pin), period_(period),
12+
subscriber_("set_blink_period", &Blinker::set_period_callback, this),
13+
service_server_("activate_blinker", &Blinker::service_callback, this)
14+
{}
15+
16+
void init(ros::NodeHandle& nh)
17+
{
18+
pinMode(pin_, OUTPUT);
19+
nh.subscribe(subscriber_);
20+
nh.advertiseService(service_server_);
21+
}
22+
23+
void run()
24+
{
25+
if(active_ && ((millis() - last_time_) >= period_))
26+
{
27+
last_time_ = millis();
28+
digitalWrite(pin_, !digitalRead(pin_));
29+
}
30+
}
31+
32+
void set_period_callback(const std_msgs::UInt16& msg)
33+
{
34+
period_ = msg.data;
35+
}
36+
37+
void service_callback(const std_srvs::SetBool::Request& req,
38+
std_srvs::SetBool::Response& res)
39+
{
40+
active_ = req.data;
41+
res.success = true;
42+
if(req.data)
43+
res.message = "Blinker ON";
44+
else
45+
res.message = "Blinker OFF";
46+
}
47+
48+
private:
49+
const byte pin_;
50+
bool active_ = true;
51+
uint16_t period_;
52+
uint32_t last_time_;
53+
ros::Subscriber<std_msgs::UInt16, Blinker> subscriber_;
54+
ros::ServiceServer<std_srvs::SetBool::Request, std_srvs::SetBool::Response, Blinker> service_server_;
55+
};
56+
57+
Blinker blinker(LED_BUILTIN, 500);
58+
59+
void setup()
60+
{
61+
nh.initNode();
62+
blinker.init(nh);
63+
}
64+
65+
void loop()
66+
{
67+
blinker.run();
68+
nh.spinOnce();
69+
delay(1);
70+
}

src/examples/Esp8266/HelloWorld.ino renamed to examples/Esp8266HelloWorld/Esp8266HelloWorld.ino

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,9 @@
11
/*
22
* rosserial Publisher Example
33
* Prints "hello world!"
4-
* This intend to connect to a Wifi Access Point
4+
* This intend to connect to a Wifi Access Point
55
* and a rosserial socket server.
6-
* You can launch the rosserial socket server with
6+
* You can launch the rosserial socket server with
77
* roslaunch rosserial_server socket.launch
88
* The default port is 11411
99
*

examples/ServiceClient/client.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
#!/usr/bin/env python
22

3-
"""
3+
"""
44
Sample code to use with ServiceClient.pde
55
"""
66

@@ -10,7 +10,7 @@
1010
from rosserial_arduino.srv import *
1111

1212
def callback(req):
13-
print "The arduino is calling! Please send it a message:"
13+
print("The arduino is calling! Please send it a message:")
1414
t = TestResponse()
1515
t.output = raw_input()
1616
return t

examples/TcpBlink/TcpBlink.ino

Lines changed: 47 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,47 @@
1+
/*
2+
* rosserial Subscriber Example using TCP on Arduino Shield (Wiznet W5100 based)
3+
* Blinks an LED on callback
4+
*/
5+
#include <SPI.h>
6+
#include <Ethernet.h>
7+
8+
#define ROSSERIAL_ARDUINO_TCP
9+
10+
#include <ros.h>
11+
#include <std_msgs/Empty.h>
12+
13+
ros::NodeHandle nh;
14+
15+
// Shield settings
16+
byte mac[] = { 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xED };
17+
IPAddress ip(192, 168, 0, 177);
18+
19+
// Server settings
20+
IPAddress server(192, 168, 0, 11);
21+
uint16_t serverPort = 11411;
22+
23+
const uint8_t ledPin = 6; // 13 already used for SPI connection with the shield
24+
25+
void messageCb( const std_msgs::Empty&){
26+
digitalWrite(ledPin, HIGH-digitalRead(ledPin)); // blink the led
27+
}
28+
29+
ros::Subscriber<std_msgs::Empty> sub("toggle_led", &messageCb );
30+
31+
void setup()
32+
{
33+
Ethernet.begin(mac, ip);
34+
// give the Ethernet shield a second to initialize:
35+
delay(1000);
36+
pinMode(ledPin, OUTPUT);
37+
nh.getHardware()->setConnection(server, serverPort);
38+
nh.initNode();
39+
nh.subscribe(sub);
40+
}
41+
42+
void loop()
43+
{
44+
nh.spinOnce();
45+
delay(1);
46+
}
47+
Lines changed: 84 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,84 @@
1+
/*
2+
* rosserial Publisher Example
3+
* Prints "hello world!"
4+
* This intend to connect to an Arduino Ethernet Shield
5+
* and a rosserial socket server.
6+
* You can launch the rosserial socket server with
7+
* roslaunch rosserial_server socket.launch
8+
* The default port is 11411
9+
*
10+
*/
11+
#include <SPI.h>
12+
#include <Ethernet.h>
13+
14+
// To use the TCP version of rosserial_arduino
15+
#define ROSSERIAL_ARDUINO_TCP
16+
17+
#include <ros.h>
18+
#include <std_msgs/String.h>
19+
20+
// Set the shield settings
21+
byte mac[] = { 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xED };
22+
IPAddress ip(192, 168, 0, 177);
23+
24+
// Set the rosserial socket server IP address
25+
IPAddress server(192,168,0,11);
26+
// Set the rosserial socket server port
27+
const uint16_t serverPort = 11411;
28+
29+
ros::NodeHandle nh;
30+
// Make a chatter publisher
31+
std_msgs::String str_msg;
32+
ros::Publisher chatter("chatter", &str_msg);
33+
34+
// Be polite and say hello
35+
char hello[13] = "hello world!";
36+
uint16_t period = 1000;
37+
uint32_t last_time = 0;
38+
39+
void setup()
40+
{
41+
// Use serial to monitor the process
42+
Serial.begin(115200);
43+
44+
// Connect the Ethernet
45+
Ethernet.begin(mac, ip);
46+
47+
// Let some time for the Ethernet Shield to be initialized
48+
delay(1000);
49+
50+
Serial.println("");
51+
Serial.println("Ethernet connected");
52+
Serial.println("IP address: ");
53+
Serial.println(Ethernet.localIP());
54+
55+
// Set the connection to rosserial socket server
56+
nh.getHardware()->setConnection(server, serverPort);
57+
nh.initNode();
58+
59+
// Another way to get IP
60+
Serial.print("IP = ");
61+
Serial.println(nh.getHardware()->getLocalIP());
62+
63+
// Start to be polite
64+
nh.advertise(chatter);
65+
}
66+
67+
void loop()
68+
{
69+
if(millis() - last_time >= period)
70+
{
71+
last_time = millis();
72+
if (nh.connected())
73+
{
74+
Serial.println("Connected");
75+
// Say hello
76+
str_msg.data = hello;
77+
chatter.publish( &str_msg );
78+
} else {
79+
Serial.println("Not Connected");
80+
}
81+
}
82+
nh.spinOnce();
83+
delay(1);
84+
}

library.properties

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
name=Rosserial Arduino Library
2-
version=0.7.9
2+
version=0.9.1
33
author=Michael Ferguson <mfergs7@gmail.com>
44
maintainer=Joshua Frank <frankjoshua@gmail.com>
55
sentence=Use an Arduino as a ROS publisher/subscriber

src/ArduinoHardware.h

Lines changed: 31 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,32 @@
3535
#ifndef ROS_ARDUINO_HARDWARE_H_
3636
#define ROS_ARDUINO_HARDWARE_H_
3737

38-
#include "ArduinoIncludes.h"
38+
#if ARDUINO>=100
39+
#include <Arduino.h> // Arduino 1.0
40+
#else
41+
#include <WProgram.h> // Arduino 0022
42+
#endif
43+
44+
#if defined(__MK20DX128__) || defined(__MK20DX256__) || defined(__MK64FX512__) || defined(__MK66FX1M0__) || defined(__MKL26Z64__) || defined(__IMXRT1062__)
45+
#if defined(USE_TEENSY_HW_SERIAL)
46+
#define SERIAL_CLASS HardwareSerial // Teensy HW Serial
47+
#else
48+
#include <usb_serial.h> // Teensy 3.0 and 3.1
49+
#define SERIAL_CLASS usb_serial_class
50+
#endif
51+
#elif defined(_SAM3XA_)
52+
#include <UARTClass.h> // Arduino Due
53+
#define SERIAL_CLASS UARTClass
54+
#elif defined(USE_USBCON)
55+
// Arduino Leonardo USB Serial Port
56+
#define SERIAL_CLASS Serial_
57+
#elif (defined(__STM32F1__) and !(defined(USE_STM32_HW_SERIAL))) or defined(SPARK)
58+
// Stm32duino Maple mini USB Serial Port
59+
#define SERIAL_CLASS USBSerial
60+
#else
61+
#include <HardwareSerial.h> // Arduino AVR
62+
#define SERIAL_CLASS HardwareSerial
63+
#endif
3964

4065
class ArduinoHardware {
4166
public:
@@ -59,6 +84,10 @@ class ArduinoHardware {
5984
this->iostream = h.iostream;
6085
this->baud_ = h.baud_;
6186
}
87+
88+
void setPort(SERIAL_CLASS* io){
89+
this->iostream = io;
90+
}
6291

6392
void setBaud(long baud){
6493
this->baud_= baud;
@@ -76,8 +105,7 @@ class ArduinoHardware {
76105

77106
int read(){return iostream->read();};
78107
void write(uint8_t* data, int length){
79-
for(int i=0; i<length; i++)
80-
iostream->write(data[i]);
108+
iostream->write(data, length);
81109
}
82110

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

0 commit comments

Comments
 (0)