Skip to content

Commit

Permalink
Fixing formatting on files.
Browse files Browse the repository at this point in the history
find -regextype egrep -regex '.*\.[ch](pp)?$' -exec astyle '{}' --style=allman --indent=spaces=2 --pad-oper --unpad-paren --pad-header --convert-tabs \;
  • Loading branch information
Mike O'Driscoll committed Nov 9, 2017
1 parent d7e08ea commit a163701
Show file tree
Hide file tree
Showing 75 changed files with 3,344 additions and 2,885 deletions.
129 changes: 72 additions & 57 deletions rosserial_arduino/src/ros_lib/ArduinoHardware.h
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
/*
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2011, Willow Garage, Inc.
Expand Down Expand Up @@ -36,80 +36,95 @@
#define ROS_ARDUINO_HARDWARE_H_

#if ARDUINO>=100
#include <Arduino.h> // Arduino 1.0
#include <Arduino.h> // Arduino 1.0
#else
#include <WProgram.h> // Arduino 0022
#include <WProgram.h> // Arduino 0022
#endif

#if defined(__MK20DX128__) || defined(__MK20DX256__) || defined(__MK64FX512__) || defined(__MK66FX1M0__) || defined(__MKL26Z64__)
#if defined(USE_TEENSY_HW_SERIAL)
#define SERIAL_CLASS HardwareSerial // Teensy HW Serial
#else
#include <usb_serial.h> // Teensy 3.0 and 3.1
#define SERIAL_CLASS usb_serial_class
#endif
#if defined(USE_TEENSY_HW_SERIAL)
#define SERIAL_CLASS HardwareSerial // Teensy HW Serial
#else
#include <usb_serial.h> // Teensy 3.0 and 3.1
#define SERIAL_CLASS usb_serial_class
#endif
#elif defined(_SAM3XA_)
#include <UARTClass.h> // Arduino Due
#define SERIAL_CLASS UARTClass
#include <UARTClass.h> // Arduino Due
#define SERIAL_CLASS UARTClass
#elif defined(USE_USBCON)
// Arduino Leonardo USB Serial Port
#define SERIAL_CLASS Serial_
#elif (defined(__STM32F1__) and !(defined(USE_STM32_HW_SERIAL))) or defined(SPARK)
// Stm32duino Maple mini USB Serial Port
#define SERIAL_CLASS USBSerial
#else
#include <HardwareSerial.h> // Arduino AVR
#define SERIAL_CLASS HardwareSerial
// Arduino Leonardo USB Serial Port
#define SERIAL_CLASS Serial_
#elif (defined(__STM32F1__) and !(defined(USE_STM32_HW_SERIAL))) or defined(SPARK)
// Stm32duino Maple mini USB Serial Port
#define SERIAL_CLASS USBSerial
#else
#include <HardwareSerial.h> // Arduino AVR
#define SERIAL_CLASS HardwareSerial
#endif

class ArduinoHardware {
public:
ArduinoHardware(SERIAL_CLASS* io , long baud= 57600){
iostream = io;
baud_ = baud;
}
ArduinoHardware()
{
class ArduinoHardware
{
public:
ArduinoHardware(SERIAL_CLASS* io , long baud = 57600)
{
iostream = io;
baud_ = baud;
}
ArduinoHardware()
{
#if defined(USBCON) and !(defined(USE_USBCON))
/* Leonardo support */
iostream = &Serial1;
/* Leonardo support */
iostream = &Serial1;
#elif defined(USE_TEENSY_HW_SERIAL) or defined(USE_STM32_HW_SERIAL)
iostream = &Serial1;
iostream = &Serial1;
#else
iostream = &Serial;
iostream = &Serial;
#endif
baud_ = 57600;
}
ArduinoHardware(ArduinoHardware& h){
this->iostream = h.iostream;
this->baud_ = h.baud_;
}

void setBaud(long baud){
this->baud_= baud;
}

int getBaud(){return baud_;}
baud_ = 57600;
}
ArduinoHardware(ArduinoHardware& h)
{
this->iostream = h.iostream;
this->baud_ = h.baud_;
}

void setBaud(long baud)
{
this->baud_ = baud;
}

int getBaud()
{
return baud_;
}

void init(){
void init()
{
#if defined(USE_USBCON)
// Startup delay as a fail-safe to upload a new sketch
delay(3000);
// Startup delay as a fail-safe to upload a new sketch
delay(3000);
#endif
iostream->begin(baud_);
}
iostream->begin(baud_);
}

int read(){return iostream->read();};
void write(uint8_t* data, int length){
for(int i=0; i<length; i++)
iostream->write(data[i]);
}
int read()
{
return iostream->read();
};
void write(uint8_t* data, int length)
{
for (int i = 0; i < length; i++)
iostream->write(data[i]);
}

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

protected:
SERIAL_CLASS* iostream;
long baud_;
protected:
SERIAL_CLASS* iostream;
long baud_;
};

#endif
14 changes: 8 additions & 6 deletions rosserial_arduino/src/ros_lib/ArduinoTcpHardware.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,13 +37,14 @@

#include <Arduino.h>
#if defined(ESP8266)
#include <ESP8266WiFi.h>
#include <ESP8266WiFi.h>
#else
#include <SPI.h>
#include <Ethernet.h>
#include <SPI.h>
#include <Ethernet.h>
#endif

class ArduinoHardware {
class ArduinoHardware
{
public:
ArduinoHardware()
{
Expand All @@ -69,10 +70,11 @@ class ArduinoHardware {
tcp_.connect(server_, serverPort_);
}

int read(){
int read()
{
if (tcp_.connected())
{
return tcp_.read();
return tcp_.read();
}
else
{
Expand Down
Loading

0 comments on commit a163701

Please sign in to comment.