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/ArduCopter/Log.cpp
Views: 1798
#include "Copter.h"1#include <AP_InertialSensor/AP_InertialSensor_rate_config.h>23#if HAL_LOGGING_ENABLED45// Code to Write and Read packets from AP_Logger log memory6// Code to interact with the user to dump or erase logs78struct PACKED log_Control_Tuning {9LOG_PACKET_HEADER;10uint64_t time_us;11float throttle_in;12float angle_boost;13float throttle_out;14float throttle_hover;15float desired_alt;16float inav_alt;17int32_t baro_alt;18float desired_rangefinder_alt;19float rangefinder_alt;20float terr_alt;21int16_t target_climb_rate;22int16_t climb_rate;23};2425// Write a control tuning packet26void Copter::Log_Write_Control_Tuning()27{28// get terrain altitude29float terr_alt = 0.0f;30#if AP_TERRAIN_AVAILABLE31if (!terrain.height_above_terrain(terr_alt, true)) {32terr_alt = logger.quiet_nan();33}34#endif35float des_alt_m = 0.0f;36int16_t target_climb_rate_cms = 0;37if (!flightmode->has_manual_throttle()) {38des_alt_m = pos_control->get_pos_target_z_cm() * 0.01f;39target_climb_rate_cms = pos_control->get_vel_target_z_cms();40}4142float desired_rangefinder_alt;43#if AP_RANGEFINDER_ENABLED44if (!surface_tracking.get_target_dist_for_logging(desired_rangefinder_alt)) {45desired_rangefinder_alt = AP::logger().quiet_nan();46}47#else48// get surface tracking alts49desired_rangefinder_alt = AP::logger().quiet_nan();50#endif5152struct log_Control_Tuning pkt = {53LOG_PACKET_HEADER_INIT(LOG_CONTROL_TUNING_MSG),54time_us : AP_HAL::micros64(),55throttle_in : attitude_control->get_throttle_in(),56angle_boost : attitude_control->angle_boost(),57throttle_out : motors->get_throttle(),58throttle_hover : motors->get_throttle_hover(),59desired_alt : des_alt_m,60inav_alt : inertial_nav.get_position_z_up_cm() * 0.01f,61baro_alt : baro_alt,62desired_rangefinder_alt : desired_rangefinder_alt,63#if AP_RANGEFINDER_ENABLED64rangefinder_alt : surface_tracking.get_dist_for_logging(),65#else66rangefinder_alt : AP::logger().quiet_nanf(),67#endif68terr_alt : terr_alt,69target_climb_rate : target_climb_rate_cms,70climb_rate : int16_t(inertial_nav.get_velocity_z_up_cms()) // float -> int16_t71};72logger.WriteBlock(&pkt, sizeof(pkt));73}7475// Write an attitude packet76void Copter::Log_Write_Attitude()77{78attitude_control->Write_ANG();79}8081void Copter::Log_Write_Rate()82{83attitude_control->Write_Rate(*pos_control);84}8586// Write PIDS packets87void Copter::Log_Write_PIDS()88{89if (should_log(MASK_LOG_PID)) {90logger.Write_PID(LOG_PIDR_MSG, attitude_control->get_rate_roll_pid().get_pid_info());91logger.Write_PID(LOG_PIDP_MSG, attitude_control->get_rate_pitch_pid().get_pid_info());92logger.Write_PID(LOG_PIDY_MSG, attitude_control->get_rate_yaw_pid().get_pid_info());93logger.Write_PID(LOG_PIDA_MSG, pos_control->get_accel_z_pid().get_pid_info() );94if (should_log(MASK_LOG_NTUN) && (flightmode->requires_GPS() || landing_with_GPS())) {95logger.Write_PID(LOG_PIDN_MSG, pos_control->get_vel_xy_pid().get_pid_info_x());96logger.Write_PID(LOG_PIDE_MSG, pos_control->get_vel_xy_pid().get_pid_info_y());97}98}99}100101// Write an EKF and POS packet102void Copter::Log_Write_EKF_POS()103{104AP::ahrs().Log_Write();105}106107struct PACKED log_Data_Int16t {108LOG_PACKET_HEADER;109uint64_t time_us;110uint8_t id;111int16_t data_value;112};113114// Write an int16_t data packet115UNUSED_FUNCTION116void Copter::Log_Write_Data(LogDataID id, int16_t value)117{118if (should_log(MASK_LOG_ANY)) {119struct log_Data_Int16t pkt = {120LOG_PACKET_HEADER_INIT(LOG_DATA_INT16_MSG),121time_us : AP_HAL::micros64(),122id : (uint8_t)id,123data_value : value124};125logger.WriteCriticalBlock(&pkt, sizeof(pkt));126}127}128129struct PACKED log_Data_UInt16t {130LOG_PACKET_HEADER;131uint64_t time_us;132uint8_t id;133uint16_t data_value;134};135136// Write an uint16_t data packet137UNUSED_FUNCTION138void Copter::Log_Write_Data(LogDataID id, uint16_t value)139{140if (should_log(MASK_LOG_ANY)) {141struct log_Data_UInt16t pkt = {142LOG_PACKET_HEADER_INIT(LOG_DATA_UINT16_MSG),143time_us : AP_HAL::micros64(),144id : (uint8_t)id,145data_value : value146};147logger.WriteCriticalBlock(&pkt, sizeof(pkt));148}149}150151struct PACKED log_Data_Int32t {152LOG_PACKET_HEADER;153uint64_t time_us;154uint8_t id;155int32_t data_value;156};157158// Write an int32_t data packet159void Copter::Log_Write_Data(LogDataID id, int32_t value)160{161if (should_log(MASK_LOG_ANY)) {162struct log_Data_Int32t pkt = {163LOG_PACKET_HEADER_INIT(LOG_DATA_INT32_MSG),164time_us : AP_HAL::micros64(),165id : (uint8_t)id,166data_value : value167};168logger.WriteCriticalBlock(&pkt, sizeof(pkt));169}170}171172struct PACKED log_Data_UInt32t {173LOG_PACKET_HEADER;174uint64_t time_us;175uint8_t id;176uint32_t data_value;177};178179// Write a uint32_t data packet180void Copter::Log_Write_Data(LogDataID id, uint32_t value)181{182if (should_log(MASK_LOG_ANY)) {183struct log_Data_UInt32t pkt = {184LOG_PACKET_HEADER_INIT(LOG_DATA_UINT32_MSG),185time_us : AP_HAL::micros64(),186id : (uint8_t)id,187data_value : value188};189logger.WriteCriticalBlock(&pkt, sizeof(pkt));190}191}192193struct PACKED log_Data_Float {194LOG_PACKET_HEADER;195uint64_t time_us;196uint8_t id;197float data_value;198};199200// Write a float data packet201UNUSED_FUNCTION202void Copter::Log_Write_Data(LogDataID id, float value)203{204if (should_log(MASK_LOG_ANY)) {205struct log_Data_Float pkt = {206LOG_PACKET_HEADER_INIT(LOG_DATA_FLOAT_MSG),207time_us : AP_HAL::micros64(),208id : (uint8_t)id,209data_value : value210};211logger.WriteCriticalBlock(&pkt, sizeof(pkt));212}213}214215struct PACKED log_ParameterTuning {216LOG_PACKET_HEADER;217uint64_t time_us;218uint8_t parameter; // parameter we are tuning, e.g. 39 is CH6_CIRCLE_RATE219float tuning_value; // normalized value used inside tuning() function220float tuning_min; // tuning minimum value221float tuning_max; // tuning maximum value222};223224void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max)225{226struct log_ParameterTuning pkt_tune = {227LOG_PACKET_HEADER_INIT(LOG_PARAMTUNE_MSG),228time_us : AP_HAL::micros64(),229parameter : param,230tuning_value : tuning_val,231tuning_min : tune_min,232tuning_max : tune_max233};234235logger.WriteBlock(&pkt_tune, sizeof(pkt_tune));236}237238void Copter::Log_Video_Stabilisation()239{240if (!should_log(MASK_LOG_VIDEO_STABILISATION)) {241return;242}243ahrs.write_video_stabilisation();244}245246struct PACKED log_SysIdD {247LOG_PACKET_HEADER;248uint64_t time_us;249float waveform_time;250float waveform_sample;251float waveform_freq;252float angle_x;253float angle_y;254float angle_z;255float accel_x;256float accel_y;257float accel_z;258};259260// Write an rate packet261void Copter::Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z)262{263#if MODE_SYSTEMID_ENABLED264struct log_SysIdD pkt_sidd = {265LOG_PACKET_HEADER_INIT(LOG_SYSIDD_MSG),266time_us : AP_HAL::micros64(),267waveform_time : waveform_time,268waveform_sample : waveform_sample,269waveform_freq : waveform_freq,270angle_x : angle_x,271angle_y : angle_y,272angle_z : angle_z,273accel_x : accel_x,274accel_y : accel_y,275accel_z : accel_z276};277logger.WriteBlock(&pkt_sidd, sizeof(pkt_sidd));278#endif279}280281struct PACKED log_SysIdS {282LOG_PACKET_HEADER;283uint64_t time_us;284uint8_t systemID_axis;285float waveform_magnitude;286float frequency_start;287float frequency_stop;288float time_fade_in;289float time_const_freq;290float time_record;291float time_fade_out;292};293294// Write an rate packet295void Copter::Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out)296{297#if MODE_SYSTEMID_ENABLED298struct log_SysIdS pkt_sids = {299LOG_PACKET_HEADER_INIT(LOG_SYSIDS_MSG),300time_us : AP_HAL::micros64(),301systemID_axis : systemID_axis,302waveform_magnitude : waveform_magnitude,303frequency_start : frequency_start,304frequency_stop : frequency_stop,305time_fade_in : time_fade_in,306time_const_freq : time_const_freq,307time_record : time_record,308time_fade_out : time_fade_out309};310logger.WriteBlock(&pkt_sids, sizeof(pkt_sids));311#endif312}313314// guided position target logging315struct PACKED log_Guided_Position_Target {316LOG_PACKET_HEADER;317uint64_t time_us;318uint8_t type;319float pos_target_x;320float pos_target_y;321float pos_target_z;322uint8_t terrain;323float vel_target_x;324float vel_target_y;325float vel_target_z;326float accel_target_x;327float accel_target_y;328float accel_target_z;329};330331// guided attitude target logging332struct PACKED log_Guided_Attitude_Target {333LOG_PACKET_HEADER;334uint64_t time_us;335uint8_t type;336float roll;337float pitch;338float yaw;339float roll_rate;340float pitch_rate;341float yaw_rate;342float thrust;343float climb_rate;344};345346// rate thread dt stats347struct PACKED log_Rate_Thread_Dt {348LOG_PACKET_HEADER;349uint64_t time_us;350float dt;351float dtAvg;352float dtMax;353float dtMin;354};355356// Write a Guided mode position target357// pos_target is lat, lon, alt OR offset from ekf origin in cm358// terrain should be 0 if pos_target.z is alt-above-ekf-origin, 1 if alt-above-terrain359// vel_target is cm/s360void Copter::Log_Write_Guided_Position_Target(ModeGuided::SubMode target_type, const Vector3f& pos_target, bool terrain_alt, const Vector3f& vel_target, const Vector3f& accel_target)361{362const log_Guided_Position_Target pkt {363LOG_PACKET_HEADER_INIT(LOG_GUIDED_POSITION_TARGET_MSG),364time_us : AP_HAL::micros64(),365type : (uint8_t)target_type,366pos_target_x : pos_target.x,367pos_target_y : pos_target.y,368pos_target_z : pos_target.z,369terrain : terrain_alt,370vel_target_x : vel_target.x,371vel_target_y : vel_target.y,372vel_target_z : vel_target.z,373accel_target_x : accel_target.x,374accel_target_y : accel_target.y,375accel_target_z : accel_target.z376};377logger.WriteBlock(&pkt, sizeof(pkt));378}379380// Write a Guided mode attitude target381// roll, pitch and yaw are in radians382// ang_vel: angular velocity, [roll rate, pitch_rate, yaw_rate] in radians/sec383// thrust is between 0 to 1384// climb_rate is in (m/s)385void Copter::Log_Write_Guided_Attitude_Target(ModeGuided::SubMode target_type, float roll, float pitch, float yaw, const Vector3f &ang_vel, float thrust, float climb_rate)386{387const log_Guided_Attitude_Target pkt {388LOG_PACKET_HEADER_INIT(LOG_GUIDED_ATTITUDE_TARGET_MSG),389time_us : AP_HAL::micros64(),390type : (uint8_t)target_type,391roll : degrees(roll), // rad to deg392pitch : degrees(pitch), // rad to deg393yaw : degrees(yaw), // rad to deg394roll_rate : degrees(ang_vel.x), // rad/s to deg/s395pitch_rate : degrees(ang_vel.y), // rad/s to deg/s396yaw_rate : degrees(ang_vel.z), // rad/s to deg/s397thrust : thrust,398climb_rate : climb_rate399};400logger.WriteBlock(&pkt, sizeof(pkt));401}402403void Copter::Log_Write_Rate_Thread_Dt(float dt, float dtAvg, float dtMax, float dtMin)404{405#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED406const log_Rate_Thread_Dt pkt {407LOG_PACKET_HEADER_INIT(LOG_RATE_THREAD_DT_MSG),408time_us : AP_HAL::micros64(),409dt : dt,410dtAvg : dtAvg,411dtMax : dtMax,412dtMin : dtMin413};414logger.WriteBlock(&pkt, sizeof(pkt));415#endif416}417418// type and unit information can be found in419// libraries/AP_Logger/Logstructure.h; search for "log_Units" for420// units and "Format characters" for field type information421const struct LogStructure Copter::log_structure[] = {422LOG_COMMON_STRUCTURES,423424// @LoggerMessage: PTUN425// @Description: Parameter Tuning information426// @URL: https://ardupilot.org/copter/docs/tuning.html#in-flight-tuning427// @Field: TimeUS: Time since system startup428// @Field: Param: Parameter being tuned429// @Field: TunVal: Normalized value used inside tuning() function430// @Field: TunMin: Tuning minimum limit431// @Field: TunMax: Tuning maximum limit432433{ LOG_PARAMTUNE_MSG, sizeof(log_ParameterTuning),434"PTUN", "QBfff", "TimeUS,Param,TunVal,TunMin,TunMax", "s----", "F----" },435436// @LoggerMessage: CTUN437// @Description: Control Tuning information438// @Field: TimeUS: Time since system startup439// @Field: ThI: throttle input440// @Field: ABst: angle boost441// @Field: ThO: throttle output442// @Field: ThH: calculated hover throttle443// @Field: DAlt: desired altitude444// @Field: Alt: achieved altitude445// @Field: BAlt: barometric altitude446// @Field: DSAlt: desired rangefinder altitude447// @Field: SAlt: achieved rangefinder altitude448// @Field: TAlt: terrain altitude449// @Field: DCRt: desired climb rate450// @Field: CRt: climb rate451452// @LoggerMessage: D16453// @Description: Generic 16-bit-signed-integer storage454// @Field: TimeUS: Time since system startup455// @Field: Id: Data type identifier456// @Field: Value: Value457458// @LoggerMessage: DU16459// @Description: Generic 16-bit-unsigned-integer storage460// @Field: TimeUS: Time since system startup461// @Field: Id: Data type identifier462// @Field: Value: Value463464// @LoggerMessage: D32465// @Description: Generic 32-bit-signed-integer storage466// @Field: TimeUS: Time since system startup467// @Field: Id: Data type identifier468// @Field: Value: Value469470// @LoggerMessage: DFLT471// @Description: Generic float storage472// @Field: TimeUS: Time since system startup473// @Field: Id: Data type identifier474// @Field: Value: Value475476// @LoggerMessage: DU32477// @Description: Generic 32-bit-unsigned-integer storage478// @Field: TimeUS: Time since system startup479// @Field: Id: Data type identifier480// @Field: Value: Value481482{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),483"CTUN", "Qffffffefffhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00B000BB" , true },484{ LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t),485"D16", "QBh", "TimeUS,Id,Value", "s--", "F--" },486{ LOG_DATA_UINT16_MSG, sizeof(log_Data_UInt16t),487"DU16", "QBH", "TimeUS,Id,Value", "s--", "F--" },488{ LOG_DATA_INT32_MSG, sizeof(log_Data_Int32t),489"D32", "QBi", "TimeUS,Id,Value", "s--", "F--" },490{ LOG_DATA_UINT32_MSG, sizeof(log_Data_UInt32t),491"DU32", "QBI", "TimeUS,Id,Value", "s--", "F--" },492{ LOG_DATA_FLOAT_MSG, sizeof(log_Data_Float),493"DFLT", "QBf", "TimeUS,Id,Value", "s--", "F--" },494495// @LoggerMessage: SIDD496// @Description: System ID data497// @Field: TimeUS: Time since system startup498// @Field: Time: Time reference for waveform499// @Field: Targ: Current waveform sample500// @Field: F: Instantaneous waveform frequency501// @Field: Gx: Delta angle, X-Axis502// @Field: Gy: Delta angle, Y-Axis503// @Field: Gz: Delta angle, Z-Axis504// @Field: Ax: Delta velocity, X-Axis505// @Field: Ay: Delta velocity, Y-Axis506// @Field: Az: Delta velocity, Z-Axis507508{ LOG_SYSIDD_MSG, sizeof(log_SysIdD),509"SIDD", "Qfffffffff", "TimeUS,Time,Targ,F,Gx,Gy,Gz,Ax,Ay,Az", "ss-zkkkooo", "F---------" , true },510511// @LoggerMessage: SIDS512// @Description: System ID settings513// @Field: TimeUS: Time since system startup514// @Field: Ax: The axis which is being excited515// @Field: Mag: Magnitude of the chirp waveform516// @Field: FSt: Frequency at the start of chirp517// @Field: FSp: Frequency at the end of chirp518// @Field: TFin: Time to reach maximum amplitude of chirp519// @Field: TC: Time at constant frequency before chirp starts520// @Field: TR: Time taken to complete chirp waveform521// @Field: TFout: Time to reach zero amplitude after chirp finishes522523{ LOG_SYSIDS_MSG, sizeof(log_SysIdS),524"SIDS", "QBfffffff", "TimeUS,Ax,Mag,FSt,FSp,TFin,TC,TR,TFout", "s--ssssss", "F--------" , true },525526// @LoggerMessage: GUIP527// @Description: Guided mode position target information528// @Field: TimeUS: Time since system startup529// @Field: Type: Type of guided mode530// @Field: pX: Target position, X-Axis531// @Field: pY: Target position, Y-Axis532// @Field: pZ: Target position, Z-Axis533// @Field: Terrain: Target position, Z-Axis is alt above terrain534// @Field: vX: Target velocity, X-Axis535// @Field: vY: Target velocity, Y-Axis536// @Field: vZ: Target velocity, Z-Axis537// @Field: aX: Target acceleration, X-Axis538// @Field: aY: Target acceleration, Y-Axis539// @Field: aZ: Target acceleration, Z-Axis540541{ LOG_GUIDED_POSITION_TARGET_MSG, sizeof(log_Guided_Position_Target),542"GUIP", "QBfffbffffff", "TimeUS,Type,pX,pY,pZ,Terrain,vX,vY,vZ,aX,aY,aZ", "s-mmm-nnnooo", "F-BBB-BBBBBB" , true },543544// @LoggerMessage: GUIA545// @Description: Guided mode attitude target information546// @Field: TimeUS: Time since system startup547// @Field: Type: Type of guided mode548// @Field: Roll: Target attitude, Roll549// @Field: Pitch: Target attitude, Pitch550// @Field: Yaw: Target attitude, Yaw551// @Field: RollRt: Roll rate552// @Field: PitchRt: Pitch rate553// @Field: YawRt: Yaw rate554// @Field: Thrust: Thrust555// @Field: ClimbRt: Climb rate556557{ LOG_GUIDED_ATTITUDE_TARGET_MSG, sizeof(log_Guided_Attitude_Target),558"GUIA", "QBffffffff", "TimeUS,Type,Roll,Pitch,Yaw,RollRt,PitchRt,YawRt,Thrust,ClimbRt", "s-dddkkk-n", "F-000000-0" , true },559560// @LoggerMessage: RTDT561// @Description: Attitude controller time deltas562// @Field: TimeUS: Time since system startup563// @Field: dt: current time delta564// @Field: dtAvg: current time delta average565// @Field: dtMax: Max time delta since last log output566// @Field: dtMin: Min time delta since last log output567568{ LOG_RATE_THREAD_DT_MSG, sizeof(log_Rate_Thread_Dt),569"RTDT", "Qffff", "TimeUS,dt,dtAvg,dtMax,dtMin", "sssss", "F----" , true },570571};572573uint8_t Copter::get_num_log_structures() const574{575return ARRAY_SIZE(log_structure);576}577578void Copter::Log_Write_Vehicle_Startup_Messages()579{580// only 200(?) bytes are guaranteed by AP_Logger581char frame_and_type_string[30];582copter.motors->get_frame_and_type_string(frame_and_type_string, ARRAY_SIZE(frame_and_type_string));583logger.Write_MessageF("%s", frame_and_type_string);584logger.Write_Mode((uint8_t)flightmode->mode_number(), control_mode_reason);585ahrs.Log_Write_Home_And_Origin();586gps.Write_AP_Logger_Log_Startup_messages();587}588589#endif // HAL_LOGGING_ENABLED590591592