global: use static method to construct AP_Parachute

This commit is contained in:
Lucas De Marchi 2017-08-29 16:55:05 -07:00 committed by Francisco Ferreira
parent 88dea049b4
commit 31db77e47b
4 changed files with 3 additions and 6 deletions

View File

@ -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

View File

@ -576,7 +576,7 @@ private:
// Parachute release
#if PARACHUTE == ENABLED
AP_Parachute parachute;
AP_Parachute parachute = AP_Parachute::create(relay);
#endif
// Landing Gear Controller

View File

@ -606,7 +606,7 @@ private:
#if PARACHUTE == ENABLED
AP_Parachute parachute {relay};
AP_Parachute parachute = AP_Parachute::create(relay);
#endif
// terrain handling

View File

@ -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()
{