Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Blimp/Log.cpp
Views: 1798
#include "Blimp.h"12#if HAL_LOGGING_ENABLED34// Code to Write and Read packets from AP_Logger log memory5// Code to interact with the user to dump or erase logs67struct PACKED log_FINI {8LOG_PACKET_HEADER;9uint64_t time_us;10float Right;11float Front;12float Down;13float Yaw;14};1516struct PACKED log_FINO {17LOG_PACKET_HEADER;18uint64_t time_us;19float Fin1_Amp;20float Fin1_Off;21float Fin2_Amp;22float Fin2_Off;23float Fin3_Amp;24float Fin3_Off;25float Fin4_Amp;26float Fin4_Off;27};2829//Write a fin input packet30void Blimp::Write_FINI(float right, float front, float down, float yaw)31{32const struct log_FINI pkt {33LOG_PACKET_HEADER_INIT(LOG_FINI_MSG),34time_us : AP_HAL::micros64(),35Right : right,36Front : front,37Down : down,38Yaw : yaw39};40logger.WriteBlock(&pkt, sizeof(pkt));41}4243//Write a fin output packet44void Blimp::Write_FINO(float *amp, float *off)45{46const struct log_FINO pkt {47LOG_PACKET_HEADER_INIT(LOG_FINO_MSG),48time_us : AP_HAL::micros64(),49Fin1_Amp : amp[0],50Fin1_Off : off[0],51Fin2_Amp : amp[1],52Fin2_Off : off[1],53Fin3_Amp : amp[2],54Fin3_Off : off[2],55Fin4_Amp : amp[3],56Fin4_Off : off[3],57};58logger.WriteBlock(&pkt, sizeof(pkt));59}6061struct PACKED log_Control_Tuning {62LOG_PACKET_HEADER;63uint64_t time_us;64float throttle_in;65float angle_boost;66float throttle_out;67float throttle_hover;68float desired_alt;69float inav_alt;70int32_t baro_alt;71float desired_rangefinder_alt;72float rangefinder_alt;73float terr_alt;74int16_t target_climb_rate;75int16_t climb_rate;76};7778// Write PID packets79void Blimp::Log_Write_PIDs()80{81logger.Write_PID(LOG_PIVN_MSG, pid_vel_xy.get_pid_info_x());82logger.Write_PID(LOG_PIVE_MSG, pid_vel_xy.get_pid_info_y());83logger.Write_PID(LOG_PIVD_MSG, pid_vel_z.get_pid_info());84logger.Write_PID(LOG_PIVY_MSG, pid_vel_yaw.get_pid_info());85logger.Write_PID(LOG_PIDN_MSG, pid_pos_xy.get_pid_info_x());86logger.Write_PID(LOG_PIDE_MSG, pid_pos_xy.get_pid_info_y());87logger.Write_PID(LOG_PIDD_MSG, pid_pos_z.get_pid_info());88logger.Write_PID(LOG_PIDY_MSG, pid_pos_yaw.get_pid_info());89}9091// Write an attitude packet92void Blimp::Log_Write_Attitude()93{94//Attitude targets are all zero since Blimp doesn't have attitude control,95//but the rest of the log message is useful.96ahrs.Write_Attitude(Vector3f{0,0,0});97}9899// Write an EKF and POS packet100void Blimp::Log_Write_EKF_POS()101{102AP::ahrs().Log_Write();103}104105struct PACKED log_Data_Int16t {106LOG_PACKET_HEADER;107uint64_t time_us;108uint8_t id;109int16_t data_value;110};111112// Write an int16_t data packet113UNUSED_FUNCTION114void Blimp::Log_Write_Data(LogDataID id, int16_t value)115{116if (should_log(MASK_LOG_ANY)) {117struct log_Data_Int16t pkt = {118LOG_PACKET_HEADER_INIT(LOG_DATA_INT16_MSG),119time_us : AP_HAL::micros64(),120id : (uint8_t)id,121data_value : value122};123logger.WriteCriticalBlock(&pkt, sizeof(pkt));124}125}126127struct PACKED log_Data_UInt16t {128LOG_PACKET_HEADER;129uint64_t time_us;130uint8_t id;131uint16_t data_value;132};133134// Write an uint16_t data packet135UNUSED_FUNCTION136void Blimp::Log_Write_Data(LogDataID id, uint16_t value)137{138if (should_log(MASK_LOG_ANY)) {139struct log_Data_UInt16t pkt = {140LOG_PACKET_HEADER_INIT(LOG_DATA_UINT16_MSG),141time_us : AP_HAL::micros64(),142id : (uint8_t)id,143data_value : value144};145logger.WriteCriticalBlock(&pkt, sizeof(pkt));146}147}148149struct PACKED log_Data_Int32t {150LOG_PACKET_HEADER;151uint64_t time_us;152uint8_t id;153int32_t data_value;154};155156// Write an int32_t data packet157void Blimp::Log_Write_Data(LogDataID id, int32_t value)158{159if (should_log(MASK_LOG_ANY)) {160struct log_Data_Int32t pkt = {161LOG_PACKET_HEADER_INIT(LOG_DATA_INT32_MSG),162time_us : AP_HAL::micros64(),163id : (uint8_t)id,164data_value : value165};166logger.WriteCriticalBlock(&pkt, sizeof(pkt));167}168}169170struct PACKED log_Data_UInt32t {171LOG_PACKET_HEADER;172uint64_t time_us;173uint8_t id;174uint32_t data_value;175};176177// Write a uint32_t data packet178void Blimp::Log_Write_Data(LogDataID id, uint32_t value)179{180if (should_log(MASK_LOG_ANY)) {181struct log_Data_UInt32t pkt = {182LOG_PACKET_HEADER_INIT(LOG_DATA_UINT32_MSG),183time_us : AP_HAL::micros64(),184id : (uint8_t)id,185data_value : value186};187logger.WriteCriticalBlock(&pkt, sizeof(pkt));188}189}190191struct PACKED log_Data_Float {192LOG_PACKET_HEADER;193uint64_t time_us;194uint8_t id;195float data_value;196};197198// Write a float data packet199UNUSED_FUNCTION200void Blimp::Log_Write_Data(LogDataID id, float value)201{202if (should_log(MASK_LOG_ANY)) {203struct log_Data_Float pkt = {204LOG_PACKET_HEADER_INIT(LOG_DATA_FLOAT_MSG),205time_us : AP_HAL::micros64(),206id : (uint8_t)id,207data_value : value208};209logger.WriteCriticalBlock(&pkt, sizeof(pkt));210}211}212213struct PACKED log_ParameterTuning {214LOG_PACKET_HEADER;215uint64_t time_us;216uint8_t parameter; // parameter we are tuning, e.g. 39 is CH6_CIRCLE_RATE217float tuning_value; // normalized value used inside tuning() function218float tuning_min; // tuning minimum value219float tuning_max; // tuning maximum value220};221222void Blimp::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max)223{224struct log_ParameterTuning pkt_tune = {225LOG_PACKET_HEADER_INIT(LOG_PARAMTUNE_MSG),226time_us : AP_HAL::micros64(),227parameter : param,228tuning_value : tuning_val,229tuning_min : tune_min,230tuning_max : tune_max231};232233logger.WriteBlock(&pkt_tune, sizeof(pkt_tune));234}235236// type and unit information can be found in237// libraries/AP_Logger/Logstructure.h; search for "log_Units" for238// units and "Format characters" for field type information239const struct LogStructure Blimp::log_structure[] = {240LOG_COMMON_STRUCTURES,241242// @LoggerMessage: FINI243// @Description: Fin input244// @Field: TimeUS: Time since system startup245// @Field: R: Right246// @Field: F: Front247// @Field: D: Down248// @Field: Y: Yaw249250{251LOG_FINI_MSG, sizeof(log_FINI),252"FINI", "Qffff", "TimeUS,R,F,D,Y", "s----", "F----"253},254255// @LoggerMessage: FINO256// @Description: Fin output257// @Field: TimeUS: Time since system startup258// @Field: F1A: Fin 1 Amplitude259// @Field: F1O: Fin 1 Offset260// @Field: F2A: Fin 2 Amplitude261// @Field: F2O: Fin 2 Offset262// @Field: F3A: Fin 3 Amplitude263// @Field: F3O: Fin 3 Offset264// @Field: F4A: Fin 4 Amplitude265// @Field: F4O: Fin 4 Offset266267{268LOG_FINO_MSG, sizeof(log_FINO),269"FINO", "Qffffffff", "TimeUS,F1A,F1O,F2A,F2O,F3A,F3O,F4A,F4O", "s--------", "F--------"270},271272// @LoggerMessage: PIDD,PIVN,PIVE,PIVD,PIVY273// @Description: Proportional/Integral/Derivative gain values274// @Field: TimeUS: Time since system startup275// @Field: Tar: desired value276// @Field: Act: achieved value277// @Field: Err: error between target and achieved278// @Field: P: proportional part of PID279// @Field: I: integral part of PID280// @Field: D: derivative part of PID281// @Field: FF: controller feed-forward portion of response282// @Field: DFF: controller derivative feed-forward portion of response283// @Field: Dmod: scaler applied to D gain to reduce limit cycling284// @Field: SRate: slew rate285// @Field: Flags: bitmask of PID state flags286// @FieldBitmaskEnum: Flags: log_PID_Flags287{288LOG_PIDD_MSG, sizeof(log_PID),289"PIDD", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS290},291{292LOG_PIVN_MSG, sizeof(log_PID),293"PIVN", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS294},295{296LOG_PIVE_MSG, sizeof(log_PID),297"PIVE", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS298},299{300LOG_PIVD_MSG, sizeof(log_PID),301"PIVD", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS302},303{304LOG_PIVY_MSG, sizeof(log_PID),305"PIVY", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS306},307308// @LoggerMessage: PTUN309// @Description: Parameter Tuning information310// @URL: https://ardupilot.org/blimp/docs/tuning.html#in-flight-tuning311// @Field: TimeUS: Time since system startup312// @Field: Param: Parameter being tuned313// @Field: TunVal: Normalized value used inside tuning() function314// @Field: TunMin: Tuning minimum limit315// @Field: TunMax: Tuning maximum limit316317{318LOG_PARAMTUNE_MSG, sizeof(log_ParameterTuning),319"PTUN", "QBfff", "TimeUS,Param,TunVal,TunMin,TunMax", "s----", "F----"320},321322// @LoggerMessage: CTUN323// @Description: Control Tuning information324// @Field: TimeUS: Time since system startup325// @Field: ThI: throttle input326// @Field: ABst: angle boost327// @Field: ThO: throttle output328// @Field: ThH: calculated hover throttle329// @Field: DAlt: desired altitude330// @Field: Alt: achieved altitude331// @Field: BAlt: barometric altitude332// @Field: DSAlt: desired rangefinder altitude333// @Field: SAlt: achieved rangefinder altitude334// @Field: TAlt: terrain altitude335// @Field: DCRt: desired climb rate336// @Field: CRt: climb rate337338// @LoggerMessage: D16339// @Description: Generic 16-bit-signed-integer storage340// @Field: TimeUS: Time since system startup341// @Field: Id: Data type identifier342// @Field: Value: Value343344// @LoggerMessage: DU16345// @Description: Generic 16-bit-unsigned-integer storage346// @Field: TimeUS: Time since system startup347// @Field: Id: Data type identifier348// @Field: Value: Value349350// @LoggerMessage: D32351// @Description: Generic 32-bit-signed-integer storage352// @Field: TimeUS: Time since system startup353// @Field: Id: Data type identifier354// @Field: Value: Value355356// @LoggerMessage: DFLT357// @Description: Generic float storage358// @Field: TimeUS: Time since system startup359// @Field: Id: Data type identifier360// @Field: Value: Value361362// @LoggerMessage: DU32363// @Description: Generic 32-bit-unsigned-integer storage364// @Field: TimeUS: Time since system startup365// @Field: Id: Data type identifier366// @Field: Value: Value367368{369LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),370"CTUN", "Qffffffefffhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00B000BB"371},372373{374LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t),375"D16", "QBh", "TimeUS,Id,Value", "s--", "F--"376},377{378LOG_DATA_UINT16_MSG, sizeof(log_Data_UInt16t),379"DU16", "QBH", "TimeUS,Id,Value", "s--", "F--"380},381{382LOG_DATA_INT32_MSG, sizeof(log_Data_Int32t),383"D32", "QBi", "TimeUS,Id,Value", "s--", "F--"384},385{386LOG_DATA_UINT32_MSG, sizeof(log_Data_UInt32t),387"DU32", "QBI", "TimeUS,Id,Value", "s--", "F--"388},389{390LOG_DATA_FLOAT_MSG, sizeof(log_Data_Float),391"DFLT", "QBf", "TimeUS,Id,Value", "s--", "F--"392},393};394395uint8_t Blimp::get_num_log_structures() const396{397return ARRAY_SIZE(log_structure);398399}400401void Blimp::Log_Write_Vehicle_Startup_Messages()402{403// only 200(?) bytes are guaranteed by AP_Logger404logger.Write_MessageF("Frame: %s", get_frame_string());405logger.Write_Mode((uint8_t)control_mode, control_mode_reason);406ahrs.Log_Write_Home_And_Origin();407gps.Write_AP_Logger_Log_Startup_messages();408}409410#endif // HAL_LOGGING_ENABLED411412413