diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 46ff0da4fd..4f7f9c2883 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -279,6 +279,9 @@ void Plane::update_logging1(void) if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_IMU)) Log_Write_IMU(); + + if (should_log(MASK_LOG_ATTITUDE_MED)) + Log_Write_AOA_SSA(); } /* diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 4bdcc0890c..c5dfec620e 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -121,6 +121,15 @@ void Plane::send_attitude(mavlink_channel_t chan) omega.z); } +void Plane::send_aoa_ssa(mavlink_channel_t chan) +{ + mavlink_msg_aoa_ssa_send( + chan, + micros(), + ahrs.getAOA(), + ahrs.getSSA()); +} + #if GEOFENCE_ENABLED == ENABLED void Plane::send_fence_status(mavlink_channel_t chan) { @@ -687,6 +696,10 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id) case MSG_BATTERY_STATUS: send_battery_status(plane.battery); break; + case MSG_AOA_SSA: + CHECK_PAYLOAD_SIZE(AOA_SSA); + plane.send_aoa_ssa(chan); + break; } return true; } @@ -873,6 +886,8 @@ GCS_MAVLINK_Plane::data_stream_send(void) send_message(MSG_ATTITUDE); send_message(MSG_SIMSTATE); send_message(MSG_RPM); + send_message(MSG_AOA_SSA); + if (plane.control_mode != MANUAL) { send_message(MSG_PID_TUNING); } diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index a7f23af2cd..e892d021fa 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -466,6 +466,12 @@ void Plane::Log_Write_Airspeed(void) DataFlash.Log_Write_Airspeed(airspeed); } +// Write a AOA and SSA packet +void Plane::Log_Write_AOA_SSA(void) +{ + DataFlash.Log_Write_AOA_SSA(ahrs); +} + // log ahrs home and EKF origin to dataflash void Plane::Log_Write_Home_And_Origin() { @@ -503,6 +509,8 @@ const struct LogStructure Plane::log_structure[] = { "STAT", "QBfBBBBBB", "TimeUS,isFlying,isFlyProb,Armed,Safety,Crash,Still,Stage,Hit" }, { LOG_QTUN_MSG, sizeof(QuadPlane::log_QControl_Tuning), "QTUN", "Qffffhhfffff", "TimeUS,AngBst,ThrOut,DAlt,Alt,DCRt,CRt,DVx,DVy,DAx,DAy,TMix" }, + { LOG_AOA_SSA_MSG, sizeof(log_AOA_SSA), + "AOA", "Qff", "TimeUS,AOA,SSA" }, #if OPTFLOW == ENABLED { LOG_OPTFLOW_MSG, sizeof(log_Optflow), "OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY" }, diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 4247657541..7610fd7d1f 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -810,6 +810,9 @@ private: void send_rpm(mavlink_channel_t chan); void send_rangefinder(mavlink_channel_t chan); void send_current_waypoint(mavlink_channel_t chan); + + void send_aoa_ssa(mavlink_channel_t chan); + bool telemetry_delayed(mavlink_channel_t chan); void gcs_send_message(enum ap_message id); void gcs_send_mission_item_reached_message(uint16_t mission_index); @@ -838,6 +841,7 @@ private: void Log_Write_Airspeed(void); void Log_Write_Home_And_Origin(); void Log_Write_Vehicle_Startup_Messages(); + void Log_Write_AOA_SSA(); void Log_Read(uint16_t log_num, int16_t start_page, int16_t end_page); void start_logging();