mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: support MAV_CMD_EXTERNAL_WIND_ESTIMATE
This commit is contained in:
parent
40e367e14f
commit
3344dba627
|
@ -131,6 +131,12 @@ public:
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED
|
||||||
|
void set_external_wind_estimate(float speed, float direction) {
|
||||||
|
dcm.set_external_wind_estimate(speed, direction);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// return the parameter AHRS_WIND_MAX in metres per second
|
// return the parameter AHRS_WIND_MAX in metres per second
|
||||||
uint8_t get_max_wind() const {
|
uint8_t get_max_wind() const {
|
||||||
return _wind_max;
|
return _wind_max;
|
||||||
|
|
|
@ -1028,6 +1028,13 @@ void AP_AHRS_DCM::estimate_wind(void)
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED
|
||||||
|
void AP_AHRS_DCM::set_external_wind_estimate(float speed, float direction) {
|
||||||
|
_wind.x = -cosf(radians(direction)) * speed;
|
||||||
|
_wind.y = -sinf(radians(direction)) * speed;
|
||||||
|
_wind.z = 0;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// return our current position estimate using
|
// return our current position estimate using
|
||||||
// dead-reckoning or GPS
|
// dead-reckoning or GPS
|
||||||
|
|
|
@ -78,6 +78,8 @@ public:
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void set_external_wind_estimate(float speed, float direction);
|
||||||
|
|
||||||
// return an airspeed estimate if available. return true
|
// return an airspeed estimate if available. return true
|
||||||
// if we have an estimate
|
// if we have an estimate
|
||||||
bool airspeed_estimate(float &airspeed_ret) const override;
|
bool airspeed_estimate(float &airspeed_ret) const override;
|
||||||
|
|
|
@ -41,3 +41,6 @@
|
||||||
#define AP_AHRS_POSITION_RESET_ENABLED (BOARD_FLASH_SIZE>1024 && AP_AHRS_ENABLED)
|
#define AP_AHRS_POSITION_RESET_ENABLED (BOARD_FLASH_SIZE>1024 && AP_AHRS_ENABLED)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED
|
||||||
|
#define AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED (BOARD_FLASH_SIZE>1024 && AP_AHRS_DCM_ENABLED)
|
||||||
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue