mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
global: use static method to construct AP_Notify
This commit is contained in:
parent
9463dbb408
commit
62ac0ab8aa
@ -251,7 +251,7 @@ private:
|
|||||||
} failsafe;
|
} failsafe;
|
||||||
|
|
||||||
// notification object for LEDs, buzzers etc (parameter set to false disables external leds)
|
// notification object for LEDs, buzzers etc (parameter set to false disables external leds)
|
||||||
AP_Notify notify;
|
AP_Notify notify = AP_Notify::create();
|
||||||
|
|
||||||
// true if we have a position estimate from AHRS
|
// true if we have a position estimate from AHRS
|
||||||
bool have_position;
|
bool have_position;
|
||||||
|
@ -96,7 +96,7 @@ private:
|
|||||||
AP_Scheduler scheduler = AP_Scheduler::create();
|
AP_Scheduler scheduler = AP_Scheduler::create();
|
||||||
|
|
||||||
// notification object for LEDs, buzzers etc
|
// notification object for LEDs, buzzers etc
|
||||||
AP_Notify notify;
|
AP_Notify notify = AP_Notify::create();
|
||||||
|
|
||||||
uint32_t start_time_ms = 0;
|
uint32_t start_time_ms = 0;
|
||||||
|
|
||||||
|
@ -178,7 +178,7 @@ private:
|
|||||||
AP_Scheduler scheduler = AP_Scheduler::create();
|
AP_Scheduler scheduler = AP_Scheduler::create();
|
||||||
|
|
||||||
// AP_Notify instance
|
// AP_Notify instance
|
||||||
AP_Notify notify;
|
AP_Notify notify = AP_Notify::create();
|
||||||
|
|
||||||
// used to detect MAVLink acks from GCS to stop compassmot
|
// used to detect MAVLink acks from GCS to stop compassmot
|
||||||
uint8_t command_ack_counter;
|
uint8_t command_ack_counter;
|
||||||
|
@ -186,7 +186,7 @@ private:
|
|||||||
RC_Channel *channel_rudder;
|
RC_Channel *channel_rudder;
|
||||||
|
|
||||||
// notification object for LEDs, buzzers etc (parameter set to false disables external leds)
|
// notification object for LEDs, buzzers etc (parameter set to false disables external leds)
|
||||||
AP_Notify notify;
|
AP_Notify notify = AP_Notify::create();
|
||||||
|
|
||||||
DataFlash_Class DataFlash;
|
DataFlash_Class DataFlash;
|
||||||
|
|
||||||
|
@ -148,7 +148,7 @@ private:
|
|||||||
AP_Scheduler scheduler = AP_Scheduler::create();
|
AP_Scheduler scheduler = AP_Scheduler::create();
|
||||||
|
|
||||||
// AP_Notify instance
|
// AP_Notify instance
|
||||||
AP_Notify notify;
|
AP_Notify notify = AP_Notify::create();
|
||||||
|
|
||||||
// primary input control channels
|
// primary input control channels
|
||||||
RC_Channel *channel_roll;
|
RC_Channel *channel_roll;
|
||||||
|
Loading…
Reference in New Issue
Block a user