SITL: remove unneeded circular rangfinder include

This commit is contained in:
Peter Barker 2022-10-02 19:21:54 +11:00 committed by Andrew Tridgell
parent 23ec7a15b2
commit 6be8d9cd06
5 changed files with 7 additions and 7 deletions

View File

@ -334,7 +334,7 @@ void AirSim::recv_fdm(const sitl_input& input)
}
// Update Rangefinder data, max sensors limit as defined
uint8_t rng_sensor_count = MIN(state.rng.rng_distances.length, RANGEFINDER_MAX_INSTANCES);
uint8_t rng_sensor_count = MIN(state.rng.rng_distances.length, ARRAY_SIZE(rangefinder_m));
for (uint8_t i=0; i<rng_sensor_count; i++) {
rangefinder_m[i] = state.rng.rng_distances.data[i];
}

View File

@ -70,7 +70,7 @@ Aircraft::Aircraft(const char *frame_str) :
}
// init rangefinder array to -1 to signify no data
for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++){
for (uint8_t i = 0; i < ARRAY_SIZE(rangefinder_m); i++){
rangefinder_m[i] = -1.0f;
}
}
@ -954,7 +954,7 @@ void Aircraft::update_external_payload(const struct sitl_input &input)
{
const float range = rangefinder_range();
for (uint8_t i=0; i<RANGEFINDER_MAX_INSTANCES; i++) {
for (uint8_t i=0; i<ARRAY_SIZE(rangefinder_m); i++) {
rangefinder_m[i] = range;
}
}

View File

@ -205,7 +205,7 @@ protected:
} scanner;
// Rangefinder
float rangefinder_m[RANGEFINDER_MAX_INSTANCES];
float rangefinder_m[SITL_NUM_RANGEFINDERS];
// Windvane apparent wind
struct {

View File

@ -663,7 +663,7 @@ Vector3f SIM::convert_earth_frame(const Matrix3f &dcm, const Vector3f &gyro)
// get the rangefinder reading for the desired rotation, returns -1 for no data
float SIM::get_rangefinder(uint8_t instance) {
if (instance < RANGEFINDER_MAX_INSTANCES) {
if (instance < ARRAY_SIZE(state.rangefinder_m)) {
return state.rangefinder_m[instance];
}
return -1;

View File

@ -26,7 +26,6 @@
#include "SIM_IntelligentEnergy24.h"
#include "SIM_Ship.h"
#include "SIM_GPS.h"
#include <AP_RangeFinder/AP_RangeFinder.h>
namespace SITL {
@ -78,7 +77,8 @@ struct sitl_fdm {
struct float_array ranges;
} scanner;
float rangefinder_m[RANGEFINDER_MAX_INSTANCES];
#define SITL_NUM_RANGEFINDERS 10
float rangefinder_m[SITL_NUM_RANGEFINDERS];
float airspeed_raw_pressure[AIRSPEED_MAX_SENSORS];
struct {