ardupilot/libraries/APO/AP_Board.h

140 lines
2.6 KiB
C
Raw Normal View History

2011-09-28 21:51:12 -03:00
/*
2011-12-07 17:31:56 -04:00
* AP_Board.h
2011-09-28 21:51:12 -03:00
*
* Created on: Apr 4, 2011
*
*/
2011-12-07 17:31:56 -04:00
#ifndef AP_BOARD_H_
#define AP_BOARD_H_
2011-09-28 21:51:12 -03:00
#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-12-07 17:31:56 -04:00
class DataFlash_Class;
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
2011-12-07 17:31:56 -04:00
class AP_Board {
2011-09-28 21:51:12 -03:00
public:
2011-12-07 17:31:56 -04:00
typedef uint32_t options_t;
options_t _options;
// enumerations
enum mode_e {
MODE_LIVE, MODE_HIL_CNTL,
/*MODE_HIL_NAV*/
};
enum options_e {
opt_gps = 0<<1,
opt_baro = 1<<1,
opt_compass = 2<<1,
opt_batteryMonitor = 3<<1,
opt_rangeFinderFront = 4<<1,
opt_rangeFinderBack = 5<<1,
opt_rangeFinderLeft = 6<<1,
opt_rangeFinderRight = 7<<1,
opt_rangeFinderUp = 8<<1,
opt_rangeFinderDown = 9<<1,
};
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-07 17:31:56 -04:00
AP_Board(mode_e mode, MAV_TYPE vehicle, options_t options): _mode(mode), _vehicle(vehicle), _options(options) {
}
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;
2011-12-07 17:31:56 -04:00
FastSerial * gcsPort;
FastSerial * hilPort;
2011-10-26 13:31:11 -03:00
/**
* data
*/
2011-12-07 17:31:56 -04:00
DataFlash_Class * dataFlash;
2011-10-26 13:31:11 -03:00
uint8_t load;
/**
* settings
*/
uint8_t slideSwitchPin;
uint8_t pushButtonPin;
uint8_t aLedPin;
uint8_t bLedPin;
uint8_t cLedPin;
uint16_t eepromMaxAddr;
// accessors
2011-12-07 17:31:56 -04:00
mode_e getMode() {
2011-10-26 13:31:11 -03:00
return _mode;
}
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
2011-12-07 17:31:56 -04:00
mode_e _mode;
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