mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: re-order initialiser lines so -Werror=reorder will work
This commit is contained in:
parent
8b9154d115
commit
5a967a60ff
|
@ -34,11 +34,11 @@ extern const AP_HAL::HAL &hal;
|
||||||
#define SQRT_2_3 0.816496580927726f
|
#define SQRT_2_3 0.816496580927726f
|
||||||
#define SQRT_6 2.449489742783178f
|
#define SQRT_6 2.449489742783178f
|
||||||
|
|
||||||
DSP::FFTWindowState::FFTWindowState(uint16_t window_size, uint16_t sample_rate, uint8_t sliding_window_size)
|
DSP::FFTWindowState::FFTWindowState(uint16_t window_size, uint16_t sample_rate, uint8_t sliding_window_size) :
|
||||||
: _window_size(window_size),
|
_bin_resolution((float)sample_rate / (float)window_size),
|
||||||
_bin_count(window_size / 2),
|
_bin_count(window_size / 2),
|
||||||
_num_stored_freqs(window_size / 2 + 1),
|
_num_stored_freqs(window_size / 2 + 1),
|
||||||
_bin_resolution((float)sample_rate / (float)window_size),
|
_window_size(window_size),
|
||||||
_sliding_window_size(sliding_window_size),
|
_sliding_window_size(sliding_window_size),
|
||||||
_current_slice(0)
|
_current_slice(0)
|
||||||
{
|
{
|
||||||
|
|
|
@ -55,17 +55,6 @@ public:
|
||||||
AP_HAL::CANIface** _can_ifaces)
|
AP_HAL::CANIface** _can_ifaces)
|
||||||
#endif
|
#endif
|
||||||
:
|
:
|
||||||
serial_array{
|
|
||||||
_serial0,
|
|
||||||
_serial1,
|
|
||||||
_serial2,
|
|
||||||
_serial3,
|
|
||||||
_serial4,
|
|
||||||
_serial5,
|
|
||||||
_serial6,
|
|
||||||
_serial7,
|
|
||||||
_serial8,
|
|
||||||
_serial9},
|
|
||||||
i2c_mgr(_i2c_mgr),
|
i2c_mgr(_i2c_mgr),
|
||||||
spi(_spi),
|
spi(_spi),
|
||||||
wspi(_wspi),
|
wspi(_wspi),
|
||||||
|
@ -78,13 +67,24 @@ public:
|
||||||
scheduler(_scheduler),
|
scheduler(_scheduler),
|
||||||
util(_util),
|
util(_util),
|
||||||
opticalflow(_opticalflow),
|
opticalflow(_opticalflow),
|
||||||
#if HAL_WITH_DSP
|
|
||||||
dsp(_dsp),
|
|
||||||
#endif
|
|
||||||
#if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
#if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
||||||
simstate(_simstate),
|
simstate(_simstate),
|
||||||
#endif
|
#endif
|
||||||
flash(_flash)
|
flash(_flash),
|
||||||
|
#if HAL_WITH_DSP
|
||||||
|
dsp(_dsp),
|
||||||
|
#endif
|
||||||
|
serial_array{
|
||||||
|
_serial0,
|
||||||
|
_serial1,
|
||||||
|
_serial2,
|
||||||
|
_serial3,
|
||||||
|
_serial4,
|
||||||
|
_serial5,
|
||||||
|
_serial6,
|
||||||
|
_serial7,
|
||||||
|
_serial8,
|
||||||
|
_serial9}
|
||||||
{
|
{
|
||||||
#if HAL_NUM_CAN_IFACES > 0
|
#if HAL_NUM_CAN_IFACES > 0
|
||||||
if (_can_ifaces == nullptr) {
|
if (_can_ifaces == nullptr) {
|
||||||
|
|
|
@ -42,8 +42,8 @@ ExpectDelay::~ExpectDelay()
|
||||||
*/
|
*/
|
||||||
TimeCheck::TimeCheck(uint32_t _limit_ms, const char *_file, uint32_t _line) :
|
TimeCheck::TimeCheck(uint32_t _limit_ms, const char *_file, uint32_t _line) :
|
||||||
limit_ms(_limit_ms),
|
limit_ms(_limit_ms),
|
||||||
file(_file),
|
line(_line),
|
||||||
line(_line)
|
file(_file)
|
||||||
{
|
{
|
||||||
start_ms = AP_HAL::millis();
|
start_ms = AP_HAL::millis();
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue