mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: move sensor init from setup(to init_ardupilot
This fixes a bug in which the external led was not being disabled if the EPM was enabled (they share pins). The cause of the problem was the EPM was being initialised before it's parameters had been loaded
This commit is contained in:
parent
cb17a5bdb6
commit
d362bb45fd
@ -909,8 +909,6 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
|||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
|
|
||||||
bool enable_external_leds = true;
|
|
||||||
|
|
||||||
// this needs to be the first call, as it fills memory with
|
// this needs to be the first call, as it fills memory with
|
||||||
// sentinel values
|
// sentinel values
|
||||||
memcheck_init();
|
memcheck_init();
|
||||||
@ -919,36 +917,6 @@ void setup() {
|
|||||||
// Load the default values of variables listed in var_info[]s
|
// Load the default values of variables listed in var_info[]s
|
||||||
AP_Param::setup_sketch_defaults();
|
AP_Param::setup_sketch_defaults();
|
||||||
|
|
||||||
// init EPM cargo gripper
|
|
||||||
#if EPM_ENABLED == ENABLED
|
|
||||||
epm.init();
|
|
||||||
enable_external_leds = !epm.enabled();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// initialise notify system
|
|
||||||
// disable external leds if epm is enabled because of pin conflict on the APM
|
|
||||||
notify.init(enable_external_leds);
|
|
||||||
|
|
||||||
// initialise battery monitor
|
|
||||||
battery.init();
|
|
||||||
|
|
||||||
#if CONFIG_SONAR == ENABLED
|
|
||||||
#if CONFIG_SONAR_SOURCE == SONAR_SOURCE_ADC
|
|
||||||
sonar_analog_source = new AP_ADC_AnalogSource(
|
|
||||||
&adc, CONFIG_SONAR_SOURCE_ADC_CHANNEL, 0.25);
|
|
||||||
#elif CONFIG_SONAR_SOURCE == SONAR_SOURCE_ANALOG_PIN
|
|
||||||
sonar_analog_source = hal.analogin->channel(
|
|
||||||
CONFIG_SONAR_SOURCE_ANALOG_PIN);
|
|
||||||
#else
|
|
||||||
#warning "Invalid CONFIG_SONAR_SOURCE"
|
|
||||||
#endif
|
|
||||||
sonar = new AP_RangeFinder_MaxsonarXL(sonar_analog_source,
|
|
||||||
&sonar_mode_filter);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
rssi_analog_source = hal.analogin->channel(g.rssi_pin);
|
|
||||||
board_vcc_analog_source = hal.analogin->channel(ANALOG_INPUT_BOARD_VCC);
|
|
||||||
|
|
||||||
init_ardupilot();
|
init_ardupilot();
|
||||||
|
|
||||||
// initialise the main loop scheduler
|
// initialise the main loop scheduler
|
||||||
|
@ -120,11 +120,43 @@ static void init_ardupilot()
|
|||||||
//
|
//
|
||||||
report_version();
|
report_version();
|
||||||
|
|
||||||
relay.init();
|
|
||||||
|
|
||||||
// load parameters from EEPROM
|
// load parameters from EEPROM
|
||||||
load_parameters();
|
load_parameters();
|
||||||
|
|
||||||
|
relay.init();
|
||||||
|
|
||||||
|
bool enable_external_leds = true;
|
||||||
|
|
||||||
|
// init EPM cargo gripper
|
||||||
|
#if EPM_ENABLED == ENABLED
|
||||||
|
epm.init();
|
||||||
|
enable_external_leds = !epm.enabled();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// initialise notify system
|
||||||
|
// disable external leds if epm is enabled because of pin conflict on the APM
|
||||||
|
notify.init(enable_external_leds);
|
||||||
|
|
||||||
|
// initialise battery monitor
|
||||||
|
battery.init();
|
||||||
|
|
||||||
|
#if CONFIG_SONAR == ENABLED
|
||||||
|
#if CONFIG_SONAR_SOURCE == SONAR_SOURCE_ADC
|
||||||
|
sonar_analog_source = new AP_ADC_AnalogSource(
|
||||||
|
&adc, CONFIG_SONAR_SOURCE_ADC_CHANNEL, 0.25);
|
||||||
|
#elif CONFIG_SONAR_SOURCE == SONAR_SOURCE_ANALOG_PIN
|
||||||
|
sonar_analog_source = hal.analogin->channel(
|
||||||
|
CONFIG_SONAR_SOURCE_ANALOG_PIN);
|
||||||
|
#else
|
||||||
|
#warning "Invalid CONFIG_SONAR_SOURCE"
|
||||||
|
#endif
|
||||||
|
sonar = new AP_RangeFinder_MaxsonarXL(sonar_analog_source,
|
||||||
|
&sonar_mode_filter);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
rssi_analog_source = hal.analogin->channel(g.rssi_pin);
|
||||||
|
board_vcc_analog_source = hal.analogin->channel(ANALOG_INPUT_BOARD_VCC);
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
barometer.init();
|
barometer.init();
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user