Fixed apo radio error.
This commit is contained in:
parent
ab183e54a0
commit
1833f69961
@ -31,7 +31,7 @@ set(APPLICATION_VERSION "${APPLICATION_VERSION_MAJOR}.${APPLICATION_VERSION_MINO
|
|||||||
|
|
||||||
# macros
|
# macros
|
||||||
include(MacroEnsureOutOfSourceBuild)
|
include(MacroEnsureOutOfSourceBuild)
|
||||||
include(UseDoxygen)
|
#include(UseDoxygen)
|
||||||
|
|
||||||
# disallow in-source build
|
# disallow in-source build
|
||||||
macro_ensure_out_of_source_build("${PROJECT_NAME} requires an out of source build.
|
macro_ensure_out_of_source_build("${PROJECT_NAME} requires an out of source build.
|
||||||
|
@ -37,12 +37,14 @@ void setup() {
|
|||||||
hal->debug = &Serial;
|
hal->debug = &Serial;
|
||||||
hal->debug->println_P(PSTR("initializing debug line"));
|
hal->debug->println_P(PSTR("initializing debug line"));
|
||||||
|
|
||||||
|
// initialize radio
|
||||||
|
hal->radio = new APM_RC_APM1;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Sensor initialization
|
* Sensor initialization
|
||||||
*/
|
*/
|
||||||
if (hal->getMode() == MODE_LIVE) {
|
if (hal->getMode() == MODE_LIVE) {
|
||||||
|
|
||||||
hal->radio = new APM_RC_APM1;
|
|
||||||
|
|
||||||
hal->debug->println_P(PSTR("initializing adc"));
|
hal->debug->println_P(PSTR("initializing adc"));
|
||||||
hal->adc = new ADC_CLASS;
|
hal->adc = new ADC_CLASS;
|
||||||
@ -131,7 +133,7 @@ void setup() {
|
|||||||
/*
|
/*
|
||||||
* navigation sensors
|
* navigation sensors
|
||||||
*/
|
*/
|
||||||
hal->imu = new AP_IMU_INS(new AP_InertialSensor_Oilpan(hal->adc), k_sensorCalib);
|
//hal->imu = new AP_IMU_INS(new AP_InertialSensor_Oilpan(hal->adc), k_sensorCalib);
|
||||||
//hal->imu = AP_IMU_INS(new AP_InertialSensor_MPU6000(mpu6000SelectPin), k_sensorCalib);
|
//hal->imu = AP_IMU_INS(new AP_InertialSensor_MPU6000(mpu6000SelectPin), k_sensorCalib);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -49,7 +49,8 @@ public:
|
|||||||
// initialized
|
// initialized
|
||||||
AP_HardwareAbstractionLayer(halMode_t mode, board_t board,
|
AP_HardwareAbstractionLayer(halMode_t mode, board_t board,
|
||||||
vehicle_t vehicle, uint8_t heartBeatTimeout) :
|
vehicle_t vehicle, uint8_t heartBeatTimeout) :
|
||||||
adc(), gps(), baro(), compass(), rangeFinders(), imu(), batteryMonitor(), rc(), gcs(),
|
adc(), gps(), baro(), compass(), rangeFinders(), imu(), batteryMonitor(),
|
||||||
|
radio(), rc(), gcs(),
|
||||||
hil(), debug(), load(), lastHeartBeat(),
|
hil(), debug(), load(), lastHeartBeat(),
|
||||||
_heartBeatTimeout(heartBeatTimeout), _mode(mode),
|
_heartBeatTimeout(heartBeatTimeout), _mode(mode),
|
||||||
_board(board), _vehicle(vehicle) {
|
_board(board), _vehicle(vehicle) {
|
||||||
|
Loading…
Reference in New Issue
Block a user