AP_Proximity: correct missing use of PROXIMITY_MAX_DIRECTION

This commit is contained in:
khancyr 2017-07-14 14:52:32 +02:00 committed by Francisco Ferreira
parent 40b860e240
commit f60e7df309
1 changed files with 2 additions and 2 deletions

View File

@ -113,8 +113,8 @@ bool AP_Proximity_Backend::get_horizontal_distances(AP_Proximity::Proximity_Dist
for (uint8_t i=0; i<_num_sectors; i++) {
if (_distance_valid[i]) {
// convert angle to orientation
int16_t orientation = _angle[i] / 45;
if ((orientation >= 0) && (orientation < 8) && (_distance[i] < prx_dist_array.distance[orientation])) {
int16_t orientation = static_cast<int16_t>(_angle[i] * (PROXIMITY_MAX_DIRECTION / 360.0f));
if ((orientation >= 0) && (orientation < PROXIMITY_MAX_DIRECTION) && (_distance[i] < prx_dist_array.distance[orientation])) {
prx_dist_array.distance[orientation] = _distance[i];
dist_set[orientation] = true;
}