mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RangeFinder: remove number_detections member variable and add number_detections reference argument to parse_response
This commit is contained in:
parent
43f2482abd
commit
8432c5fb4a
@ -69,8 +69,9 @@ bool AP_RangeFinder_LeddarOne::get_reading(uint16_t &reading_cm)
|
|||||||
|
|
||||||
// parse a response message, set number_detections, detections and sum_distance
|
// parse a response message, set number_detections, detections and sum_distance
|
||||||
// must be signed to handle errors
|
// must be signed to handle errors
|
||||||
if (parse_response() != LEDDARONE_OK) {
|
uint8_t number_detections;
|
||||||
// TODO: when (number_detections < 0) handle LEDDARONE_ERR_
|
if (parse_response(number_detections) != LEDDARONE_OK) {
|
||||||
|
// TODO: when (not LEDDARONE_OK) handle LEDDARONE_ERR_
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -166,7 +167,7 @@ LeddarOne_Status AP_RangeFinder_LeddarOne::send_request(void)
|
|||||||
/*
|
/*
|
||||||
parse a response message from Modbus
|
parse a response message from Modbus
|
||||||
*/
|
*/
|
||||||
LeddarOne_Status AP_RangeFinder_LeddarOne::parse_response(void)
|
LeddarOne_Status AP_RangeFinder_LeddarOne::parse_response(uint8_t &number_detections)
|
||||||
{
|
{
|
||||||
uint8_t data_buffer[25] = {0};
|
uint8_t data_buffer[25] = {0};
|
||||||
uint32_t start_ms = AP_HAL::millis();
|
uint32_t start_ms = AP_HAL::millis();
|
||||||
@ -204,7 +205,7 @@ LeddarOne_Status AP_RangeFinder_LeddarOne::parse_response(void)
|
|||||||
number_detections = data_buffer[10];
|
number_detections = data_buffer[10];
|
||||||
|
|
||||||
// if the number of detection is over or zero , it is false
|
// if the number of detection is over or zero , it is false
|
||||||
if (number_detections > LEDDARONE_DETECTIONS_MAX || number_detections <= 0) {
|
if (number_detections > LEDDARONE_DETECTIONS_MAX || number_detections == 0) {
|
||||||
return LEDDARONE_ERR_NUMBER_DETECTIONS;
|
return LEDDARONE_ERR_NUMBER_DETECTIONS;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -46,12 +46,11 @@ private:
|
|||||||
LeddarOne_Status send_request(void);
|
LeddarOne_Status send_request(void);
|
||||||
|
|
||||||
// parse a response message from ModBus
|
// parse a response message from ModBus
|
||||||
LeddarOne_Status parse_response(void);
|
LeddarOne_Status parse_response(uint8_t &number_detections);
|
||||||
|
|
||||||
AP_HAL::UARTDriver *uart = nullptr;
|
AP_HAL::UARTDriver *uart = nullptr;
|
||||||
uint32_t last_reading_ms;
|
uint32_t last_reading_ms;
|
||||||
|
|
||||||
uint16_t detections[LEDDARONE_DETECTIONS_MAX];
|
uint16_t detections[LEDDARONE_DETECTIONS_MAX];
|
||||||
uint32_t sum_distance;
|
uint32_t sum_distance;
|
||||||
uint8_t number_detections;
|
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user