123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531 |
- #include "AP_AHRS.h"
- #include "AP_AHRS_View.h"
- #include <AP_HAL/AP_HAL.h>
- #include <AP_Logger/AP_Logger.h>
- #include <AP_GPS/AP_GPS.h>
- #include <AP_Baro/AP_Baro.h>
- #include <AP_NMEA_Output/AP_NMEA_Output.h>
- extern const AP_HAL::HAL& hal;
- const AP_Param::GroupInfo AP_AHRS::var_info[] = {
-
-
-
-
-
-
-
- AP_GROUPINFO("GPS_GAIN", 2, AP_AHRS, gps_gain, 1.0f),
-
-
-
-
-
- AP_GROUPINFO("GPS_USE", 3, AP_AHRS, _gps_use, 1),
-
-
-
-
-
-
- AP_GROUPINFO("YAW_P", 4, AP_AHRS, _kp_yaw, 0.2f),
-
-
-
-
-
-
- AP_GROUPINFO("RP_P", 5, AP_AHRS, _kp, 0.2f),
-
-
-
-
-
-
-
- AP_GROUPINFO("WIND_MAX", 6, AP_AHRS, _wind_max, 0.0f),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("TRIM", 8, AP_AHRS, _trim, 0),
-
-
-
-
-
- AP_GROUPINFO("ORIENTATION", 9, AP_AHRS, _board_orientation, 0),
-
-
-
-
-
-
- AP_GROUPINFO("COMP_BETA", 10, AP_AHRS, beta, 0.1f),
-
-
-
-
-
-
- AP_GROUPINFO("GPS_MINSATS", 11, AP_AHRS, _gps_minsats, 6),
-
-
-
- #if AP_AHRS_NAVEKF_AVAILABLE
-
-
-
-
-
- AP_GROUPINFO("EKF_TYPE", 14, AP_AHRS, _ekf_type, 2),
- #endif
-
-
-
-
-
-
-
- AP_GROUPINFO("CUSTOM_ROLL", 15, AP_AHRS, _custom_roll, 0),
-
-
-
-
-
-
-
- AP_GROUPINFO("CUSTOM_PIT", 16, AP_AHRS, _custom_pitch, 0),
-
-
-
-
-
-
-
- AP_GROUPINFO("CUSTOM_YAW", 17, AP_AHRS, _custom_yaw, 0),
- AP_GROUPEND
- };
- void AP_AHRS::init()
- {
- update_orientation();
- #if !HAL_MINIMIZE_FEATURES && AP_AHRS_NAVEKF_AVAILABLE
- _nmea_out = AP_NMEA_Output::probe();
- #endif
- }
- Vector3f AP_AHRS::get_gyro_latest(void) const
- {
- const uint8_t primary_gyro = get_primary_gyro_index();
- return AP::ins().get_gyro(primary_gyro) + get_gyro_drift();
- }
- bool AP_AHRS::airspeed_estimate(float *airspeed_ret) const
- {
- if (airspeed_sensor_enabled()) {
- *airspeed_ret = _airspeed->get_airspeed();
- if (_wind_max > 0 && AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
-
-
- const float gnd_speed = AP::gps().ground_speed();
- float true_airspeed = *airspeed_ret * get_EAS2TAS();
- true_airspeed = constrain_float(true_airspeed,
- gnd_speed - _wind_max,
- gnd_speed + _wind_max);
- *airspeed_ret = true_airspeed / get_EAS2TAS();
- }
- return true;
- }
- return false;
- }
- void AP_AHRS::set_trim(const Vector3f &new_trim)
- {
- Vector3f trim;
- trim.x = constrain_float(new_trim.x, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(AP_AHRS_TRIM_LIMIT));
- trim.y = constrain_float(new_trim.y, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(AP_AHRS_TRIM_LIMIT));
- _trim.set_and_save(trim);
- }
- void AP_AHRS::add_trim(float roll_in_radians, float pitch_in_radians, bool save_to_eeprom)
- {
- Vector3f trim = _trim.get();
-
- trim.x = constrain_float(trim.x + roll_in_radians, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(AP_AHRS_TRIM_LIMIT));
- trim.y = constrain_float(trim.y + pitch_in_radians, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(AP_AHRS_TRIM_LIMIT));
-
- _trim.set(trim);
-
- if( save_to_eeprom ) {
- _trim.save();
- }
- }
- void AP_AHRS::update_orientation()
- {
- const enum Rotation orientation = (enum Rotation)_board_orientation.get();
- if (orientation != ROTATION_CUSTOM) {
- AP::ins().set_board_orientation(orientation);
- if (_compass != nullptr) {
- _compass->set_board_orientation(orientation);
- }
- } else {
- _custom_rotation.from_euler(radians(_custom_roll), radians(_custom_pitch), radians(_custom_yaw));
- AP::ins().set_board_orientation(orientation, &_custom_rotation);
- if (_compass != nullptr) {
- _compass->set_board_orientation(orientation, &_custom_rotation);
- }
- }
- }
- Vector2f AP_AHRS::groundspeed_vector(void)
- {
-
- Vector2f gndVelADS;
- Vector2f gndVelGPS;
- float airspeed = 0;
- const bool gotAirspeed = airspeed_estimate_true(&airspeed);
- const bool gotGPS = (AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D);
- if (gotAirspeed) {
- const Vector3f wind = wind_estimate();
- const Vector2f wind2d(wind.x, wind.y);
- const Vector2f airspeed_vector(_cos_yaw * airspeed, _sin_yaw * airspeed);
- gndVelADS = airspeed_vector + wind2d;
- }
-
- if (gotGPS) {
- const float cog = radians(AP::gps().ground_course_cd()*0.01f);
- gndVelGPS = Vector2f(cosf(cog), sinf(cog)) * AP::gps().ground_speed();
- }
-
- if (gotAirspeed && gotGPS) {
-
-
-
-
-
-
-
-
-
- const float alpha = 1.0f - beta;
-
- _lp = gndVelGPS * beta + _lp * alpha;
-
- _hp = (gndVelADS - _lastGndVelADS) + _hp * alpha;
-
- _lastGndVelADS = gndVelADS;
-
- return _hp + _lp;
- }
-
- if (gotAirspeed && !gotGPS) {
- return gndVelADS;
- }
-
- if (!gotAirspeed && gotGPS) {
- return gndVelGPS;
- }
- if (airspeed > 0) {
-
-
-
- Vector2f ret(cosf(yaw), sinf(yaw));
- ret *= airspeed;
-
- const Vector3f wind = wind_estimate();
- ret.x += wind.x;
- ret.y += wind.y;
- return ret;
- }
- return Vector2f(0.0f, 0.0f);
- }
- void AP_AHRS::calc_trig(const Matrix3f &rot,
- float &cr, float &cp, float &cy,
- float &sr, float &sp, float &sy) const
- {
- Vector2f yaw_vector(rot.a.x, rot.b.x);
- if (fabsf(yaw_vector.x) > 0 ||
- fabsf(yaw_vector.y) > 0) {
- yaw_vector.normalize();
- }
- sy = constrain_float(yaw_vector.y, -1.0f, 1.0f);
- cy = constrain_float(yaw_vector.x, -1.0f, 1.0f);
-
- if (yaw_vector.is_inf() || yaw_vector.is_nan()) {
- sy = 0.0f;
- cy = 1.0f;
- }
- const float cx2 = rot.c.x * rot.c.x;
- if (cx2 >= 1.0f) {
- cp = 0;
- cr = 1.0f;
- } else {
- cp = safe_sqrt(1 - cx2);
- cr = rot.c.z / cp;
- }
- cp = constrain_float(cp, 0.0f, 1.0f);
- cr = constrain_float(cr, -1.0f, 1.0f);
- sp = -rot.c.x;
- if (!is_zero(cp)) {
- sr = rot.c.y / cp;
- }
- if (is_zero(cp) || isinf(cr) || isnan(cr) || isinf(sr) || isnan(sr)) {
- float r, p, y;
- rot.to_euler(&r, &p, &y);
- cr = cosf(r);
- sr = sinf(r);
- }
- }
- void AP_AHRS::update_trig(void)
- {
- if (_last_trim != _trim.get()) {
- _last_trim = _trim.get();
- _rotation_autopilot_body_to_vehicle_body.from_euler(_last_trim.x, _last_trim.y, 0.0f);
- _rotation_vehicle_body_to_autopilot_body = _rotation_autopilot_body_to_vehicle_body.transposed();
- }
- calc_trig(get_rotation_body_to_ned(),
- _cos_roll, _cos_pitch, _cos_yaw,
- _sin_roll, _sin_pitch, _sin_yaw);
- }
- void AP_AHRS::update_cd_values(void)
- {
- roll_sensor = degrees(roll) * 100;
- pitch_sensor = degrees(pitch) * 100;
- yaw_sensor = degrees(yaw) * 100;
- if (yaw_sensor < 0)
- yaw_sensor += 36000;
- }
- AP_AHRS_View *AP_AHRS::create_view(enum Rotation rotation, float pitch_trim_deg)
- {
- if (_view != nullptr) {
-
- return nullptr;
- }
- _view = new AP_AHRS_View(*this, rotation, pitch_trim_deg);
- return _view;
- }
- void AP_AHRS::update_AOA_SSA(void)
- {
- #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
- const uint32_t now = AP_HAL::millis();
- if (now - _last_AOA_update_ms < 50) {
-
- return;
- }
- _last_AOA_update_ms = now;
-
- Vector3f aoa_velocity, aoa_wind;
-
- if (get_velocity_NED(aoa_velocity) == false) {
- return;
- }
- aoa_wind = wind_estimate();
-
- const Matrix3f &rot = get_rotation_body_to_ned();
- aoa_velocity = rot.mul_transpose(aoa_velocity);
- aoa_wind = rot.mul_transpose(aoa_wind);
-
- aoa_velocity = aoa_velocity - aoa_wind;
- const float vel_len = aoa_velocity.length();
-
- if (vel_len < 2.0) {
- _AOA = 0;
- _SSA = 0;
- return;
- }
-
- if (aoa_velocity.x > 0) {
- _AOA = degrees(atanf(aoa_velocity.z / aoa_velocity.x));
- } else {
- _AOA = 0;
- }
- _SSA = degrees(safe_asin(aoa_velocity.y / vel_len));
- #endif
- }
- float AP_AHRS::getAOA(void)
- {
- update_AOA_SSA();
- return _AOA;
- }
- float AP_AHRS::getSSA(void)
- {
- update_AOA_SSA();
- return _SSA;
- }
- Vector2f AP_AHRS::rotate_earth_to_body2D(const Vector2f &ef) const
- {
- return Vector2f(ef.x * _cos_yaw + ef.y * _sin_yaw,
- -ef.x * _sin_yaw + ef.y * _cos_yaw);
- }
- Vector2f AP_AHRS::rotate_body_to_earth2D(const Vector2f &bf) const
- {
- return Vector2f(bf.x * _cos_yaw - bf.y * _sin_yaw,
- bf.x * _sin_yaw + bf.y * _cos_yaw);
- }
- void AP_AHRS::Log_Write_Home_And_Origin()
- {
- AP_Logger *logger = AP_Logger::get_singleton();
- if (logger == nullptr) {
- return;
- }
- #if AP_AHRS_NAVEKF_AVAILABLE
- Location ekf_orig;
- if (get_origin(ekf_orig)) {
- logger->Write_Origin(LogOriginType::ekf_origin, ekf_orig);
- }
- #endif
- if (home_is_set()) {
- logger->Write_Origin(LogOriginType::ahrs_home, _home);
- }
- }
- float AP_AHRS::get_EAS2TAS(void) const {
- return AP::baro().get_EAS2TAS();
- }
- void AP_AHRS::update_nmea_out()
- {
- #if !HAL_MINIMIZE_FEATURES && AP_AHRS_NAVEKF_AVAILABLE
- if (_nmea_out != nullptr) {
- _nmea_out->update();
- }
- #endif
- }
- AP_AHRS *AP_AHRS::_singleton;
- namespace AP {
- AP_AHRS &ahrs()
- {
- return *AP_AHRS::get_singleton();
- }
- }
|