Path: blob/master/libraries/AP_AHRS/AP_AHRS_Logging.cpp
9507 views
#include <AP_Logger/AP_Logger_config.h>12#if HAL_LOGGING_ENABLED34#include "AP_AHRS.h"5#include <AP_Logger/AP_Logger.h>67#include <AC_AttitudeControl/AC_AttitudeControl.h>8#include <AC_AttitudeControl/AC_PosControl.h>91011// Write an AHRS2 packet12void AP_AHRS::Write_AHRS2() const13{14Vector3f euler;15Location loc;16Quaternion quat;17if (!get_secondary_attitude(euler) || !get_secondary_position(loc) || !get_secondary_quaternion(quat)) {18return;19}20float alt;21if (!loc.initialised() || !loc.get_alt_m(Location::AltFrame::ABSOLUTE, alt)) {22alt = AP_Logger::quiet_nanf();23}24const struct log_AHRS pkt{25LOG_PACKET_HEADER_INIT(LOG_AHR2_MSG),26time_us : AP_HAL::micros64(),27roll : (int16_t)(degrees(euler.x)*100),28pitch : (int16_t)(degrees(euler.y)*100),29yaw : (uint16_t)(wrap_360_cd(degrees(euler.z)*100)),30alt : alt,31lat : loc.lat,32lng : loc.lng,33q1 : quat.q1,34q2 : quat.q2,35q3 : quat.q3,36q4 : quat.q4,37};38AP::logger().WriteBlock(&pkt, sizeof(pkt));39}4041// Write AOA and SSA42void AP_AHRS::Write_AOA_SSA(void) const43{44const struct log_AOA_SSA aoa_ssa{45LOG_PACKET_HEADER_INIT(LOG_AOA_SSA_MSG),46time_us : AP_HAL::micros64(),47AOA : getAOA(),48SSA : getSSA()49};5051AP::logger().WriteBlock(&aoa_ssa, sizeof(aoa_ssa));52}5354// Write an attitude packet, targets in degrees55void AP_AHRS::Write_Attitude(const Vector3f &targets) const56{57const struct log_Attitude pkt{58LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),59time_us : AP_HAL::micros64(),60control_roll : targets.x,61roll : degrees(roll),62control_pitch : targets.y,63pitch : degrees(pitch),64control_yaw : wrap_360(targets.z),65yaw : wrap_360(degrees(yaw)),66active : uint8_t(active_EKF_type()),67};68AP::logger().WriteBlock(&pkt, sizeof(pkt));69}7071void AP_AHRS::Write_Origin(LogOriginType origin_type, const Location &loc) const72{73int32_t alt_cm;74if (!loc.initialised() || !loc.get_alt_cm(Location::AltFrame::ABSOLUTE, alt_cm)) {75alt_cm = 0;76}77const struct log_ORGN pkt{78LOG_PACKET_HEADER_INIT(LOG_ORGN_MSG),79time_us : AP_HAL::micros64(),80origin_type : (uint8_t)origin_type,81latitude : loc.lat,82longitude : loc.lng,83altitude : alt_cm84};85AP::logger().WriteBlock(&pkt, sizeof(pkt));86}8788// Write a POS packet89void AP_AHRS::Write_POS() const90{91Location loc;92if (!get_location(loc)) {93return;94}95float home;96AP::ahrs().get_relative_position_D_home(home);9798const auto nanf = AP_Logger::quiet_nanf();99float origin_pos_up;100if (get_relative_position_D_origin_float(origin_pos_up)) {101origin_pos_up *= -1; // down -> up102} else {103origin_pos_up = nanf;104}105float alt;106if (!loc.get_alt_m(Location::AltFrame::ABSOLUTE, alt)) {107alt = nanf;108}109const struct log_POS pkt{110LOG_PACKET_HEADER_INIT(LOG_POS_MSG),111time_us : AP_HAL::micros64(),112lat : loc.lat,113lng : loc.lng,114alt : alt,115rel_home_alt : -home,116rel_origin_alt : origin_pos_up,117};118AP::logger().WriteBlock(&pkt, sizeof(pkt));119}120121// Write a packet for video stabilisation122void AP_AHRS::write_video_stabilisation() const123{124Quaternion current_attitude;125get_quat_body_to_ned(current_attitude);126Vector3f accel = get_accel() - get_accel_bias();127const struct log_Video_Stabilisation pkt {128LOG_PACKET_HEADER_INIT(LOG_VIDEO_STABILISATION_MSG),129time_us : AP_HAL::micros64(),130gyro_x : state.gyro_estimate.x,131gyro_y : state.gyro_estimate.y,132gyro_z : state.gyro_estimate.z,133accel_x : accel.x,134accel_y : accel.y,135accel_z : accel.z,136Q1 : current_attitude.q1,137Q2 : current_attitude.q2,138Q3 : current_attitude.q3,139Q4 : current_attitude.q4,140};141AP::logger().WriteBlock(&pkt, sizeof(pkt));142}143144// Write an attitude view packet, targets in degrees145void AP_AHRS_View::Write_AttitudeView(const Vector3f &targets) const146{147const struct log_Attitude pkt{148LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),149time_us : AP_HAL::micros64(),150control_roll : targets.x,151roll : degrees(roll),152control_pitch : targets.y,153pitch : degrees(pitch),154control_yaw : wrap_360(targets.z),155yaw : wrap_360(degrees(yaw)),156active : uint8_t(AP::ahrs().active_EKF_type()),157};158AP::logger().WriteBlock(&pkt, sizeof(pkt));159}160161#endif // HAL_LOGGING_ENABLED162163164