mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Vehicle: move AP_PARM_KEY_DUMP function up to AP_Vehicle base class
Common to all vehicles now, including Tracker
This commit is contained in:
parent
d0edfd2c0d
commit
1db081b095
@ -79,6 +79,7 @@ void AP_Vehicle::setup()
|
||||
|
||||
// init_ardupilot is where the vehicle does most of its initialisation.
|
||||
init_ardupilot();
|
||||
|
||||
// gyro FFT needs to be initialized really late
|
||||
#if HAL_GYROFFT_ENABLED
|
||||
gyro_fft.init(AP::scheduler().get_loop_period_us());
|
||||
@ -89,6 +90,10 @@ void AP_Vehicle::setup()
|
||||
#if HAL_HOTT_TELEM_ENABLED
|
||||
hott_telem.init();
|
||||
#endif
|
||||
|
||||
#if AP_PARAM_KEY_DUMP
|
||||
AP_Param::show_all(hal.console, true);
|
||||
#endif
|
||||
}
|
||||
|
||||
void AP_Vehicle::loop()
|
||||
|
Loading…
Reference in New Issue
Block a user