AP_HAL: global rename PPMInput -> RCInput, PWMOutput -> RCOutput

* for clarity. nobody cares that PPM/PWM is the implementation, and with
  sbus etc it might not be
This commit is contained in:
Pat Hickey 2012-08-27 11:44:50 -07:00 committed by Andrew Tridgell
parent 46f31aa69c
commit db76562cd5
14 changed files with 110 additions and 109 deletions

View File

@ -13,8 +13,8 @@
#include "Log.h" #include "Log.h"
#include "Console.h" #include "Console.h"
#include "GPIO.h" #include "GPIO.h"
#include "PPMInput.h" #include "RCInput.h"
#include "PWMOutput.h" #include "RCOutput.h"
#include "Scheduler.h" #include "Scheduler.h"
#include "utility/Print.h" #include "utility/Print.h"

View File

@ -16,8 +16,8 @@ namespace AP_HAL {
class Log; class Log;
class Console; class Console;
class GPIO; class GPIO;
class PPMInput; class RCInput;
class PWMOutput; class RCOutput;
class Scheduler; class Scheduler;
class EmptyUARTDriver; class EmptyUARTDriver;

View File

@ -11,8 +11,8 @@
#include "../AP_HAL/Log.h" #include "../AP_HAL/Log.h"
#include "../AP_HAL/Console.h" #include "../AP_HAL/Console.h"
#include "../AP_HAL/GPIO.h" #include "../AP_HAL/GPIO.h"
#include "../AP_HAL/PPMInput.h" #include "../AP_HAL/RCInput.h"
#include "../AP_HAL/PWMOutput.h" #include "../AP_HAL/RCOutput.h"
class AP_HAL::HAL { class AP_HAL::HAL {
public: public:
@ -27,8 +27,8 @@ public:
AP_HAL::Log* _log, AP_HAL::Log* _log,
AP_HAL::Console* _console, AP_HAL::Console* _console,
AP_HAL::GPIO* _gpio, AP_HAL::GPIO* _gpio,
AP_HAL::PPMInput* _ppmin, AP_HAL::RCInput* _rcin,
AP_HAL::PWMOutput* _pwmout, AP_HAL::RCOutput* _rcout,
AP_HAL::Scheduler* _scheduler) AP_HAL::Scheduler* _scheduler)
: :
uart0(_uart0), uart0(_uart0),
@ -42,8 +42,8 @@ public:
log(_log), log(_log),
console(_console), console(_console),
gpio(_gpio), gpio(_gpio),
ppmin(_ppmin), rcin(_rcin),
pwmout(_pwmout), rcout(_rcout),
scheduler(_scheduler) scheduler(_scheduler)
{} {}
@ -60,8 +60,8 @@ public:
AP_HAL::Log* log; AP_HAL::Log* log;
AP_HAL::Console* console; AP_HAL::Console* console;
AP_HAL::GPIO* gpio; AP_HAL::GPIO* gpio;
AP_HAL::PPMInput* ppmin; AP_HAL::RCInput* rcin;
AP_HAL::PWMOutput* pwmout; AP_HAL::RCOutput* rcout;
AP_HAL::Scheduler* scheduler; AP_HAL::Scheduler* scheduler;
}; };

View File

@ -1,14 +0,0 @@
#ifndef __AP_HAL_PPM_INPUT_H__
#define __AP_HAL_PPM_INPUT_H__
#include "AP_HAL_Namespace.h"
class AP_HAL::PPMInput {
public:
PPMInput() {}
virtual void init(int machtnicht) = 0;
};
#endif // __AP_HAL_PPM_INPUT_H__

View File

@ -1,14 +0,0 @@
#ifndef __AP_HAL_PWM_OUTPUT_H__
#define __AP_HAL_PWM_OUTPUT_H__
#include "AP_HAL_Namespace.h"
class AP_HAL::PWMOutput {
public:
PWMOutput() {}
virtual void init(int machtnicht) = 0;
};
#endif // __AP_HAL_PWM_OUTPUT_H__

View File

@ -0,0 +1,14 @@
#ifndef __AP_HAL_RC_INPUT_H__
#define __AP_HAL_RC_INPUT_H__
#include "AP_HAL_Namespace.h"
class AP_HAL::RCInput {
public:
RCInput() {}
virtual void init(int machtnicht) = 0;
};
#endif // __AP_HAL_RC_INPUT_H__

View File

@ -0,0 +1,14 @@
#ifndef __AP_HAL_RC_OUTPUT_H__
#define __AP_HAL_RC_OUTPUT_H__
#include "AP_HAL_Namespace.h"
class AP_HAL::RCOutput {
public:
RCOutput() {}
virtual void init(int machtnicht) = 0;
};
#endif // __AP_HAL_RC_OUTPUT_H__

View File

@ -12,8 +12,8 @@
#include "Log.h" #include "Log.h"
#include "Console.h" #include "Console.h"
#include "GPIO.h" #include "GPIO.h"
#include "PPMInput.h" #include "RCInput.h"
#include "PWMOutput.h" #include "RCOutput.h"
#include "Scheduler.h" #include "Scheduler.h"
using namespace AP_HAL; using namespace AP_HAL;
@ -36,10 +36,10 @@ static DataFlashAPM1Log apm1DataFlashLog;
static DataFlashAPM2Log apm2DataFlashLog; static DataFlashAPM2Log apm2DataFlashLog;
static AVRUARTConsole avrUartConsole(&avrUart0Driver); static AVRUARTConsole avrUartConsole(&avrUart0Driver);
static ArduinoGPIO arduinoGPIO; static ArduinoGPIO arduinoGPIO;
static APM1PPMInput apm1PPMInput; static APM1RCInput apm1RCInput;
static APM2PPMInput apm2PPMInput; static APM2RCInput apm2RCInput;
static APM1PWMOutput apm1PWMOutput; static APM1RCOutput apm1RCOutput;
static APM2PWMOutput apm2PWMOutput; static APM2RCOutput apm2RCOutput;
static ArduinoScheduler arduinoScheduler; static ArduinoScheduler arduinoScheduler;
const HAL_AVR AP_HAL_AVR_APM1( const HAL_AVR AP_HAL_AVR_APM1(
@ -54,8 +54,8 @@ const HAL_AVR AP_HAL_AVR_APM1(
&apm1DataFlashLog, &apm1DataFlashLog,
&avrUartConsole, &avrUartConsole,
&arduinoGPIO, &arduinoGPIO,
&apm1PPMInput, &apm1RCInput,
&apm1PWMOutput, &apm1RCOutput,
&arduinoScheduler ); &arduinoScheduler );
const HAL_AVR AP_HAL_AVR_APM2( const HAL_AVR AP_HAL_AVR_APM2(
@ -70,7 +70,7 @@ const HAL_AVR AP_HAL_AVR_APM2(
&apm2DataFlashLog, &apm2DataFlashLog,
&avrUartConsole, &avrUartConsole,
&arduinoGPIO, &arduinoGPIO,
&apm2PPMInput, &apm2RCInput,
&apm2PWMOutput, &apm2RCOutput,
&arduinoScheduler ); &arduinoScheduler );

View File

@ -14,10 +14,10 @@ namespace AP_HAL_AVR {
class DataFlashAPM2Log; class DataFlashAPM2Log;
class AVRUARTConsole; class AVRUARTConsole;
class ArduinoGPIO; class ArduinoGPIO;
class APM1PPMInput; class APM1RCInput;
class APM2PPMInput; class APM2RCInput;
class APM1PWMOutput; class APM1RCOutput;
class APM2PWMOutput; class APM2RCOutput;
class ArduinoScheduler; class ArduinoScheduler;
} }

View File

@ -5,7 +5,8 @@
#include <AP_HAL.h> #include <AP_HAL.h>
#include "AP_HAL_AVR_Namespace.h" #include "AP_HAL_AVR_Namespace.h"
/* HAL_AVR class derives from HAL but provides an AVR-specific /**
* HAL_AVR class derives from HAL but provides an AVR-specific
* init method. * init method.
*/ */
@ -23,13 +24,13 @@ public:
AP_HAL::Log* _log, AP_HAL::Log* _log,
AP_HAL::Console* _console, AP_HAL::Console* _console,
AP_HAL::GPIO* _gpio, AP_HAL::GPIO* _gpio,
AP_HAL::PPMInput* _ppmin, AP_HAL::RCInput* _rcin,
AP_HAL::PWMOutput* _pwmout, AP_HAL::RCOutput* _rcout,
AP_HAL::Scheduler* _scheduler) AP_HAL::Scheduler* _scheduler)
: AP_HAL::HAL( _uart0, _uart1, _uart2, _uart3, : AP_HAL::HAL( _uart0, _uart1, _uart2, _uart3,
_i2c, _spi, _analogIn, _storage, _i2c, _spi, _analogIn, _storage,
_log, _console, _gpio, _ppmin, _log, _console, _gpio, _rcin,
_pwmout, _scheduler) {} _rcout, _scheduler) {}
void init(void* opts) const; void init(void* opts) const;
}; };

View File

@ -1,25 +0,0 @@
#ifndef __AP_HAL_AVR_PPM_INPUT_H__
#define __AP_HAL_AVR_PPM_INPUT_H__
#include <AP_HAL.h>
#include "AP_HAL_AVR_Namespace.h"
class AP_HAL_AVR::APM1PPMInput : public AP_HAL::PPMInput {
public:
APM1PPMInput() : _init(0) {}
void init(int machtnicht) { _init = 1; }
private:
int _init;
};
class AP_HAL_AVR::APM2PPMInput : public AP_HAL::PPMInput {
public:
APM2PPMInput() : _init(0) {}
void init(int machtnicht) { _init = 2; }
private:
int _init;
};
#endif // __AP_HAL_AVR_PPM_INPUT_H__

View File

@ -1,25 +0,0 @@
#ifndef __AP_HAL_AVR_PWM_OUTPUT_H__
#define __AP_HAL_AVR_PWM_OUTPUT_H__
#include <AP_HAL.h>
#include "AP_HAL_AVR_Namespace.h"
class AP_HAL_AVR::APM1PWMOutput : public AP_HAL::PWMOutput {
public:
APM1PWMOutput() : _init(0) {}
void init(int machtnicht) { _init = 1; }
private:
int _init;
};
class AP_HAL_AVR::APM2PWMOutput : public AP_HAL::PWMOutput {
public:
APM2PWMOutput() : _init(0) {}
void init(int machtnicht) { _init = 2; }
private:
int _init;
};
#endif // __AP_HAL_AVR_PWM_OUTPUT_H__

View File

@ -0,0 +1,25 @@
#ifndef __AP_HAL_AVR_RC_INPUT_H__
#define __AP_HAL_AVR_RC_INPUT_H__
#include <AP_HAL.h>
#include "AP_HAL_AVR_Namespace.h"
class AP_HAL_AVR::APM1RCInput : public AP_HAL::RCInput {
public:
APM1RCInput() : _init(0) {}
void init(int machtnicht) { _init = 1; }
private:
int _init;
};
class AP_HAL_AVR::APM2RCInput : public AP_HAL::RCInput {
public:
APM2RCInput() : _init(0) {}
void init(int machtnicht) { _init = 2; }
private:
int _init;
};
#endif // __AP_HAL_AVR_RC_INPUT_H__

View File

@ -0,0 +1,25 @@
#ifndef __AP_HAL_AVR_RC_OUTPUT_H__
#define __AP_HAL_AVR_RC_OUTPUT_H__
#include <AP_HAL.h>
#include "AP_HAL_AVR_Namespace.h"
class AP_HAL_AVR::APM1RCOutput : public AP_HAL::RCOutput {
public:
APM1RCOutput() : _init(0) {}
void init(int machtnicht) { _init = 1; }
private:
int _init;
};
class AP_HAL_AVR::APM2RCOutput : public AP_HAL::RCOutput {
public:
APM2RCOutput() : _init(0) {}
void init(int machtnicht) { _init = 2; }
private:
int _init;
};
#endif // __AP_HAL_AVR_RC_OUTPUT_H__