AP_Proximity: use strtol instead of sscanf
This commit is contained in:
parent
9d760a2956
commit
a4258639c8
@ -383,8 +383,8 @@ bool AP_Proximity_LightWareSF40C::process_reply()
|
|||||||
case RequestType_Health:
|
case RequestType_Health:
|
||||||
// expect result in the form "0xhhhh"
|
// expect result in the form "0xhhhh"
|
||||||
if (element_len[0] > 0) {
|
if (element_len[0] > 0) {
|
||||||
int result;
|
long int result = strtol(element_buf[0], nullptr, 16);
|
||||||
if (sscanf(element_buf[0], "%x", &result) > 0) {
|
if (result > 0) {
|
||||||
_sensor_status.value = result;
|
_sensor_status.value = result;
|
||||||
success = true;
|
success = true;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user