mirror of https://github.com/ArduPilot/ardupilot
AP_Periph: rearrange apd periph initialiser for --error=reorder
This commit is contained in:
parent
43970c0c7a
commit
d1674b089a
|
@ -17,8 +17,9 @@ extern const AP_HAL::HAL& hal;
|
||||||
#define TELEM_LEN 0x16
|
#define TELEM_LEN 0x16
|
||||||
|
|
||||||
ESC_APD_Telem::ESC_APD_Telem (AP_HAL::UARTDriver *_uart, float num_poles) :
|
ESC_APD_Telem::ESC_APD_Telem (AP_HAL::UARTDriver *_uart, float num_poles) :
|
||||||
pole_count(num_poles),
|
uart(_uart),
|
||||||
uart(_uart) {
|
pole_count(num_poles)
|
||||||
|
{
|
||||||
uart->begin(115200);
|
uart->begin(115200);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue