mirror of https://github.com/ArduPilot/ardupilot
AP_ESC_Telem: fix out of bound access
This commit is contained in:
parent
6e9e529967
commit
2d0e359065
|
@ -56,7 +56,7 @@ public:
|
||||||
|
|
||||||
// return the last time telemetry data was received in ms for the given ESC or 0 if never
|
// return the last time telemetry data was received in ms for the given ESC or 0 if never
|
||||||
uint32_t get_last_telem_data_ms(uint8_t esc_index) const {
|
uint32_t get_last_telem_data_ms(uint8_t esc_index) const {
|
||||||
if (esc_index > ESC_TELEM_MAX_ESCS) return 0;
|
if (esc_index >= ESC_TELEM_MAX_ESCS) {return 0;}
|
||||||
return _telem_data[esc_index].last_update_ms;
|
return _telem_data[esc_index].last_update_ms;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue