mirror of https://github.com/ArduPilot/ardupilot
global: use static method to construct AP_Relay
This commit is contained in:
parent
87d2bf22f2
commit
13d7f58036
|
@ -202,7 +202,7 @@ private:
|
|||
GCS_Rover &gcs() { return _gcs; }
|
||||
|
||||
// relay support
|
||||
AP_Relay relay;
|
||||
AP_Relay relay = AP_Relay::create();
|
||||
|
||||
AP_ServoRelayEvents ServoRelayEvents;
|
||||
|
||||
|
|
|
@ -536,7 +536,7 @@ private:
|
|||
uint8_t auto_trim_counter;
|
||||
|
||||
// Reference to the relay object
|
||||
AP_Relay relay;
|
||||
AP_Relay relay = AP_Relay::create();
|
||||
|
||||
// handle repeated servo and relay events
|
||||
AP_ServoRelayEvents ServoRelayEvents;
|
||||
|
|
|
@ -267,7 +267,7 @@ private:
|
|||
AP_SpdHgtControl *SpdHgt_Controller = &TECS_controller;
|
||||
|
||||
// Relay
|
||||
AP_Relay relay;
|
||||
AP_Relay relay = AP_Relay::create();
|
||||
|
||||
// handle servo and relay events
|
||||
AP_ServoRelayEvents ServoRelayEvents {relay};
|
||||
|
|
|
@ -408,7 +408,7 @@ private:
|
|||
uint16_t mainLoop_count;
|
||||
|
||||
// Reference to the relay object
|
||||
AP_Relay relay;
|
||||
AP_Relay relay = AP_Relay::create();
|
||||
|
||||
// handle repeated servo and relay events
|
||||
AP_ServoRelayEvents ServoRelayEvents;
|
||||
|
|
|
@ -19,7 +19,7 @@ void loop();
|
|||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
// Relay
|
||||
AP_Relay relay;
|
||||
static AP_Relay relay = AP_Relay::create();
|
||||
|
||||
// Parachute
|
||||
AP_Parachute parachute(relay);
|
||||
|
|
Loading…
Reference in New Issue