mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
SITL: SIM_Aircraft: add rangefinder array
This commit is contained in:
parent
e18c195df4
commit
16a9506cf2
@ -83,6 +83,11 @@ Aircraft::Aircraft(const char *frame_str) :
|
||||
}
|
||||
|
||||
terrain = &AP::terrain();
|
||||
|
||||
// init rangefinder array to -1 to signify no data
|
||||
for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++){
|
||||
rangefinder_m[i] = -1.0f;
|
||||
}
|
||||
}
|
||||
|
||||
void Aircraft::set_start_location(const Location &start_loc, const float start_yaw)
|
||||
@ -374,6 +379,9 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
|
||||
fdm.scanner.points = scanner.points;
|
||||
fdm.scanner.ranges = scanner.ranges;
|
||||
|
||||
// copy rangefinder
|
||||
memcpy(fdm.rangefinder_m, rangefinder_m, sizeof(fdm.rangefinder_m));
|
||||
|
||||
if (is_smoothed) {
|
||||
fdm.xAccel = smoothing.accel_body.x;
|
||||
fdm.yAccel = smoothing.accel_body.y;
|
||||
|
@ -181,7 +181,10 @@ protected:
|
||||
struct vector3f_array points;
|
||||
struct float_array ranges;
|
||||
} scanner;
|
||||
|
||||
|
||||
// Rangefinder
|
||||
float rangefinder_m[RANGEFINDER_MAX_INSTANCES];
|
||||
|
||||
// Wind Turbulence simulated Data
|
||||
float turbulence_azimuth = 0.0f;
|
||||
float turbulence_horizontal_speed = 0.0f; // m/s
|
||||
|
Loading…
Reference in New Issue
Block a user