2011-11-12 23:29:07 -04:00
|
|
|
/* ************************************************************ */
|
2019-01-18 00:23:42 -04:00
|
|
|
/* Test for AP_Logger Log library */
|
2011-11-12 23:29:07 -04:00
|
|
|
/* ************************************************************ */
|
2016-02-17 21:25:53 -04:00
|
|
|
#pragma once
|
2011-11-12 23:29:07 -04:00
|
|
|
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2018-12-27 07:58:29 -04:00
|
|
|
#include <AP_AHRS/AP_AHRS.h>
|
|
|
|
#include <AP_AHRS/AP_AHRS_DCM.h>
|
|
|
|
#include <AP_AHRS/AP_AHRS_NavEKF.h>
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
|
|
|
#include <AP_InertialSensor/AP_InertialSensor.h>
|
|
|
|
#include <AP_Mission/AP_Mission.h>
|
2015-08-15 19:53:26 -03:00
|
|
|
#include <AP_RPM/AP_RPM.h>
|
2019-01-18 00:23:42 -04:00
|
|
|
#include <AP_Logger/LogStructure.h>
|
2016-03-24 22:11:11 -03:00
|
|
|
#include <AP_Motors/AP_Motors.h>
|
2016-07-03 23:14:26 -03:00
|
|
|
#include <AP_Rally/AP_Rally.h>
|
2017-04-18 11:43:03 -03:00
|
|
|
#include <AP_Beacon/AP_Beacon.h>
|
2017-07-14 14:00:13 -03:00
|
|
|
#include <AP_Proximity/AP_Proximity.h>
|
2017-09-01 08:05:16 -03:00
|
|
|
#include <AP_InertialSensor/AP_InertialSensor_Backend.h>
|
2019-10-17 00:48:00 -03:00
|
|
|
#include <AP_Vehicle/ModeReason.h>
|
2017-09-01 08:05:16 -03:00
|
|
|
|
2011-11-12 23:29:07 -04:00
|
|
|
#include <stdint.h>
|
|
|
|
|
2019-01-18 00:23:42 -04:00
|
|
|
#include "LoggerMessageWriter.h"
|
2014-11-13 06:38:33 -04:00
|
|
|
|
2019-01-18 00:23:42 -04:00
|
|
|
class AP_Logger_Backend;
|
2019-08-27 17:08:01 -03:00
|
|
|
class AP_AHRS;
|
|
|
|
class AP_AHRS_View;
|
2015-11-09 18:14:22 -04:00
|
|
|
|
2019-02-01 07:29:43 -04:00
|
|
|
// do not do anything here apart from add stuff; maintaining older
|
|
|
|
// entries means log analysis is easier
|
2019-10-25 03:03:57 -03:00
|
|
|
enum class LogEvent : uint8_t {
|
|
|
|
ARMED = 10,
|
|
|
|
DISARMED = 11,
|
|
|
|
AUTO_ARMED = 15,
|
|
|
|
LAND_COMPLETE_MAYBE = 17,
|
|
|
|
LAND_COMPLETE = 18,
|
|
|
|
NOT_LANDED = 28,
|
|
|
|
LOST_GPS = 19,
|
|
|
|
FLIP_START = 21,
|
|
|
|
FLIP_END = 22,
|
|
|
|
SET_HOME = 25,
|
|
|
|
SET_SIMPLE_ON = 26,
|
|
|
|
SET_SIMPLE_OFF = 27,
|
|
|
|
SET_SUPERSIMPLE_ON = 29,
|
|
|
|
AUTOTUNE_INITIALISED = 30,
|
|
|
|
AUTOTUNE_OFF = 31,
|
|
|
|
AUTOTUNE_RESTART = 32,
|
|
|
|
AUTOTUNE_SUCCESS = 33,
|
|
|
|
AUTOTUNE_FAILED = 34,
|
|
|
|
AUTOTUNE_REACHED_LIMIT = 35,
|
|
|
|
AUTOTUNE_PILOT_TESTING = 36,
|
|
|
|
AUTOTUNE_SAVEDGAINS = 37,
|
|
|
|
SAVE_TRIM = 38,
|
|
|
|
SAVEWP_ADD_WP = 39,
|
|
|
|
FENCE_ENABLE = 41,
|
|
|
|
FENCE_DISABLE = 42,
|
|
|
|
ACRO_TRAINER_OFF = 43,
|
|
|
|
ACRO_TRAINER_LEVELING = 44,
|
|
|
|
ACRO_TRAINER_LIMITED = 45,
|
|
|
|
GRIPPER_GRAB = 46,
|
|
|
|
GRIPPER_RELEASE = 47,
|
|
|
|
PARACHUTE_DISABLED = 49,
|
|
|
|
PARACHUTE_ENABLED = 50,
|
|
|
|
PARACHUTE_RELEASED = 51,
|
|
|
|
LANDING_GEAR_DEPLOYED = 52,
|
|
|
|
LANDING_GEAR_RETRACTED = 53,
|
|
|
|
MOTORS_EMERGENCY_STOPPED = 54,
|
|
|
|
MOTORS_EMERGENCY_STOP_CLEARED = 55,
|
|
|
|
MOTORS_INTERLOCK_DISABLED = 56,
|
|
|
|
MOTORS_INTERLOCK_ENABLED = 57,
|
|
|
|
ROTOR_RUNUP_COMPLETE = 58, // Heli only
|
|
|
|
ROTOR_SPEED_BELOW_CRITICAL = 59, // Heli only
|
|
|
|
EKF_ALT_RESET = 60,
|
|
|
|
LAND_CANCELLED_BY_PILOT = 61,
|
|
|
|
EKF_YAW_RESET = 62,
|
|
|
|
AVOIDANCE_ADSB_ENABLE = 63,
|
|
|
|
AVOIDANCE_ADSB_DISABLE = 64,
|
|
|
|
AVOIDANCE_PROXIMITY_ENABLE = 65,
|
|
|
|
AVOIDANCE_PROXIMITY_DISABLE = 66,
|
|
|
|
GPS_PRIMARY_CHANGED = 67,
|
|
|
|
WINCH_RELAXED = 68,
|
|
|
|
WINCH_LENGTH_CONTROL = 69,
|
|
|
|
WINCH_RATE_CONTROL = 70,
|
|
|
|
ZIGZAG_STORE_A = 71,
|
|
|
|
ZIGZAG_STORE_B = 72,
|
|
|
|
LAND_REPO_ACTIVE = 73,
|
|
|
|
STANDBY_ENABLE = 74,
|
|
|
|
STANDBY_DISABLE = 75,
|
|
|
|
|
|
|
|
SURFACED = 163,
|
|
|
|
NOT_SURFACED = 164,
|
|
|
|
BOTTOMED = 165,
|
|
|
|
NOT_BOTTOMED = 166,
|
|
|
|
};
|
|
|
|
|
|
|
|
enum class LogDataID : uint8_t {
|
|
|
|
AP_STATE = 7,
|
|
|
|
// SYSTEM_TIME_SET = 8,
|
|
|
|
INIT_SIMPLE_BEARING = 9,
|
2019-02-01 07:29:43 -04:00
|
|
|
};
|
|
|
|
|
2019-03-24 22:04:59 -03:00
|
|
|
enum class LogErrorSubsystem : uint8_t {
|
|
|
|
MAIN = 1,
|
|
|
|
RADIO = 2,
|
|
|
|
COMPASS = 3,
|
|
|
|
OPTFLOW = 4, // not used
|
|
|
|
FAILSAFE_RADIO = 5,
|
|
|
|
FAILSAFE_BATT = 6,
|
|
|
|
FAILSAFE_GPS = 7, // not used
|
|
|
|
FAILSAFE_GCS = 8,
|
|
|
|
FAILSAFE_FENCE = 9,
|
|
|
|
FLIGHT_MODE = 10,
|
|
|
|
GPS = 11,
|
|
|
|
CRASH_CHECK = 12,
|
|
|
|
FLIP = 13,
|
|
|
|
AUTOTUNE = 14, // not used
|
|
|
|
PARACHUTES = 15,
|
|
|
|
EKFCHECK = 16,
|
|
|
|
FAILSAFE_EKFINAV = 17,
|
|
|
|
BARO = 18,
|
|
|
|
CPU = 19,
|
|
|
|
FAILSAFE_ADSB = 20,
|
|
|
|
TERRAIN = 21,
|
|
|
|
NAVIGATION = 22,
|
|
|
|
FAILSAFE_TERRAIN = 23,
|
|
|
|
EKF_PRIMARY = 24,
|
|
|
|
THRUST_LOSS_CHECK = 25,
|
2019-03-24 22:52:59 -03:00
|
|
|
FAILSAFE_SENSORS = 26,
|
|
|
|
FAILSAFE_LEAK = 27,
|
|
|
|
PILOT_INPUT = 28,
|
2019-10-04 23:13:59 -03:00
|
|
|
FAILSAFE_VIBE = 29,
|
2019-03-24 22:04:59 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
// bizarrely this enumeration has lots of duplicate values, offering
|
|
|
|
// very little in the way of typesafety
|
|
|
|
enum class LogErrorCode : uint8_t {
|
|
|
|
// general error codes
|
|
|
|
ERROR_RESOLVED = 0,
|
|
|
|
FAILED_TO_INITIALISE = 1,
|
|
|
|
UNHEALTHY = 4,
|
|
|
|
// subsystem specific error codes -- radio
|
|
|
|
RADIO_LATE_FRAME = 2,
|
|
|
|
// subsystem specific error codes -- failsafe_thr, batt, gps
|
|
|
|
FAILSAFE_RESOLVED = 0,
|
|
|
|
FAILSAFE_OCCURRED = 1,
|
|
|
|
// subsystem specific error codes -- main
|
|
|
|
MAIN_INS_DELAY = 1,
|
|
|
|
// subsystem specific error codes -- crash checker
|
|
|
|
CRASH_CHECK_CRASH = 1,
|
|
|
|
CRASH_CHECK_LOSS_OF_CONTROL = 2,
|
|
|
|
// subsystem specific error codes -- flip
|
|
|
|
FLIP_ABANDONED = 2,
|
|
|
|
// subsystem specific error codes -- terrain
|
|
|
|
MISSING_TERRAIN_DATA = 2,
|
|
|
|
// subsystem specific error codes -- navigation
|
|
|
|
FAILED_TO_SET_DESTINATION = 2,
|
|
|
|
RESTARTED_RTL = 3,
|
|
|
|
FAILED_CIRCLE_INIT = 4,
|
|
|
|
DEST_OUTSIDE_FENCE = 5,
|
2019-12-12 02:22:03 -04:00
|
|
|
RTL_MISSING_RNGFND = 6,
|
2019-03-24 22:04:59 -03:00
|
|
|
|
|
|
|
// parachute failed to deploy because of low altitude or landed
|
|
|
|
PARACHUTE_TOO_LOW = 2,
|
|
|
|
PARACHUTE_LANDED = 3,
|
|
|
|
// EKF check definitions
|
|
|
|
EKFCHECK_BAD_VARIANCE = 2,
|
|
|
|
EKFCHECK_VARIANCE_CLEARED = 0,
|
|
|
|
// Baro specific error codes
|
|
|
|
BARO_GLITCH = 2,
|
2019-03-26 23:52:32 -03:00
|
|
|
BAD_DEPTH = 3, // sub-only
|
2019-03-24 22:04:59 -03:00
|
|
|
// GPS specific error coces
|
|
|
|
GPS_GLITCH = 2,
|
|
|
|
};
|
|
|
|
|
2016-03-24 22:11:11 -03:00
|
|
|
// fwd declarations to avoid include errors
|
|
|
|
class AC_AttitudeControl;
|
|
|
|
class AC_PosControl;
|
|
|
|
|
2019-01-18 00:23:42 -04:00
|
|
|
class AP_Logger
|
2011-11-12 23:29:07 -04:00
|
|
|
{
|
2019-01-18 00:23:42 -04:00
|
|
|
friend class AP_Logger_Backend; // for _num_types
|
2015-08-06 09:18:28 -03:00
|
|
|
|
2013-02-22 20:17:34 -04:00
|
|
|
public:
|
2019-01-18 00:24:08 -04:00
|
|
|
FUNCTOR_TYPEDEF(vehicle_startup_message_Writer, void);
|
2017-08-23 17:40:59 -03:00
|
|
|
|
2019-01-18 00:23:42 -04:00
|
|
|
AP_Logger(const AP_Int32 &log_bitmask);
|
2017-12-12 21:06:15 -04:00
|
|
|
|
|
|
|
/* Do not allow copies */
|
2019-01-18 00:23:42 -04:00
|
|
|
AP_Logger(const AP_Logger &other) = delete;
|
|
|
|
AP_Logger &operator=(const AP_Logger&) = delete;
|
2015-08-06 09:18:28 -03:00
|
|
|
|
2016-05-03 03:33:15 -03:00
|
|
|
// get singleton instance
|
2019-02-10 14:05:22 -04:00
|
|
|
static AP_Logger *get_singleton(void) {
|
|
|
|
return _singleton;
|
2016-05-03 03:33:15 -03:00
|
|
|
}
|
2017-08-23 17:40:59 -03:00
|
|
|
|
2013-02-22 20:17:34 -04:00
|
|
|
// initialisation
|
2015-06-25 10:53:20 -03:00
|
|
|
void Init(const struct LogStructure *structure, uint8_t num_types);
|
2018-04-22 07:19:30 -03:00
|
|
|
void set_num_types(uint8_t num_types) { _num_types = num_types; }
|
2015-12-07 20:21:18 -04:00
|
|
|
|
2015-06-25 10:53:20 -03:00
|
|
|
bool CardInserted(void);
|
2013-02-22 20:17:34 -04:00
|
|
|
|
|
|
|
// erase handling
|
2015-06-25 10:53:20 -03:00
|
|
|
void EraseAll();
|
2013-02-22 20:17:34 -04:00
|
|
|
|
|
|
|
/* Write a block of data at current offset */
|
2015-11-09 18:14:22 -04:00
|
|
|
void WriteBlock(const void *pBuffer, uint16_t size);
|
2015-08-06 09:18:28 -03:00
|
|
|
/* Write an *important* block of data at current offset */
|
2015-11-09 18:14:22 -04:00
|
|
|
void WriteCriticalBlock(const void *pBuffer, uint16_t size);
|
2013-02-22 20:17:34 -04:00
|
|
|
|
|
|
|
// high level interface
|
2015-10-20 07:32:31 -03:00
|
|
|
uint16_t find_last_log() const;
|
2019-01-18 18:45:36 -04:00
|
|
|
void get_log_boundaries(uint16_t log_num, uint32_t & start_page, uint32_t & end_page);
|
2015-06-25 10:53:20 -03:00
|
|
|
uint16_t get_num_logs(void);
|
2013-02-22 20:17:34 -04:00
|
|
|
|
2019-01-18 00:24:08 -04:00
|
|
|
void setVehicle_Startup_Writer(vehicle_startup_message_Writer writer);
|
2015-08-06 09:18:28 -03:00
|
|
|
|
2017-07-06 22:28:42 -03:00
|
|
|
void PrepForArming();
|
|
|
|
|
2017-06-14 22:21:17 -03:00
|
|
|
void EnableWrites(bool enable) { _writes_enabled = enable; }
|
|
|
|
bool WritesEnabled() const { return _writes_enabled; }
|
2016-01-01 06:03:22 -04:00
|
|
|
|
2016-04-22 10:33:40 -03:00
|
|
|
void StopLogging();
|
|
|
|
|
2019-01-18 00:24:08 -04:00
|
|
|
void Write_Parameter(const char *name, float value);
|
2019-10-25 03:03:57 -03:00
|
|
|
void Write_Event(LogEvent id);
|
2019-03-24 22:04:59 -03:00
|
|
|
void Write_Error(LogErrorSubsystem sub_system,
|
|
|
|
LogErrorCode error_code);
|
2019-01-18 00:24:08 -04:00
|
|
|
void Write_GPS(uint8_t instance, uint64_t time_us=0);
|
|
|
|
void Write_IMU();
|
|
|
|
void Write_IMUDT(uint64_t time_us, uint8_t imu_mask);
|
|
|
|
bool Write_ISBH(uint16_t seqno,
|
2017-09-01 08:05:16 -03:00
|
|
|
AP_InertialSensor::IMU_SENSOR_TYPE sensor_type,
|
|
|
|
uint8_t instance,
|
|
|
|
uint16_t multiplier,
|
2017-10-10 20:36:04 -03:00
|
|
|
uint16_t sample_count,
|
2017-09-01 08:05:16 -03:00
|
|
|
uint64_t sample_us,
|
|
|
|
float sample_rate_hz);
|
2019-01-18 00:24:08 -04:00
|
|
|
bool Write_ISBD(uint16_t isb_seqno,
|
2017-09-01 08:05:16 -03:00
|
|
|
uint16_t seqno,
|
|
|
|
const int16_t x[32],
|
|
|
|
const int16_t y[32],
|
|
|
|
const int16_t z[32]);
|
2019-01-18 00:24:08 -04:00
|
|
|
void Write_Vibration();
|
|
|
|
void Write_RCIN(void);
|
|
|
|
void Write_RCOUT(void);
|
2019-04-05 19:48:11 -03:00
|
|
|
void Write_RSSI();
|
2019-03-28 03:45:53 -03:00
|
|
|
void Write_Rally();
|
2019-01-18 00:24:08 -04:00
|
|
|
void Write_Baro(uint64_t time_us=0);
|
|
|
|
void Write_Power(void);
|
2019-10-23 21:32:32 -03:00
|
|
|
void Write_AHRS2();
|
|
|
|
void Write_POS();
|
2019-01-18 00:24:08 -04:00
|
|
|
void Write_Radio(const mavlink_radio_t &packet);
|
|
|
|
void Write_Message(const char *message);
|
|
|
|
void Write_MessageF(const char *fmt, ...);
|
2019-06-27 04:24:04 -03:00
|
|
|
void Write_CameraInfo(enum LogMessages msg, const Location ¤t_loc, uint64_t timestamp_us=0);
|
|
|
|
void Write_Camera(const Location ¤t_loc, uint64_t timestamp_us=0);
|
|
|
|
void Write_Trigger(const Location ¤t_loc);
|
2019-11-19 21:37:29 -04:00
|
|
|
void Write_ESC(uint8_t id, uint64_t time_us, int32_t rpm, uint16_t voltage, uint16_t current, int16_t esc_temp, uint16_t current_tot, int16_t motor_temp);
|
2020-01-04 00:25:55 -04:00
|
|
|
void Write_ServoStatus(uint64_t time_us, uint8_t id, float position, float force, float speed, uint8_t power_pct);
|
2020-01-04 00:56:44 -04:00
|
|
|
void Write_ESCStatus(uint64_t time_us, uint8_t id, uint32_t error_count, float voltage, float current, float temperature, int32_t rpm, uint8_t power_pct);
|
2019-10-23 21:32:32 -03:00
|
|
|
void Write_Attitude(const Vector3f &targets);
|
2019-01-18 00:24:08 -04:00
|
|
|
void Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets);
|
|
|
|
void Write_Current();
|
|
|
|
void Write_Compass(uint64_t time_us=0);
|
2019-10-17 00:48:00 -03:00
|
|
|
void Write_Mode(uint8_t mode, const ModeReason reason);
|
2019-01-18 00:24:08 -04:00
|
|
|
|
2019-01-29 21:43:24 -04:00
|
|
|
void Write_EntireMission();
|
2019-08-22 22:21:39 -03:00
|
|
|
void Write_Command(const mavlink_command_int_t &packet, MAV_RESULT result, bool was_command_long=false);
|
2019-01-18 00:24:08 -04:00
|
|
|
void Write_Mission_Cmd(const AP_Mission &mission,
|
2015-06-30 01:33:50 -03:00
|
|
|
const AP_Mission::Mission_Command &cmd);
|
2019-01-18 00:24:08 -04:00
|
|
|
void Write_Origin(uint8_t origin_type, const Location &loc);
|
|
|
|
void Write_RPM(const AP_RPM &rpm_sensor);
|
|
|
|
void Write_Rate(const AP_AHRS_View *ahrs,
|
2016-03-24 22:11:11 -03:00
|
|
|
const AP_Motors &motors,
|
|
|
|
const AC_AttitudeControl &attitude_control,
|
|
|
|
const AC_PosControl &pos_control);
|
2018-12-29 00:02:29 -04:00
|
|
|
void Write_RallyPoint(uint8_t total,
|
|
|
|
uint8_t sequence,
|
|
|
|
const RallyLocation &rally_point);
|
2019-01-18 00:24:08 -04:00
|
|
|
void Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence);
|
2020-06-04 04:54:19 -03:00
|
|
|
void Write_VisualPosition(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, float roll, float pitch, float yaw, float pos_err, float ang_err, uint8_t reset_counter);
|
2020-05-28 22:24:26 -03:00
|
|
|
void Write_VisualVelocity(uint64_t remote_time_us, uint32_t time_ms, const Vector3f &vel, float vel_err, uint8_t reset_counter);
|
2019-01-18 00:24:08 -04:00
|
|
|
void Write_AOA_SSA(AP_AHRS &ahrs);
|
|
|
|
void Write_Beacon(AP_Beacon &beacon);
|
|
|
|
void Write_Proximity(AP_Proximity &proximity);
|
|
|
|
void Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f& point);
|
2019-08-05 03:22:05 -03:00
|
|
|
void Write_OABendyRuler(bool active, float target_yaw, float margin, const Location &final_dest, const Location &oa_dest);
|
2019-09-07 01:56:51 -03:00
|
|
|
void Write_OADijkstra(uint8_t state, uint8_t error_id, uint8_t curr_point, uint8_t tot_points, const Location &final_dest, const Location &oa_dest);
|
2015-06-30 01:33:50 -03:00
|
|
|
|
2019-01-18 00:24:08 -04:00
|
|
|
void Write(const char *name, const char *labels, const char *fmt, ...);
|
|
|
|
void Write(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...);
|
2019-05-15 01:39:32 -03:00
|
|
|
void WriteCritical(const char *name, const char *labels, const char *fmt, ...);
|
|
|
|
void WriteCritical(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...);
|
|
|
|
void WriteV(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list, bool is_critical=false);
|
2016-04-20 02:07:48 -03:00
|
|
|
|
2015-05-21 22:42:08 -03:00
|
|
|
// This structure provides information on the internal member data of a PID for logging purposes
|
|
|
|
struct PID_Info {
|
2019-06-27 06:31:52 -03:00
|
|
|
float target;
|
2018-08-08 01:11:43 -03:00
|
|
|
float actual;
|
2019-06-27 06:31:52 -03:00
|
|
|
float error;
|
2015-05-21 22:42:08 -03:00
|
|
|
float P;
|
|
|
|
float I;
|
|
|
|
float D;
|
|
|
|
float FF;
|
|
|
|
};
|
|
|
|
|
2019-01-18 00:24:08 -04:00
|
|
|
void Write_PID(uint8_t msg_type, const PID_Info &info);
|
2015-05-21 22:42:08 -03:00
|
|
|
|
2017-06-27 01:14:27 -03:00
|
|
|
// returns true if logging of a message should be attempted
|
|
|
|
bool should_log(uint32_t mask) const;
|
2017-06-14 09:45:54 -03:00
|
|
|
|
2015-06-25 10:53:20 -03:00
|
|
|
bool logging_started(void);
|
2013-04-19 04:49:16 -03:00
|
|
|
|
2015-06-18 22:57:01 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
2019-01-18 00:23:42 -04:00
|
|
|
// currently only AP_Logger_File support this:
|
2015-06-18 22:57:01 -03:00
|
|
|
void flush(void);
|
|
|
|
#endif
|
|
|
|
|
2019-04-30 07:22:48 -03:00
|
|
|
void handle_mavlink_msg(class GCS_MAVLINK &, const mavlink_message_t &msg);
|
2015-11-10 02:34:31 -04:00
|
|
|
|
2015-08-06 09:18:28 -03:00
|
|
|
void periodic_tasks(); // may want to split this into GCS/non-GCS duties
|
|
|
|
|
2016-04-21 03:11:21 -03:00
|
|
|
// number of blocks that have been dropped
|
|
|
|
uint32_t num_dropped(void) const;
|
2016-05-08 23:00:55 -03:00
|
|
|
|
|
|
|
// accesss to public parameters
|
2018-07-05 20:58:50 -03:00
|
|
|
void set_force_log_disarmed(bool force_logging) { _force_log_disarmed = force_logging; }
|
2019-06-10 18:55:30 -03:00
|
|
|
bool log_while_disarmed(void) const;
|
2016-05-08 23:00:55 -03:00
|
|
|
uint8_t log_replay(void) const { return _params.log_replay; }
|
2016-04-21 03:11:21 -03:00
|
|
|
|
2019-01-18 00:24:08 -04:00
|
|
|
vehicle_startup_message_Writer _vehicle_messages;
|
2015-08-06 09:18:28 -03:00
|
|
|
|
2015-11-09 18:14:22 -04:00
|
|
|
// parameter support
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
struct {
|
|
|
|
AP_Int8 backend_types;
|
2015-12-03 07:01:53 -04:00
|
|
|
AP_Int8 file_bufsize; // in kilobytes
|
2016-07-28 02:58:20 -03:00
|
|
|
AP_Int8 file_disarm_rot;
|
2016-05-08 23:00:55 -03:00
|
|
|
AP_Int8 log_disarmed;
|
|
|
|
AP_Int8 log_replay;
|
2018-04-23 01:35:29 -03:00
|
|
|
AP_Int8 mav_bufsize; // in kilobytes
|
2019-08-03 04:00:17 -03:00
|
|
|
AP_Int16 file_timeout; // in seconds
|
2020-06-01 17:07:07 -03:00
|
|
|
AP_Int16 min_MB_free;
|
2015-11-09 18:14:22 -04:00
|
|
|
} _params;
|
|
|
|
|
|
|
|
const struct LogStructure *structure(uint16_t num) const;
|
2015-12-07 20:51:46 -04:00
|
|
|
const struct UnitStructure *unit(uint16_t num) const;
|
|
|
|
const struct MultiplierStructure *multiplier(uint16_t num) const;
|
2015-11-09 18:14:22 -04:00
|
|
|
|
2018-12-04 00:33:02 -04:00
|
|
|
// methods for mavlink SYS_STATUS message (send_sys_status)
|
2016-07-07 04:12:27 -03:00
|
|
|
// these methods cover only the first logging backend used -
|
2019-01-18 00:23:42 -04:00
|
|
|
// typically AP_Logger_File.
|
2016-07-07 04:12:27 -03:00
|
|
|
bool logging_present() const;
|
|
|
|
bool logging_enabled() const;
|
|
|
|
bool logging_failed() const;
|
|
|
|
|
2019-06-10 18:55:30 -03:00
|
|
|
// notify logging subsystem of an arming failure. This triggers
|
|
|
|
// logging for HAL_LOGGER_ARM_PERSIST seconds
|
|
|
|
void arming_failure() { _last_arming_failure_ms = AP_HAL::millis(); }
|
|
|
|
|
2016-07-28 00:06:03 -03:00
|
|
|
void set_vehicle_armed(bool armed_state);
|
2017-06-09 01:19:11 -03:00
|
|
|
bool vehicle_is_armed() const { return _armed; }
|
2016-07-28 00:06:03 -03:00
|
|
|
|
2018-03-19 00:37:21 -03:00
|
|
|
void handle_log_send();
|
2019-12-04 23:29:47 -04:00
|
|
|
bool in_log_download() const {
|
|
|
|
return transfer_activity != TransferActivity::IDLE;
|
|
|
|
}
|
2017-06-18 20:43:15 -03:00
|
|
|
|
2017-07-21 23:27:45 -03:00
|
|
|
float quiet_nanf() const { return nanf("0x4152"); } // "AR"
|
|
|
|
double quiet_nan() const { return nan("0x4152445550490a"); } // "ARDUPI"
|
|
|
|
|
2018-04-22 07:19:30 -03:00
|
|
|
// returns true if msg_type is associated with a message
|
|
|
|
bool msg_type_in_use(uint8_t msg_type) const;
|
|
|
|
|
2020-01-15 22:17:01 -04:00
|
|
|
// calculate the length of a message using fields specified in
|
|
|
|
// fmt; includes the message header
|
|
|
|
int16_t Write_calc_msg_len(const char *fmt) const;
|
|
|
|
|
|
|
|
// this structure looks much like struct LogStructure in
|
|
|
|
// LogStructure.h, however we need to remember a pointer value for
|
|
|
|
// efficiency of finding message types
|
|
|
|
struct log_write_fmt {
|
|
|
|
struct log_write_fmt *next;
|
|
|
|
uint8_t msg_type;
|
|
|
|
uint8_t msg_len;
|
|
|
|
uint8_t sent_mask; // bitmask of backends sent to
|
|
|
|
const char *name;
|
|
|
|
const char *fmt;
|
|
|
|
const char *labels;
|
|
|
|
const char *units;
|
|
|
|
const char *mults;
|
|
|
|
} *log_write_fmts;
|
|
|
|
|
|
|
|
// return (possibly allocating) a log_write_fmt for a name
|
|
|
|
struct log_write_fmt *msg_fmt_for_name(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, const bool direct_comp = false);
|
|
|
|
|
|
|
|
// output a FMT message for each backend if not already done so
|
|
|
|
void Safe_Write_Emit_FMT(log_write_fmt *f);
|
|
|
|
|
2013-04-19 04:49:16 -03:00
|
|
|
protected:
|
2015-08-06 09:18:28 -03:00
|
|
|
|
2013-12-16 20:12:42 -04:00
|
|
|
const struct LogStructure *_structures;
|
|
|
|
uint8_t _num_types;
|
2015-12-07 20:51:46 -04:00
|
|
|
const struct UnitStructure *_units = log_Units;
|
|
|
|
const struct MultiplierStructure *_multipliers = log_Multipliers;
|
|
|
|
const uint8_t _num_units = (sizeof(log_Units) / sizeof(log_Units[0]));
|
|
|
|
const uint8_t _num_multipliers = (sizeof(log_Multipliers) / sizeof(log_Multipliers[0]));
|
2013-04-19 21:25:10 -03:00
|
|
|
|
2015-08-06 09:18:28 -03:00
|
|
|
/* Write a block with specified importance */
|
|
|
|
/* might be useful if you have a boolean indicating a message is
|
|
|
|
* important... */
|
2015-11-09 18:14:22 -04:00
|
|
|
void WritePrioritisedBlock(const void *pBuffer, uint16_t size,
|
2015-08-06 09:18:28 -03:00
|
|
|
bool is_critical);
|
|
|
|
|
2015-06-25 10:53:20 -03:00
|
|
|
private:
|
2019-02-11 04:38:01 -04:00
|
|
|
#define LOGGER_MAX_BACKENDS 2
|
2015-11-09 18:14:22 -04:00
|
|
|
uint8_t _next_backend;
|
2019-02-11 04:38:01 -04:00
|
|
|
AP_Logger_Backend *backends[LOGGER_MAX_BACKENDS];
|
2017-06-27 01:14:27 -03:00
|
|
|
const AP_Int32 &_log_bitmask;
|
2016-04-20 02:07:48 -03:00
|
|
|
|
2019-02-28 21:23:55 -04:00
|
|
|
enum class Backend_Type : uint8_t {
|
|
|
|
NONE = 0,
|
|
|
|
FILESYSTEM = (1<<0),
|
|
|
|
MAVLINK = (1<<1),
|
|
|
|
BLOCK = (1<<2),
|
|
|
|
};
|
|
|
|
|
2016-04-20 02:07:48 -03:00
|
|
|
/*
|
2019-01-18 00:24:08 -04:00
|
|
|
* support for dynamic Write; user-supplies name, format,
|
2016-04-20 02:07:48 -03:00
|
|
|
* labels and values in a single function call.
|
|
|
|
*/
|
2020-01-18 17:57:26 -04:00
|
|
|
HAL_Semaphore log_write_fmts_sem;
|
2016-04-20 02:07:48 -03:00
|
|
|
|
2016-05-04 06:06:23 -03:00
|
|
|
// return (possibly allocating) a log_write_fmt for a name
|
2018-08-08 23:12:18 -03:00
|
|
|
const struct log_write_fmt *log_write_fmt_for_msg_type(uint8_t msg_type) const;
|
2017-11-07 23:32:45 -04:00
|
|
|
|
2018-08-08 23:12:18 -03:00
|
|
|
const struct LogStructure *structure_for_msg_type(uint8_t msg_type);
|
|
|
|
|
2016-04-20 02:07:48 -03:00
|
|
|
// return a msg_type which is not currently in use (or -1 if none available)
|
|
|
|
int16_t find_free_msg_type() const;
|
|
|
|
|
|
|
|
// fill LogStructure with information about msg_type
|
|
|
|
bool fill_log_write_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const;
|
|
|
|
|
2016-07-28 00:06:03 -03:00
|
|
|
bool _armed;
|
|
|
|
|
2019-01-18 00:24:08 -04:00
|
|
|
void Write_Baro_instance(uint64_t time_us, uint8_t baro_instance, enum LogMessages type);
|
|
|
|
void Write_IMU_instance(uint64_t time_us,
|
2017-09-28 23:34:58 -03:00
|
|
|
uint8_t imu_instance,
|
|
|
|
enum LogMessages type);
|
2019-01-18 00:24:08 -04:00
|
|
|
void Write_Compass_instance(uint64_t time_us,
|
2017-09-28 23:53:31 -03:00
|
|
|
uint8_t mag_instance,
|
|
|
|
enum LogMessages type);
|
2020-01-07 19:58:03 -04:00
|
|
|
void Write_Current_instance(uint64_t time_us, uint8_t battery_instance);
|
2019-01-18 00:24:08 -04:00
|
|
|
void Write_IMUDT_instance(uint64_t time_us,
|
2017-09-29 00:28:34 -03:00
|
|
|
uint8_t imu_instance,
|
|
|
|
enum LogMessages type);
|
2017-09-27 21:19:35 -03:00
|
|
|
|
2019-01-18 00:23:42 -04:00
|
|
|
void backend_starting_new_log(const AP_Logger_Backend *backend);
|
2017-04-28 04:37:13 -03:00
|
|
|
|
2019-02-10 14:05:22 -04:00
|
|
|
static AP_Logger *_singleton;
|
2015-12-07 20:21:18 -04:00
|
|
|
|
2017-11-14 20:24:54 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
2017-11-08 00:55:06 -04:00
|
|
|
bool validate_structure(const struct LogStructure *logstructure, int16_t offset);
|
2017-06-14 07:22:18 -03:00
|
|
|
void validate_structures(const struct LogStructure *logstructures, const uint8_t num_types);
|
|
|
|
void dump_structure_field(const struct LogStructure *logstructure, const char *label, const uint8_t fieldnum);
|
|
|
|
void dump_structures(const struct LogStructure *logstructures, const uint8_t num_types);
|
2017-11-14 20:02:56 -04:00
|
|
|
void assert_same_fmt_for_name(const log_write_fmt *f,
|
|
|
|
const char *name,
|
|
|
|
const char *labels,
|
|
|
|
const char *units,
|
|
|
|
const char *mults,
|
|
|
|
const char *fmt) const;
|
2015-12-07 20:21:18 -04:00
|
|
|
const char* unit_name(const uint8_t unit_id);
|
|
|
|
double multiplier_name(const uint8_t multiplier_id);
|
2017-11-08 00:55:06 -04:00
|
|
|
bool seen_ids[256] = { };
|
2020-04-07 02:16:51 -03:00
|
|
|
bool labels_string_is_good(const char *labels) const;
|
2017-11-08 00:55:06 -04:00
|
|
|
#endif
|
2017-04-27 22:34:02 -03:00
|
|
|
|
2017-06-12 10:05:02 -03:00
|
|
|
// possibly expensive calls to start log system:
|
|
|
|
void Prep();
|
2017-06-14 22:21:17 -03:00
|
|
|
|
2018-02-22 05:38:58 -04:00
|
|
|
bool _writes_enabled:1;
|
2018-07-05 20:58:50 -03:00
|
|
|
bool _force_log_disarmed:1;
|
2017-06-14 22:21:17 -03:00
|
|
|
|
2017-06-18 20:43:15 -03:00
|
|
|
/* support for retrieving logs via mavlink: */
|
|
|
|
|
2019-12-04 23:29:47 -04:00
|
|
|
enum class TransferActivity {
|
2018-06-19 21:13:22 -03:00
|
|
|
IDLE, // not doing anything, all file descriptors closed
|
|
|
|
LISTING, // actively sending log_entry packets
|
|
|
|
SENDING, // actively sending log_sending packets
|
2019-12-04 23:29:47 -04:00
|
|
|
} transfer_activity = TransferActivity::IDLE;
|
2017-06-19 22:52:47 -03:00
|
|
|
|
2017-06-18 20:43:15 -03:00
|
|
|
// next log list entry to send
|
|
|
|
uint16_t _log_next_list_entry;
|
|
|
|
|
|
|
|
// last log list entry to send
|
|
|
|
uint16_t _log_last_list_entry;
|
|
|
|
|
|
|
|
// number of log files
|
|
|
|
uint16_t _log_num_logs;
|
|
|
|
|
|
|
|
// log number for data send
|
|
|
|
uint16_t _log_num_data;
|
|
|
|
|
|
|
|
// offset in log
|
|
|
|
uint32_t _log_data_offset;
|
|
|
|
|
|
|
|
// size of log file
|
|
|
|
uint32_t _log_data_size;
|
|
|
|
|
|
|
|
// number of bytes left to send
|
|
|
|
uint32_t _log_data_remaining;
|
|
|
|
|
|
|
|
// start page of log data
|
2019-01-18 18:45:36 -04:00
|
|
|
uint32_t _log_data_page;
|
2017-06-18 20:43:15 -03:00
|
|
|
|
2018-03-19 00:37:21 -03:00
|
|
|
GCS_MAVLINK *_log_sending_link;
|
2020-01-18 17:57:26 -04:00
|
|
|
HAL_Semaphore _log_send_sem;
|
2017-07-16 04:04:14 -03:00
|
|
|
|
2019-06-10 18:55:30 -03:00
|
|
|
// last time arming failed, for backends
|
|
|
|
uint32_t _last_arming_failure_ms;
|
|
|
|
|
2017-06-19 22:52:47 -03:00
|
|
|
bool should_handle_log_message();
|
2019-04-30 07:22:48 -03:00
|
|
|
void handle_log_message(class GCS_MAVLINK &, const mavlink_message_t &msg);
|
2017-06-18 20:43:15 -03:00
|
|
|
|
2019-04-30 07:22:48 -03:00
|
|
|
void handle_log_request_list(class GCS_MAVLINK &, const mavlink_message_t &msg);
|
|
|
|
void handle_log_request_data(class GCS_MAVLINK &, const mavlink_message_t &msg);
|
|
|
|
void handle_log_request_erase(class GCS_MAVLINK &, const mavlink_message_t &msg);
|
|
|
|
void handle_log_request_end(class GCS_MAVLINK &, const mavlink_message_t &msg);
|
2018-06-19 21:13:22 -03:00
|
|
|
void handle_log_send_listing(); // handle LISTING state
|
|
|
|
void handle_log_sending(); // handle SENDING state
|
|
|
|
bool handle_log_send_data(); // send data chunk to client
|
2017-06-18 20:43:15 -03:00
|
|
|
|
|
|
|
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
|
2017-07-08 07:59:28 -03:00
|
|
|
|
|
|
|
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
|
|
|
|
2017-06-18 20:43:15 -03:00
|
|
|
/* end support for retrieving logs via mavlink: */
|
|
|
|
|
2011-11-12 23:29:07 -04:00
|
|
|
};
|
2019-01-17 21:40:57 -04:00
|
|
|
|
|
|
|
namespace AP {
|
|
|
|
AP_Logger &logger();
|
|
|
|
};
|