Path: blob/master/libraries/AP_AHRS/AP_AHRS_SIM.cpp
9449 views
#include "AP_AHRS_SIM.h"12#if AP_AHRS_SIM_ENABLED34#include "AP_AHRS.h"56bool AP_AHRS_SIM::get_location(Location &loc) const7{8if (_sitl == nullptr) {9return false;10}1112const struct SITL::sitl_fdm &fdm = _sitl->state;13loc = {};14loc.lat = fdm.latitude * 1e7;15loc.lng = fdm.longitude * 1e7;16loc.alt = fdm.altitude*100;1718return true;19}2021bool AP_AHRS_SIM::wind_estimate(Vector3f &wind) const22{23if (_sitl == nullptr) {24return false;25}2627wind = _sitl->state.wind_ef;28return true;29}3031bool AP_AHRS_SIM::airspeed_EAS(float &airspeed_ret) const32{33if (_sitl == nullptr) {34return false;35}3637airspeed_ret = _sitl->state.airspeed;3839return true;40}4142bool AP_AHRS_SIM::airspeed_EAS(uint8_t index, float &airspeed_ret) const43{44return airspeed_EAS(airspeed_ret);45}4647Vector2f AP_AHRS_SIM::groundspeed_vector(void)48{49if (_sitl == nullptr) {50return Vector2f{};51}5253const struct SITL::sitl_fdm &fdm = _sitl->state;5455return Vector2f(fdm.speedN, fdm.speedE);56}5758bool AP_AHRS_SIM::get_hagl(float &height) const59{60if (_sitl == nullptr) {61return false;62}6364height = _sitl->state.altitude - AP::ahrs().get_home().alt*0.01f;6566return true;67}6869bool AP_AHRS_SIM::get_relative_position_NED_origin(Vector3p &vec) const70{71if (_sitl == nullptr) {72return false;73}7475Location loc, orgn;76if (!get_location(loc) ||77!get_origin(orgn)) {78return false;79}8081const Vector2p diff2d = orgn.get_distance_NE_postype(loc);82const struct SITL::sitl_fdm &fdm = _sitl->state;83vec = Vector3p(diff2d.x, diff2d.y,84-(fdm.altitude - orgn.alt*0.01f));8586return true;87}8889bool AP_AHRS_SIM::get_relative_position_NE_origin(Vector2p &posNE) const90{91Location loc, orgn;92if (!get_location(loc) ||93!get_origin(orgn)) {94return false;95}96posNE = orgn.get_distance_NE_postype(loc);9798return true;99}100101bool AP_AHRS_SIM::get_relative_position_D_origin(postype_t &posD) const102{103if (_sitl == nullptr) {104return false;105}106const struct SITL::sitl_fdm &fdm = _sitl->state;107Location orgn;108if (!get_origin(orgn)) {109return false;110}111posD = -(fdm.altitude - orgn.alt*0.01f);112113return true;114}115116bool AP_AHRS_SIM::get_filter_status(nav_filter_status &status) const117{118memset(&status, 0, sizeof(status));119status.flags.attitude = true;120status.flags.horiz_vel = true;121status.flags.vert_vel = true;122status.flags.horiz_pos_rel = true;123status.flags.horiz_pos_abs = true;124status.flags.vert_pos = true;125status.flags.pred_horiz_pos_rel = true;126status.flags.pred_horiz_pos_abs = true;127status.flags.using_gps = true;128129return true;130}131132void AP_AHRS_SIM::get_control_limits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const133{134// same as EKF2 for no optical flow135ekfGndSpdLimit = 400.0f;136ekfNavVelGainScaler = 1.0f;137}138139void AP_AHRS_SIM::send_ekf_status_report(GCS_MAVLINK &link) const140{141#if HAL_GCS_ENABLED142// send status report with everything looking good143const uint16_t flags =144EKF_ATTITUDE | /* Set if EKF's attitude estimate is good. | */145EKF_VELOCITY_HORIZ | /* Set if EKF's horizontal velocity estimate is good. | */146EKF_VELOCITY_VERT | /* Set if EKF's vertical velocity estimate is good. | */147EKF_POS_HORIZ_REL | /* Set if EKF's horizontal position (relative) estimate is good. | */148EKF_POS_HORIZ_ABS | /* Set if EKF's horizontal position (absolute) estimate is good. | */149EKF_POS_VERT_ABS | /* Set if EKF's vertical position (absolute) estimate is good. | */150EKF_POS_VERT_AGL | /* Set if EKF's vertical position (above ground) estimate is good. | */151//EKF_CONST_POS_MODE | /* EKF is in constant position mode and does not know it's absolute or relative position. | */152EKF_PRED_POS_HORIZ_REL | /* Set if EKF's predicted horizontal position (relative) estimate is good. | */153EKF_PRED_POS_HORIZ_ABS; /* Set if EKF's predicted horizontal position (absolute) estimate is good. | */154mavlink_msg_ekf_status_report_send(link.get_chan(), flags, 0, 0, 0, 0, 0, 0);155#endif // HAL_GCS_ENABLED156}157158bool AP_AHRS_SIM::get_origin(Location &ret) const159{160if (_sitl == nullptr) {161return false;162}163164ret = _sitl->state.home;165166return true;167}168169// return the innovations for the specified instance170// An out of range instance (eg -1) returns data for the primary instance171bool AP_AHRS_SIM::get_innovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const172{173velInnov.zero();174posInnov.zero();175magInnov.zero();176tasInnov = 0.0f;177yawInnov = 0.0f;178179return true;180}181182bool AP_AHRS_SIM::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const183{184velVar = 0;185posVar = 0;186hgtVar = 0;187magVar.zero();188tasVar = 0;189190return true;191}192193void AP_AHRS_SIM::get_results(AP_AHRS_Backend::Estimates &results)194{195if (_sitl == nullptr) {196_sitl = AP::sitl();197if (_sitl == nullptr) {198return;199}200}201202const struct SITL::sitl_fdm &fdm = _sitl->state;203const AP_InertialSensor &_ins = AP::ins();204205results.attitude_valid = true;206207// note that this result is rotated by AP_AHRS::get_quaternion208results.quaternion = fdm.quaternion;209210fdm.quaternion.rotation_matrix(results.dcm_matrix);211results.dcm_matrix = results.dcm_matrix * AP::ahrs().get_rotation_vehicle_body_to_autopilot_body();212results.dcm_matrix.to_euler(&results.roll_rad, &results.pitch_rad, &results.yaw_rad);213214results.gyro_estimate = _ins.get_gyro();215results.gyro_drift.zero();216217const Vector3f &accel = _ins.get_accel();218results.accel_ef = results.dcm_matrix * AP::ahrs().get_rotation_autopilot_body_to_vehicle_body() * accel;219220results.velocity_NED = Vector3f(fdm.speedN, fdm.speedE, fdm.speedD);221results.velocity_NED_valid = true;222223// a derivative of the vertical position in m/s which is kinematically consistent with the vertical position is required by some control loops.224// This is different to the vertical velocity from the EKF which is not always consistent with the vertical position due to the various errors that are being corrected for.225results.vert_pos_rate_D_valid = true;226results.vert_pos_rate_D = _sitl->state.speedD;227228results.location_valid = get_location(results.location);229230#if HAL_NAVEKF3_AVAILABLE231if (_sitl->odom_enable) {232// use SITL states to write body frame odometry data at 20Hz233uint32_t timeStamp_ms = AP_HAL::millis();234if (timeStamp_ms - _last_body_odm_update_ms > 50) {235const float quality = 100.0f;236const Vector3f posOffset(0.0f, 0.0f, 0.0f);237const float delTime = 0.001f * (timeStamp_ms - _last_body_odm_update_ms);238_last_body_odm_update_ms = timeStamp_ms;239timeStamp_ms -= (timeStamp_ms - _last_body_odm_update_ms)/2; // correct for first order hold average delay240Vector3f delAng = _ins.get_gyro();241242delAng *= delTime;243// rotate earth velocity into body frame and calculate delta position244Matrix3f Tbn;245Tbn.from_euler(radians(fdm.rollDeg),radians(fdm.pitchDeg),radians(fdm.yawDeg));246const Vector3f earth_vel(fdm.speedN,fdm.speedE,fdm.speedD);247const Vector3f delPos = Tbn.transposed() * (earth_vel * delTime);248// write to EKF249EKF3.writeBodyFrameOdom(quality, delPos, delAng, delTime, timeStamp_ms, 0, posOffset);250}251}252#endif // HAL_NAVEKF3_AVAILABLE253}254255#endif // AP_AHRS_SIM_ENABLED256257258