Arduino 1.0 - changed all #includes of "WProgram.h", "wiring.h" and "WConstants.h to "Arduino.h".
Modified FastSerial's write function to return size_t (number of bytes written).
This commit is contained in:
parent
f3a95ff3cb
commit
ed19c25a97
@ -21,7 +21,11 @@
|
|||||||
#include "APM_RC_APM1.h"
|
#include "APM_RC_APM1.h"
|
||||||
|
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
#include "WProgram.h"
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__)
|
#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__)
|
||||||
# error Please check the Tools/Board menu to ensure you have selected Arduino Mega as your target.
|
# error Please check the Tools/Board menu to ensure you have selected Arduino Mega as your target.
|
||||||
|
@ -20,7 +20,11 @@
|
|||||||
*/
|
*/
|
||||||
#include "APM_RC_APM2.h"
|
#include "APM_RC_APM2.h"
|
||||||
|
|
||||||
#include "WProgram.h"
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__)
|
#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__)
|
||||||
# error Please check the Tools/Board menu to ensure you have selected Arduino Mega as your target.
|
# error Please check the Tools/Board menu to ensure you have selected Arduino Mega as your target.
|
||||||
|
@ -44,15 +44,19 @@
|
|||||||
Channel 7 : Differential pressure sensor port
|
Channel 7 : Differential pressure sensor port
|
||||||
|
|
||||||
*/
|
*/
|
||||||
|
#include "AP_ADC_ADS7844.h"
|
||||||
|
|
||||||
extern "C" {
|
extern "C" {
|
||||||
// AVR LibC Includes
|
// AVR LibC Includes
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
#include "WConstants.h"
|
|
||||||
}
|
}
|
||||||
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
#include "AP_ADC_ADS7844.h"
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WConstants.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
// Commands for reading ADC channels on ADS7844
|
// Commands for reading ADC channels on ADS7844
|
||||||
static const unsigned char adc_cmd[9] = { 0x87, 0xC7, 0x97, 0xD7, 0xA7, 0xE7, 0xB7, 0xF7, 0x00 };
|
static const unsigned char adc_cmd[9] = { 0x87, 0xC7, 0x97, 0xD7, 0xA7, 0xE7, 0xB7, 0xF7, 0x00 };
|
||||||
|
@ -1,5 +1,9 @@
|
|||||||
#include "AP_ADC_HIL.h"
|
#include "AP_ADC_HIL.h"
|
||||||
#include "WProgram.h"
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
AP_ADC_HIL.cpp
|
AP_ADC_HIL.cpp
|
||||||
|
@ -1,6 +1,10 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
|
||||||
#include "wiring.h"
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "wiring.h"
|
||||||
|
#endif
|
||||||
#include "AP_AnalogSource_Arduino.h"
|
#include "AP_AnalogSource_Arduino.h"
|
||||||
|
|
||||||
float AP_AnalogSource_Arduino::read(void)
|
float AP_AnalogSource_Arduino::read(void)
|
||||||
|
@ -39,8 +39,12 @@ extern "C" {
|
|||||||
// AVR LibC Includes
|
// AVR LibC Includes
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
#include "WConstants.h"
|
|
||||||
}
|
}
|
||||||
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WConstants.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
|
@ -4,8 +4,12 @@ extern "C" {
|
|||||||
// AVR LibC Includes
|
// AVR LibC Includes
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
#include "WConstants.h"
|
|
||||||
}
|
}
|
||||||
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WConstants.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "AP_Baro_BMP085_hil.h"
|
#include "AP_Baro_BMP085_hil.h"
|
||||||
|
|
||||||
|
@ -16,7 +16,11 @@
|
|||||||
#define _AP_COMMON_H
|
#define _AP_COMMON_H
|
||||||
|
|
||||||
// Get the common arduino functions
|
// Get the common arduino functions
|
||||||
#include "wiring.h"
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "wiring.h"
|
||||||
|
#endif
|
||||||
// ... and remove some of their stupid macros
|
// ... and remove some of their stupid macros
|
||||||
#undef round
|
#undef round
|
||||||
#undef abs
|
#undef abs
|
||||||
|
@ -22,7 +22,11 @@
|
|||||||
#include "../FastSerial/BetterStream.h"
|
#include "../FastSerial/BetterStream.h"
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include <WProgram.h>
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include <WProgram.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef ASSERT
|
#ifdef ASSERT
|
||||||
const static char vectorSource[] ="Vector.hpp";
|
const static char vectorSource[] ="Vector.hpp";
|
||||||
|
@ -9,7 +9,11 @@
|
|||||||
|
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include "c++.h"
|
#include "c++.h"
|
||||||
#include "WProgram.h"
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
void * operator new(size_t size)
|
void * operator new(size_t size)
|
||||||
{
|
{
|
||||||
|
@ -15,8 +15,12 @@
|
|||||||
|
|
||||||
// AVR LibC Includes
|
// AVR LibC Includes
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
#include "WConstants.h"
|
|
||||||
#include <FastSerial.h>
|
#include <FastSerial.h>
|
||||||
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WConstants.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
#include <I2C.h>
|
#include <I2C.h>
|
||||||
#include "AP_Compass_HMC5843.h"
|
#include "AP_Compass_HMC5843.h"
|
||||||
|
@ -10,12 +10,15 @@
|
|||||||
#include "../FastSerial/FastSerial.h"
|
#include "../FastSerial/FastSerial.h"
|
||||||
#include "../AP_Math/AP_Math.h"
|
#include "../AP_Math/AP_Math.h"
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include "WProgram.h"
|
|
||||||
#include "../AP_Compass/AP_Compass.h"
|
#include "../AP_Compass/AP_Compass.h"
|
||||||
#include "../AP_ADC/AP_ADC.h"
|
#include "../AP_ADC/AP_ADC.h"
|
||||||
#include "../AP_GPS/AP_GPS.h"
|
#include "../AP_GPS/AP_GPS.h"
|
||||||
#include "../AP_IMU/AP_IMU.h"
|
#include "../AP_IMU/AP_IMU.h"
|
||||||
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
class AP_DCM
|
class AP_DCM
|
||||||
{
|
{
|
||||||
|
@ -4,11 +4,15 @@
|
|||||||
#include "../FastSerial/FastSerial.h"
|
#include "../FastSerial/FastSerial.h"
|
||||||
#include "../AP_Math/AP_Math.h"
|
#include "../AP_Math/AP_Math.h"
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include "WProgram.h"
|
|
||||||
#include "../AP_Compass/AP_Compass.h"
|
#include "../AP_Compass/AP_Compass.h"
|
||||||
#include "../AP_ADC/AP_ADC.h"
|
#include "../AP_ADC/AP_ADC.h"
|
||||||
#include "../AP_GPS/AP_GPS.h"
|
#include "../AP_GPS/AP_GPS.h"
|
||||||
#include "../AP_IMU/AP_IMU.h"
|
#include "../AP_IMU/AP_IMU.h"
|
||||||
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
class AP_DCM_HIL
|
class AP_DCM_HIL
|
||||||
|
@ -6,8 +6,11 @@
|
|||||||
#ifndef AP_EEPROMB_h
|
#ifndef AP_EEPROMB_h
|
||||||
#define AP_EEPROMB_h
|
#define AP_EEPROMB_h
|
||||||
|
|
||||||
//#include <stdint.h>
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
#include "WProgram.h"
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
/// @class AP_EEPROMB
|
/// @class AP_EEPROMB
|
||||||
/// @brief Object for reading and writing to the EEPROM
|
/// @brief Object for reading and writing to the EEPROM
|
||||||
|
@ -11,7 +11,11 @@
|
|||||||
|
|
||||||
#include "../FastSerial/FastSerial.h" // because we need to change baud rates... ugh.
|
#include "../FastSerial/FastSerial.h" // because we need to change baud rates... ugh.
|
||||||
#include "AP_GPS_406.h"
|
#include "AP_GPS_406.h"
|
||||||
#include "WProgram.h"
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
static const char init_str[] = "$PSRF100,0,57600,8,1,0*37";
|
static const char init_str[] = "$PSRF100,0,57600,8,1,0*37";
|
||||||
|
|
||||||
|
@ -12,7 +12,11 @@
|
|||||||
//
|
//
|
||||||
|
|
||||||
#include "AP_GPS_HIL.h"
|
#include "AP_GPS_HIL.h"
|
||||||
#include "WProgram.h"
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
// Constructors ////////////////////////////////////////////////////////////////
|
// Constructors ////////////////////////////////////////////////////////////////
|
||||||
AP_GPS_HIL::AP_GPS_HIL(Stream *s) : GPS(s)
|
AP_GPS_HIL::AP_GPS_HIL(Stream *s) : GPS(s)
|
||||||
|
@ -28,7 +28,11 @@
|
|||||||
|
|
||||||
*/
|
*/
|
||||||
#include "AP_GPS_IMU.h"
|
#include "AP_GPS_IMU.h"
|
||||||
#include "WProgram.h"
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
// Constructors ////////////////////////////////////////////////////////////////
|
// Constructors ////////////////////////////////////////////////////////////////
|
||||||
|
@ -13,7 +13,11 @@
|
|||||||
|
|
||||||
#include "AP_GPS_MTK16.h"
|
#include "AP_GPS_MTK16.h"
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <wiring.h>
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include <wiring.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
// Constructors ////////////////////////////////////////////////////////////////
|
// Constructors ////////////////////////////////////////////////////////////////
|
||||||
AP_GPS_MTK16::AP_GPS_MTK16(Stream *s) : GPS(s)
|
AP_GPS_MTK16::AP_GPS_MTK16(Stream *s) : GPS(s)
|
||||||
|
@ -1,7 +1,11 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||||
|
|
||||||
#include "GPS.h"
|
#include "GPS.h"
|
||||||
#include "WProgram.h"
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
void
|
void
|
||||||
GPS::update(void)
|
GPS::update(void)
|
||||||
|
@ -3,8 +3,12 @@
|
|||||||
|
|
||||||
#include "AP_InertialSensor_MPU6000.h"
|
#include "AP_InertialSensor_MPU6000.h"
|
||||||
|
|
||||||
#include <wiring.h>
|
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include <wiring.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
// MPU 6000 registers
|
// MPU 6000 registers
|
||||||
#define MPUREG_WHOAMI 0x75 //
|
#define MPUREG_WHOAMI 0x75 //
|
||||||
|
@ -6,7 +6,11 @@
|
|||||||
#define XTRACK_ENTRY_ANGLE 3000 // Max angle used to correct for track following degrees*100
|
#define XTRACK_ENTRY_ANGLE 3000 // Max angle used to correct for track following degrees*100
|
||||||
#include <GPS.h> // ArduPilot GPS Library
|
#include <GPS.h> // ArduPilot GPS Library
|
||||||
#include "Waypoints.h" // ArduPilot Waypoints Library
|
#include "Waypoints.h" // ArduPilot Waypoints Library
|
||||||
#include "WProgram.h"
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
#define T7 10000000
|
#define T7 10000000
|
||||||
|
|
||||||
|
@ -24,8 +24,12 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include "AP_OpticalFlow_ADNS3080.h"
|
#include "AP_OpticalFlow_ADNS3080.h"
|
||||||
#include "WProgram.h"
|
|
||||||
#include "SPI.h"
|
#include "SPI.h"
|
||||||
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
#define AP_SPI_TIMEOUT 1000
|
#define AP_SPI_TIMEOUT 1000
|
||||||
|
|
||||||
|
@ -5,9 +5,13 @@
|
|||||||
extern "C" {
|
extern "C" {
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include "WConstants.h"
|
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
}
|
}
|
||||||
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WConstants.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
uint8_t AP_TimerProcess::_period;
|
uint8_t AP_TimerProcess::_period;
|
||||||
ap_procedure AP_TimerProcess::_proc[AP_TIMERPROCESS_MAX_PROCS];
|
ap_procedure AP_TimerProcess::_proc[AP_TIMERPROCESS_MAX_PROCS];
|
||||||
|
@ -10,8 +10,12 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include "AP_RC.h"
|
#include "AP_RC.h"
|
||||||
#include "WProgram.h"
|
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
// Variable definition for interrupt
|
// Variable definition for interrupt
|
||||||
volatile uint16_t timer1count = 0;
|
volatile uint16_t timer1count = 0;
|
||||||
|
@ -11,7 +11,11 @@
|
|||||||
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
#include <avr/eeprom.h>
|
#include <avr/eeprom.h>
|
||||||
#include "WProgram.h"
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
#include "AP_RC_Channel.h"
|
#include "AP_RC_Channel.h"
|
||||||
|
|
||||||
#define ANGLE 0
|
#define ANGLE 0
|
||||||
|
@ -26,7 +26,11 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
// AVR LibC Includes
|
// AVR LibC Includes
|
||||||
#include "WConstants.h"
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WConstants.h"
|
||||||
|
#endif
|
||||||
#include "AP_RangeFinder_MaxsonarXL.h"
|
#include "AP_RangeFinder_MaxsonarXL.h"
|
||||||
|
|
||||||
// Constructor //////////////////////////////////////////////////////////////
|
// Constructor //////////////////////////////////////////////////////////////
|
||||||
|
@ -26,7 +26,11 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
// AVR LibC Includes
|
// AVR LibC Includes
|
||||||
#include "WConstants.h"
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WConstants.h"
|
||||||
|
#endif
|
||||||
#include "AP_RangeFinder_SharpGP2Y.h"
|
#include "AP_RangeFinder_SharpGP2Y.h"
|
||||||
|
|
||||||
// Constructor //////////////////////////////////////////////////////////////
|
// Constructor //////////////////////////////////////////////////////////////
|
||||||
|
@ -13,7 +13,11 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
// AVR LibC Includes
|
// AVR LibC Includes
|
||||||
#include "WConstants.h"
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WConstants.h"
|
||||||
|
#endif
|
||||||
#include "RangeFinder.h"
|
#include "RangeFinder.h"
|
||||||
|
|
||||||
|
|
||||||
|
@ -8,7 +8,11 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
#include "wiring.h"
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "wiring.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "AP_Relay.h"
|
#include "AP_Relay.h"
|
||||||
|
|
||||||
|
@ -36,8 +36,12 @@ extern "C" {
|
|||||||
// AVR LibC Includes
|
// AVR LibC Includes
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
#include "WConstants.h"
|
|
||||||
}
|
}
|
||||||
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WConstants.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "DataFlash_APM2.h"
|
#include "DataFlash_APM2.h"
|
||||||
|
|
||||||
|
@ -31,7 +31,12 @@
|
|||||||
|
|
||||||
//#include "../AP_Common/AP_Common.h"
|
//#include "../AP_Common/AP_Common.h"
|
||||||
#include "FastSerial.h"
|
#include "FastSerial.h"
|
||||||
#include "WProgram.h"
|
|
||||||
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
#if defined(UDR3)
|
#if defined(UDR3)
|
||||||
# define FS_MAX_PORTS 4
|
# define FS_MAX_PORTS 4
|
||||||
@ -197,6 +202,30 @@ void FastSerial::flush(void)
|
|||||||
_txBuffer->tail = _txBuffer->head;
|
_txBuffer->tail = _txBuffer->head;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
size_t FastSerial::write(uint8_t c)
|
||||||
|
{
|
||||||
|
uint16_t i;
|
||||||
|
|
||||||
|
if (!_open) // drop bytes if not open
|
||||||
|
return 0;
|
||||||
|
|
||||||
|
// wait for room in the tx buffer
|
||||||
|
i = (_txBuffer->head + 1) & _txBuffer->mask;
|
||||||
|
while (i == _txBuffer->tail)
|
||||||
|
;
|
||||||
|
|
||||||
|
// add byte to the buffer
|
||||||
|
_txBuffer->bytes[_txBuffer->head] = c;
|
||||||
|
_txBuffer->head = i;
|
||||||
|
|
||||||
|
// enable the data-ready interrupt, as it may be off if the buffer is empty
|
||||||
|
*_ucsrb |= _portTxBits;
|
||||||
|
|
||||||
|
// return number of bytes written (always 1)
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
#else
|
||||||
void FastSerial::write(uint8_t c)
|
void FastSerial::write(uint8_t c)
|
||||||
{
|
{
|
||||||
uint16_t i;
|
uint16_t i;
|
||||||
@ -216,6 +245,7 @@ void FastSerial::write(uint8_t c)
|
|||||||
// enable the data-ready interrupt, as it may be off if the buffer is empty
|
// enable the data-ready interrupt, as it may be off if the buffer is empty
|
||||||
*_ucsrb |= _portTxBits;
|
*_ucsrb |= _portTxBits;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// Buffer management ///////////////////////////////////////////////////////////
|
// Buffer management ///////////////////////////////////////////////////////////
|
||||||
|
|
||||||
|
@ -116,7 +116,11 @@ public:
|
|||||||
virtual int read(void);
|
virtual int read(void);
|
||||||
virtual int peek(void);
|
virtual int peek(void);
|
||||||
virtual void flush(void);
|
virtual void flush(void);
|
||||||
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
virtual size_t write(uint8_t c);
|
||||||
|
#else
|
||||||
virtual void write(uint8_t c);
|
virtual void write(uint8_t c);
|
||||||
|
#endif
|
||||||
using BetterStream::write;
|
using BetterStream::write;
|
||||||
//@}
|
//@}
|
||||||
|
|
||||||
|
@ -31,9 +31,13 @@
|
|||||||
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "WProgram.h"
|
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include "I2C.h"
|
#include "I2C.h"
|
||||||
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -31,8 +31,12 @@
|
|||||||
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "WProgram.h"
|
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef I2C_h
|
#ifndef I2C_h
|
||||||
#define I2C_h
|
#define I2C_h
|
||||||
|
@ -14,7 +14,11 @@
|
|||||||
#include "ModeFilter.h"
|
#include "ModeFilter.h"
|
||||||
|
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
#include "WProgram.h"
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
// Constructors ////////////////////////////////////////////////////////////////
|
// Constructors ////////////////////////////////////////////////////////////////
|
||||||
|
@ -11,7 +11,11 @@
|
|||||||
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
#include <avr/eeprom.h>
|
#include <avr/eeprom.h>
|
||||||
#include "WProgram.h"
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
#include "RC_Channel.h"
|
#include "RC_Channel.h"
|
||||||
|
|
||||||
#define RC_CHANNEL_ANGLE 0
|
#define RC_CHANNEL_ANGLE 0
|
||||||
|
@ -2,8 +2,12 @@
|
|||||||
#define Waypoints_h
|
#define Waypoints_h
|
||||||
|
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include "WProgram.h"
|
|
||||||
#include <avr/eeprom.h>
|
#include <avr/eeprom.h>
|
||||||
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
class Waypoints
|
class Waypoints
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user