AP_Proximity: fix compilation warning in LightWare driver

../../libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp: In member
function ‘void AP_Proximity_LightWareSF40C::request_new_data()’:
../../libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp:235:6:
warning:
‘__builtin___snprintf_chk’ output may be truncated before the last
format
character [-Wformat-truncation=]
 void AP_Proximity_LightWareSF40C::request_new_data()
      ^~~~~~~~~~~~~~~~~~~~~~~~~~~
In file included from /usr/include/stdio.h:862:0,
                 from ../../libraries/AP_Common/AP_Common.h:179,
                 from ../../libraries/AP_HAL/UARTDriver.h:5,
                 from ../../libraries/AP_HAL/HAL.h:11,
                 from ../../libraries/AP_HAL/AP_HAL_Main.h:19,
                 from ../../libraries/AP_HAL/AP_HAL.h:8,
                 from
../../libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp:16:
/usr/include/x86_64-linux-gnu/bits/stdio2.h:65:44: note:
‘__builtin___snprintf_chk’ output between 10 and 16 bytes into a
destination
of size 15
        __bos (__s), __fmt, __va_arg_pack ());
                                            ^
../../libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp: In member
function ‘bool
AP_Proximity_LightWareSF40C::send_request_for_distance()’:
../../libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp:275:6:
warning:
‘__builtin___snprintf_chk’ output may be truncated before the last
format
character [-Wformat-truncation=]
 bool AP_Proximity_LightWareSF40C::send_request_for_distance()
      ^~~~~~~~~~~~~~~~~~~~~~~~~~~
In file included from /usr/include/stdio.h:862:0,
                 from ../../libraries/AP_Common/AP_Common.h:179,
                 from ../../libraries/AP_HAL/UARTDriver.h:5,
                 from ../../libraries/AP_HAL/HAL.h:11,
                 from ../../libraries/AP_HAL/AP_HAL_Main.h:19,
                 from ../../libraries/AP_HAL/AP_HAL.h:8,
                 from
../../libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp:16:
/usr/include/x86_64-linux-gnu/bits/stdio2.h:65:44: note:
This commit is contained in:
Peter Barker 2018-01-25 23:00:22 +11:00 committed by Randy Mackay
parent 2d31a7b318
commit 51991fdd76

View File

@ -222,7 +222,8 @@ void AP_Proximity_LightWareSF40C::set_forward_direction()
// set forward direction
char request_str[15];
int16_t yaw_corr = frontend.get_yaw_correction(state.instance);
snprintf(request_str, sizeof(request_str), "#MBF,%d\r\n", (int)yaw_corr);
yaw_corr = constrain_int16(yaw_corr, -999, 999);
snprintf(request_str, sizeof(request_str), "#MBF,%d\r\n", yaw_corr);
uart->write(request_str);
// request update on motor direction
@ -286,7 +287,9 @@ bool AP_Proximity_LightWareSF40C::send_request_for_distance()
// prepare request
char request_str[16];
snprintf(request_str, sizeof(request_str), "?TS,%d,%d\r\n", (int)(_sector_width_deg[_last_sector]), (int)(_sector_middle_deg[_last_sector]));
snprintf(request_str, sizeof(request_str), "?TS,%u,%u\r\n",
MIN(_sector_width_deg[_last_sector], 999),
MIN(_sector_middle_deg[_last_sector], 999));
uart->write(request_str);