mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-05 21:23:58 -04:00
AP_RangeFinder: change error and ok status defines to LeddarOne_Status enum
This commit is contained in:
parent
de5b40d70e
commit
6123fad124
@ -67,17 +67,15 @@ bool AP_RangeFinder_LeddarOne::get_reading(uint16_t &reading_cm)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// parse a response message, set detections and sum_distance
|
// parse a response message, set number_detectins, detections and sum_distance
|
||||||
// must be signed to handle errors
|
// must be signed to handle errors
|
||||||
int8_t number_detections = parse_response();
|
if (parse_response() != LEDDARONE_OK) {
|
||||||
|
|
||||||
if (number_detections <= 0) {
|
|
||||||
// TODO: when (number_detections < 0) handle LEDDARONE_ERR_
|
// TODO: when (number_detections < 0) handle LEDDARONE_ERR_
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// calculate average distance
|
// calculate average distance
|
||||||
reading_cm = sum_distance / (uint8_t)number_detections;
|
reading_cm = sum_distance / number_detections;
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@ -130,7 +128,7 @@ bool AP_RangeFinder_LeddarOne::CRC16(uint8_t *aBuffer, uint8_t aLength, bool aCh
|
|||||||
/*
|
/*
|
||||||
send a request message to execute ModBus function 0x04
|
send a request message to execute ModBus function 0x04
|
||||||
*/
|
*/
|
||||||
int8_t AP_RangeFinder_LeddarOne::send_request(void)
|
LeddarOne_Status AP_RangeFinder_LeddarOne::send_request(void)
|
||||||
{
|
{
|
||||||
uint8_t data_buffer[10] = {0};
|
uint8_t data_buffer[10] = {0};
|
||||||
uint8_t i = 0;
|
uint8_t i = 0;
|
||||||
@ -168,7 +166,7 @@ int8_t AP_RangeFinder_LeddarOne::send_request(void)
|
|||||||
/*
|
/*
|
||||||
parse a response message from Modbus
|
parse a response message from Modbus
|
||||||
*/
|
*/
|
||||||
int8_t AP_RangeFinder_LeddarOne::parse_response(void)
|
LeddarOne_Status AP_RangeFinder_LeddarOne::parse_response(void)
|
||||||
{
|
{
|
||||||
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();
|
||||||
@ -203,10 +201,10 @@ int8_t AP_RangeFinder_LeddarOne::parse_response(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// number of detections
|
// number of detections
|
||||||
uint8_t number_detections = data_buffer[10];
|
number_detections = data_buffer[10];
|
||||||
|
|
||||||
// if the number of detection is over , it is false
|
// if the number of detection is over or zero , it is false
|
||||||
if (number_detections > LEDDARONE_DETECTIONS_MAX) {
|
if (number_detections > LEDDARONE_DETECTIONS_MAX || number_detections <= 0) {
|
||||||
return LEDDARONE_ERR_NUMBER_DETECTIONS;
|
return LEDDARONE_ERR_NUMBER_DETECTIONS;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -219,5 +217,5 @@ int8_t AP_RangeFinder_LeddarOne::parse_response(void)
|
|||||||
index_offset += 4;
|
index_offset += 4;
|
||||||
}
|
}
|
||||||
|
|
||||||
return (int8_t)number_detections;
|
return LEDDARONE_OK;
|
||||||
}
|
}
|
||||||
|
@ -10,14 +10,16 @@
|
|||||||
// default slave address
|
// default slave address
|
||||||
#define LEDDARONE_DEFAULT_ADDRESS 0x01
|
#define LEDDARONE_DEFAULT_ADDRESS 0x01
|
||||||
|
|
||||||
// error codes
|
// LeddarOne status
|
||||||
#define LEDDARONE_OK 0
|
enum LeddarOne_Status {
|
||||||
#define LEDDARONE_ERR_BAD_CRC -1
|
LEDDARONE_OK = 0,
|
||||||
#define LEDDARONE_ERR_NO_RESPONSES -2
|
LEDDARONE_ERR_BAD_CRC = -1,
|
||||||
#define LEDDARONE_ERR_BAD_RESPONSE -3
|
LEDDARONE_ERR_NO_RESPONSES = -2,
|
||||||
#define LEDDARONE_ERR_SHORT_RESPONSE -4
|
LEDDARONE_ERR_BAD_RESPONSE = -3,
|
||||||
#define LEDDARONE_ERR_SERIAL_PORT -5
|
LEDDARONE_ERR_SHORT_RESPONSE = -4,
|
||||||
#define LEDDARONE_ERR_NUMBER_DETECTIONS -6
|
LEDDARONE_ERR_SERIAL_PORT = -5,
|
||||||
|
LEDDARONE_ERR_NUMBER_DETECTIONS = -6
|
||||||
|
};
|
||||||
|
|
||||||
class AP_RangeFinder_LeddarOne : public AP_RangeFinder_Backend
|
class AP_RangeFinder_LeddarOne : public AP_RangeFinder_Backend
|
||||||
{
|
{
|
||||||
@ -41,14 +43,15 @@ private:
|
|||||||
bool CRC16(uint8_t *aBuffer, uint8_t aLength, bool aCheck);
|
bool CRC16(uint8_t *aBuffer, uint8_t aLength, bool aCheck);
|
||||||
|
|
||||||
// send a request message to execute ModBus function
|
// send a request message to execute ModBus function
|
||||||
int8_t send_request(void);
|
LeddarOne_Status send_request(void);
|
||||||
|
|
||||||
// parse a response message from ModBus
|
// parse a response message from ModBus
|
||||||
int8_t parse_response(void);
|
LeddarOne_Status parse_response(void);
|
||||||
|
|
||||||
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