AP_Vehicle: move many members up to base class

This commit is contained in:
Peter Barker 2018-12-27 17:31:34 +11:00 committed by Andrew Tridgell
parent 286963ad16
commit dbb1f01445

View File

@ -19,11 +19,25 @@
parameters needed by multiple libraries
*/
#include <AP_Baro/AP_Baro.h>
#include <AP_BoardConfig/AP_BoardConfig.h> // board configuration library
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
#include <AP_Button/AP_Button.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_Notify/AP_Notify.h> // Notify library
#include <AP_Param/AP_Param.h>
#include <AP_Relay/AP_Relay.h> // APM relay
#include <AP_RSSI/AP_RSSI.h> // RSSI Library
#include <AP_SerialManager/AP_SerialManager.h> // Serial manager library
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
class AP_Vehicle {
class AP_Vehicle : public AP_HAL::HAL::Callbacks {
public:
AP_Vehicle() {}
/*
common parameters for fixed wing aircraft
*/
@ -76,7 +90,39 @@ public:
struct MultiCopter {
AP_Int16 angle_max;
};
protected:
// board specific config
AP_BoardConfig BoardConfig;
#if HAL_WITH_UAVCAN
// board specific config for CAN bus
AP_BoardConfig_CAN BoardConfig_CAN;
#endif
// sensor drivers
AP_GPS gps;
AP_Baro barometer;
Compass compass;
AP_InertialSensor ins;
AP_Button button;
RangeFinder rangefinder;
AP_RSSI rssi;
AP_SerialManager serial_manager;
AP_Relay relay;
AP_ServoRelayEvents ServoRelayEvents;
// notification object for LEDs, buzzers etc (parameter set to
// false disables external leds)
AP_Notify notify;
};
extern const AP_HAL::HAL& hal;
#include "AP_Vehicle_Type.h"