mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_RangeFinder: To define the OK status to LEDDARONE status.
This commit is contained in:
parent
94f83c3e78
commit
d58c193c90
@ -54,7 +54,7 @@ bool AP_RangeFinder_LeddarOne::get_reading(uint16_t &reading_cm)
|
||||
}
|
||||
|
||||
// send a request message for Modbus function 4
|
||||
if (send_request() < 0) {
|
||||
if (send_request() != LEDDARONE_OK) {
|
||||
// TODO: handle LEDDARONE_ERR_SERIAL_PORT
|
||||
return false;
|
||||
}
|
||||
@ -162,7 +162,7 @@ int8_t AP_RangeFinder_LeddarOne::send_request(void)
|
||||
}
|
||||
uart->flush();
|
||||
|
||||
return 0;
|
||||
return LEDDARONE_OK;
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -11,6 +11,7 @@
|
||||
#define LEDDARONE_DEFAULT_ADDRESS 0x01
|
||||
|
||||
// error codes
|
||||
#define LEDDARONE_OK 0
|
||||
#define LEDDARONE_ERR_BAD_CRC -1
|
||||
#define LEDDARONE_ERR_NO_RESPONSES -2
|
||||
#define LEDDARONE_ERR_BAD_RESPONSE -3
|
||||
|
Loading…
Reference in New Issue
Block a user