mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
SITL: add apparent wind sensor support
This commit is contained in:
parent
51b54d3740
commit
2764126a1c
@ -384,6 +384,9 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
|
||||
// copy rangefinder
|
||||
memcpy(fdm.rangefinder_m, rangefinder_m, sizeof(fdm.rangefinder_m));
|
||||
|
||||
fdm.wind_vane_apparent.direction = wind_vane_apparent.direction;
|
||||
fdm.wind_vane_apparent.speed = wind_vane_apparent.speed;
|
||||
|
||||
if (is_smoothed) {
|
||||
fdm.xAccel = smoothing.accel_body.x;
|
||||
fdm.yAccel = smoothing.accel_body.y;
|
||||
|
@ -185,6 +185,12 @@ protected:
|
||||
// Rangefinder
|
||||
float rangefinder_m[RANGEFINDER_MAX_INSTANCES];
|
||||
|
||||
// Windvane apparent wind
|
||||
struct {
|
||||
float speed;
|
||||
float direction;
|
||||
} wind_vane_apparent;
|
||||
|
||||
// Wind Turbulence simulated Data
|
||||
float turbulence_azimuth = 0.0f;
|
||||
float turbulence_horizontal_speed = 0.0f; // m/s
|
||||
|
@ -70,6 +70,11 @@ struct sitl_fdm {
|
||||
} scanner;
|
||||
|
||||
float rangefinder_m[RANGEFINDER_MAX_INSTANCES];
|
||||
|
||||
struct {
|
||||
float speed;
|
||||
float direction;
|
||||
} wind_vane_apparent;
|
||||
};
|
||||
|
||||
// number of rc output channels
|
||||
@ -403,6 +408,9 @@ public:
|
||||
// get the rangefinder reading for the desired instance, returns -1 for no data
|
||||
float get_rangefinder(uint8_t instance);
|
||||
|
||||
// get the apparent wind speed and direction as set by external physics backend
|
||||
float get_apparent_wind_dir(){return state.wind_vane_apparent.direction;}
|
||||
float get_apparent_wind_spd(){return state.wind_vane_apparent.speed;}
|
||||
};
|
||||
|
||||
} // namespace SITL
|
||||
|
Loading…
Reference in New Issue
Block a user