mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
global: use static method to construct AP_Parachute
This commit is contained in:
parent
88dea049b4
commit
31db77e47b
@ -66,9 +66,6 @@ Copter::Copter(void)
|
||||
mainLoop_count(0),
|
||||
rtl_loiter_start_time(0),
|
||||
auto_trim_counter(0),
|
||||
#if PARACHUTE == ENABLED
|
||||
parachute(relay),
|
||||
#endif
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
terrain(ahrs, mission, rally),
|
||||
#endif
|
||||
|
@ -576,7 +576,7 @@ private:
|
||||
|
||||
// Parachute release
|
||||
#if PARACHUTE == ENABLED
|
||||
AP_Parachute parachute;
|
||||
AP_Parachute parachute = AP_Parachute::create(relay);
|
||||
#endif
|
||||
|
||||
// Landing Gear Controller
|
||||
|
@ -606,7 +606,7 @@ private:
|
||||
|
||||
|
||||
#if PARACHUTE == ENABLED
|
||||
AP_Parachute parachute {relay};
|
||||
AP_Parachute parachute = AP_Parachute::create(relay);
|
||||
#endif
|
||||
|
||||
// terrain handling
|
||||
|
@ -22,7 +22,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
static AP_Relay relay = AP_Relay::create();
|
||||
|
||||
// Parachute
|
||||
AP_Parachute parachute(relay);
|
||||
static AP_Parachute parachute = AP_Parachute::create(relay);
|
||||
|
||||
void setup()
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user