Skip to content

Commit

Permalink
support MAV_CMD_EXTERNAL_WIND_ESTIMATE (move if)
Browse files Browse the repository at this point in the history
  • Loading branch information
python36 committed Aug 20, 2024
1 parent ec5c124 commit c57caf4
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_AHRS/AP_AHRS.h
Original file line number Diff line number Diff line change
Expand Up @@ -131,11 +131,11 @@ class AP_AHRS {
#endif
}

void external_wind_estimate(float speed, float direction) {
#if AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED
void external_wind_estimate(float speed, float direction) {
dcm.external_wind_estimate(speed, direction);
#endif
}
#endif

// return the parameter AHRS_WIND_MAX in metres per second
uint8_t get_max_wind() const {
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_AHRS/AP_AHRS_DCM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1028,6 +1028,7 @@ void AP_AHRS_DCM::estimate_wind(void)
#endif
}

#ifdef AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED
void AP_AHRS_DCM::external_wind_estimate(float speed, float direction) {
Vector3f wind = Vector3f();
wind.z = 0;
Expand All @@ -1037,6 +1038,7 @@ void AP_AHRS_DCM::external_wind_estimate(float speed, float direction) {

_wind = wind;
}
#endif

// return our current position estimate using
// dead-reckoning or GPS
Expand Down

0 comments on commit c57caf4

Please sign in to comment.