ardupilot/libraries/APO/AP_HardwareAbstractionLayer.h

125 lines
2.2 KiB
C
Raw Normal View History

2011-09-28 21:51:12 -03:00
/*
* AP_HardwareAbstractionLayer.h
*
* Created on: Apr 4, 2011
*
*/
#ifndef AP_HARDWAREABSTRACTIONLAYER_H_
#define AP_HARDWAREABSTRACTIONLAYER_H_
#include "../AP_Common/AP_Vector.h"
#include "../GCS_MAVLink/GCS_MAVLink.h"
class AP_ADC;
class IMU;
class GPS;
class APM_BMP085_Class;
class Compass;
class BetterStream;
class RangeFinder;
class FastSerial;
class AP_IMU_INS;
class AP_InertialSensor;
class APM_RC_Class;
class AP_TimerProcess;
class Arduino_Mega_ISR_Registry;
2011-09-28 21:51:12 -03:00
namespace apo {
class AP_RcChannel;
class AP_CommLink;
class AP_BatteryMonitor;
2011-09-28 21:51:12 -03:00
// enumerations
enum halMode_t {
2011-10-26 13:31:11 -03:00
MODE_LIVE, MODE_HIL_CNTL,
/*MODE_HIL_NAV*/
};
2011-09-28 21:51:12 -03:00
enum board_t {
2011-10-26 13:31:11 -03:00
BOARD_ARDUPILOTMEGA_1280, BOARD_ARDUPILOTMEGA_2560, BOARD_ARDUPILOTMEGA_2
2011-09-28 21:51:12 -03:00
};
class AP_HardwareAbstractionLayer {
public:
2011-10-26 13:31:11 -03:00
// default ctors on pointers called on pointers here, this
// allows NULL to be used as a boolean for if the device was
// initialized
2011-12-06 19:56:16 -04:00
AP_HardwareAbstractionLayer(halMode_t mode, board_t board, MAV_TYPE vehicle);
2011-10-26 13:31:11 -03:00
/**
* Sensors
*/
AP_ADC * adc;
GPS * gps;
APM_BMP085_Class * baro;
Compass * compass;
Vector<RangeFinder *> rangeFinders;
AP_BatteryMonitor * batteryMonitor;
AP_IMU_INS * imu;
AP_InertialSensor * ins;
/**
* Scheduler
*/
AP_TimerProcess * scheduler;
Arduino_Mega_ISR_Registry * isr_registry;
/**
* Actuators
*/
APM_RC_Class * radio;
2011-10-26 13:31:11 -03:00
/**
* Radio Channels
*/
Vector<AP_RcChannel *> rc;
/**
* Communication Channels
*/
AP_CommLink * gcs;
AP_CommLink * hil;
FastSerial * debug;
/**
* data
*/
uint8_t load;
/**
* settings
*/
uint8_t slideSwitchPin;
uint8_t pushButtonPin;
uint8_t aLedPin;
uint8_t bLedPin;
uint8_t cLedPin;
uint16_t eepromMaxAddr;
// accessors
halMode_t getMode() {
return _mode;
}
board_t getBoard() {
return _board;
}
2011-11-29 14:59:44 -04:00
MAV_TYPE getVehicle() {
2011-10-26 13:31:11 -03:00
return _vehicle;
}
2011-09-28 21:51:12 -03:00
private:
2011-10-26 13:31:11 -03:00
// enumerations
halMode_t _mode;
board_t _board;
2011-11-29 14:59:44 -04:00
MAV_TYPE _vehicle;
2011-09-28 21:51:12 -03:00
};
2011-10-26 15:59:40 -03:00
} // namespace apo
2011-09-28 21:51:12 -03:00
#endif /* AP_HARDWAREABSTRACTIONLAYER_H_ */
2011-10-26 15:59:40 -03:00
// vim:ts=4:sw=4:expandtab