ekf2: define max number of range finders seperate from max number of mutli uORB topics

Signed-off-by: CarlOlsson <carlolsson.co@gmail.com>
This commit is contained in:
CarlOlsson 2020-02-05 07:12:54 +01:00 committed by Beat Küng
parent 36f836be79
commit 37db7d3bba
1 changed files with 3 additions and 2 deletions

View File

@ -253,7 +253,8 @@ private:
bool _callback_registered{false};
// because we can have several distance sensor instances with different orientations
uORB::Subscription _range_finder_subs[ORB_MULTI_MAX_INSTANCES] {{ORB_ID(distance_sensor), 0}, {ORB_ID(distance_sensor), 1}, {ORB_ID(distance_sensor), 2}, {ORB_ID(distance_sensor), 3}};
static constexpr int MAX_RNG_SENSOR_COUNT = 4;
uORB::Subscription _range_finder_subs[MAX_RNG_SENSOR_COUNT] {{ORB_ID(distance_sensor), 0}, {ORB_ID(distance_sensor), 1}, {ORB_ID(distance_sensor), 2}, {ORB_ID(distance_sensor), 3}};
int _range_finder_sub_index = -1; // index for downward-facing range finder subscription
// because we can have multiple GPS instances
@ -1748,7 +1749,7 @@ void Ekf2::resetPreFlightChecks()
int Ekf2::getRangeSubIndex()
{
for (unsigned i = 0; i < ORB_MULTI_MAX_INSTANCES; i++) {
for (unsigned i = 0; i < MAX_RNG_SENSOR_COUNT; i++) {
distance_sensor_s report{};
if (_range_finder_subs[i].update(&report)) {