mirror of https://github.com/ArduPilot/ardupilot
AP_PiccoloCAN: fixed build error on Linux
_thread_name too short
This commit is contained in:
parent
0be0e93534
commit
e1f89c2c0d
|
@ -365,7 +365,7 @@ void AP_PiccoloCAN::send_esc_messages(void)
|
||||||
if (hal.util->get_soft_armed()) {
|
if (hal.util->get_soft_armed()) {
|
||||||
|
|
||||||
bool send_cmd = false;
|
bool send_cmd = false;
|
||||||
int16_t cmd[4];
|
int16_t cmd[4] {};
|
||||||
uint8_t idx;
|
uint8_t idx;
|
||||||
|
|
||||||
// Transmit bulk command packets to 4x ESC simultaneously
|
// Transmit bulk command packets to 4x ESC simultaneously
|
||||||
|
|
|
@ -99,7 +99,7 @@ private:
|
||||||
bool handle_esc_message(uavcan::CanFrame &frame);
|
bool handle_esc_message(uavcan::CanFrame &frame);
|
||||||
|
|
||||||
bool _initialized;
|
bool _initialized;
|
||||||
char _thread_name[9];
|
char _thread_name[16];
|
||||||
uint8_t _driver_index;
|
uint8_t _driver_index;
|
||||||
uavcan::ICanDriver* _can_driver;
|
uavcan::ICanDriver* _can_driver;
|
||||||
const uavcan::CanFrame* _select_frames[uavcan::MaxCanIfaces] { };
|
const uavcan::CanFrame* _select_frames[uavcan::MaxCanIfaces] { };
|
||||||
|
|
Loading…
Reference in New Issue