SITL: expire stationary sim_adsb targets after an hour

This commit is contained in:
Tom Pittenger 2021-11-18 14:25:11 -08:00 committed by Peter Barker
parent ec5820044b
commit 659c35d1a9
2 changed files with 6 additions and 0 deletions

View File

@ -55,14 +55,19 @@ void ADSB_Vehicle::update(float delta_t)
type = (ADSB_EMITTER_TYPE)(rand() % (ADSB_EMITTER_TYPE_POINT_OBSTACLE + 1));
// don't allow surface emitters to move
if (type == ADSB_EMITTER_TYPE_POINT_OBSTACLE) {
stationary_object_created_ms = AP_HAL::millis64();
velocity_ef.zero();
} else {
stationary_object_created_ms = 0;
velocity_ef.x = Aircraft::rand_normal(vel_min, vel_max);
velocity_ef.y = Aircraft::rand_normal(vel_min, vel_max);
if (type < ADSB_EMITTER_TYPE_EMERGENCY_SURFACE) {
velocity_ef.z = Aircraft::rand_normal(-3, 3);
}
}
} else if (stationary_object_created_ms > 0 && AP_HAL::millis64() - stationary_object_created_ms > AP_MSEC_PER_HOUR) {
// regenerate stationary objects so we don't randomly fill up the screen with them over time
initialised = false;
}
position += velocity_ef * delta_t;

View File

@ -47,6 +47,7 @@ private:
uint32_t ICAO_address;
bool initialised = false;
ADSB_EMITTER_TYPE type;
uint64_t stationary_object_created_ms; // allows expiring of slow/stationary objects
};
class ADSB {