AP_Logger.h 19 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526
  1. /* ************************************************************ */
  2. /* Test for AP_Logger Log library */
  3. /* ************************************************************ */
  4. #pragma once
  5. #include <AP_HAL/AP_HAL.h>
  6. #include <AP_Common/AP_Common.h>
  7. #include <AP_Param/AP_Param.h>
  8. #include <AP_InertialSensor/AP_InertialSensor.h>
  9. #include <AP_Mission/AP_Mission.h>
  10. #include <AP_RPM/AP_RPM.h>
  11. #include <AP_Logger/LogStructure.h>
  12. #include <AP_Motors/AP_Motors.h>
  13. #include <AP_Rally/AP_Rally.h>
  14. #include <AP_Beacon/AP_Beacon.h>
  15. #include <AP_Proximity/AP_Proximity.h>
  16. #include <AP_InertialSensor/AP_InertialSensor_Backend.h>
  17. #include <stdint.h>
  18. #include "LoggerMessageWriter.h"
  19. class AP_Logger_Backend;
  20. class AP_AHRS;
  21. class AP_AHRS_View;
  22. // do not do anything here apart from add stuff; maintaining older
  23. // entries means log analysis is easier
  24. enum Log_Event : uint8_t {
  25. DATA_AP_STATE = 7,
  26. // DATA_SYSTEM_TIME_SET = 8,
  27. DATA_INIT_SIMPLE_BEARING = 9,
  28. DATA_ARMED = 10,
  29. DATA_DISARMED = 11,
  30. DATA_AUTO_ARMED = 15,
  31. DATA_LAND_COMPLETE_MAYBE = 17,
  32. DATA_LAND_COMPLETE = 18,
  33. DATA_NOT_LANDED = 28,
  34. DATA_LOST_GPS = 19,
  35. DATA_FLIP_START = 21,
  36. DATA_FLIP_END = 22,
  37. DATA_SET_HOME = 25,
  38. DATA_SET_SIMPLE_ON = 26,
  39. DATA_SET_SIMPLE_OFF = 27,
  40. DATA_SET_SUPERSIMPLE_ON = 29,
  41. DATA_AUTOTUNE_INITIALISED = 30,
  42. DATA_AUTOTUNE_OFF = 31,
  43. DATA_AUTOTUNE_RESTART = 32,
  44. DATA_AUTOTUNE_SUCCESS = 33,
  45. DATA_AUTOTUNE_FAILED = 34,
  46. DATA_AUTOTUNE_REACHED_LIMIT = 35,
  47. DATA_AUTOTUNE_PILOT_TESTING = 36,
  48. DATA_AUTOTUNE_SAVEDGAINS = 37,
  49. DATA_SAVE_TRIM = 38,
  50. DATA_SAVEWP_ADD_WP = 39,
  51. DATA_FENCE_ENABLE = 41,
  52. DATA_FENCE_DISABLE = 42,
  53. DATA_ACRO_TRAINER_DISABLED = 43,
  54. DATA_ACRO_TRAINER_LEVELING = 44,
  55. DATA_ACRO_TRAINER_LIMITED = 45,
  56. DATA_GRIPPER_GRAB = 46,
  57. DATA_GRIPPER_RELEASE = 47,
  58. DATA_PARACHUTE_DISABLED = 49,
  59. DATA_PARACHUTE_ENABLED = 50,
  60. DATA_PARACHUTE_RELEASED = 51,
  61. DATA_LANDING_GEAR_DEPLOYED = 52,
  62. DATA_LANDING_GEAR_RETRACTED = 53,
  63. DATA_MOTORS_EMERGENCY_STOPPED = 54,
  64. DATA_MOTORS_EMERGENCY_STOP_CLEARED = 55,
  65. DATA_MOTORS_INTERLOCK_DISABLED = 56,
  66. DATA_MOTORS_INTERLOCK_ENABLED = 57,
  67. DATA_ROTOR_RUNUP_COMPLETE = 58, // Heli only
  68. DATA_ROTOR_SPEED_BELOW_CRITICAL = 59, // Heli only
  69. DATA_EKF_ALT_RESET = 60,
  70. DATA_LAND_CANCELLED_BY_PILOT = 61,
  71. DATA_EKF_YAW_RESET = 62,
  72. DATA_AVOIDANCE_ADSB_ENABLE = 63,
  73. DATA_AVOIDANCE_ADSB_DISABLE = 64,
  74. DATA_AVOIDANCE_PROXIMITY_ENABLE = 65,
  75. DATA_AVOIDANCE_PROXIMITY_DISABLE = 66,
  76. DATA_GPS_PRIMARY_CHANGED = 67,
  77. DATA_WINCH_RELAXED = 68,
  78. DATA_WINCH_LENGTH_CONTROL = 69,
  79. DATA_WINCH_RATE_CONTROL = 70,
  80. DATA_ZIGZAG_STORE_A = 71,
  81. DATA_ZIGZAG_STORE_B = 72,
  82. DATA_LAND_REPO_ACTIVE = 73,
  83. DATA_SURFACED = 163,
  84. DATA_NOT_SURFACED = 164,
  85. DATA_BOTTOMED = 165,
  86. DATA_NOT_BOTTOMED = 166,
  87. };
  88. enum class LogErrorSubsystem : uint8_t {
  89. MAIN = 1,
  90. RADIO = 2,
  91. COMPASS = 3,
  92. OPTFLOW = 4, // not used
  93. FAILSAFE_RADIO = 5,
  94. FAILSAFE_BATT = 6,
  95. FAILSAFE_GPS = 7, // not used
  96. FAILSAFE_GCS = 8,
  97. FAILSAFE_FENCE = 9,
  98. FLIGHT_MODE = 10,
  99. GPS = 11,
  100. CRASH_CHECK = 12,
  101. FLIP = 13,
  102. AUTOTUNE = 14, // not used
  103. PARACHUTES = 15,
  104. EKFCHECK = 16,
  105. FAILSAFE_EKFINAV = 17,
  106. BARO = 18,
  107. CPU = 19,
  108. FAILSAFE_ADSB = 20,
  109. TERRAIN = 21,
  110. NAVIGATION = 22,
  111. FAILSAFE_TERRAIN = 23,
  112. EKF_PRIMARY = 24,
  113. THRUST_LOSS_CHECK = 25,
  114. FAILSAFE_SENSORS = 26,
  115. FAILSAFE_LEAK = 27,
  116. PILOT_INPUT = 28,
  117. };
  118. // bizarrely this enumeration has lots of duplicate values, offering
  119. // very little in the way of typesafety
  120. enum class LogErrorCode : uint8_t {
  121. // general error codes
  122. ERROR_RESOLVED = 0,
  123. FAILED_TO_INITIALISE = 1,
  124. UNHEALTHY = 4,
  125. // subsystem specific error codes -- radio
  126. RADIO_LATE_FRAME = 2,
  127. // subsystem specific error codes -- failsafe_thr, batt, gps
  128. FAILSAFE_RESOLVED = 0,
  129. FAILSAFE_OCCURRED = 1,
  130. // subsystem specific error codes -- main
  131. MAIN_INS_DELAY = 1,
  132. // subsystem specific error codes -- crash checker
  133. CRASH_CHECK_CRASH = 1,
  134. CRASH_CHECK_LOSS_OF_CONTROL = 2,
  135. // subsystem specific error codes -- flip
  136. FLIP_ABANDONED = 2,
  137. // subsystem specific error codes -- terrain
  138. MISSING_TERRAIN_DATA = 2,
  139. // subsystem specific error codes -- navigation
  140. FAILED_TO_SET_DESTINATION = 2,
  141. RESTARTED_RTL = 3,
  142. FAILED_CIRCLE_INIT = 4,
  143. DEST_OUTSIDE_FENCE = 5,
  144. // parachute failed to deploy because of low altitude or landed
  145. PARACHUTE_TOO_LOW = 2,
  146. PARACHUTE_LANDED = 3,
  147. // EKF check definitions
  148. EKFCHECK_BAD_VARIANCE = 2,
  149. EKFCHECK_VARIANCE_CLEARED = 0,
  150. // Baro specific error codes
  151. BARO_GLITCH = 2,
  152. BAD_DEPTH = 3, // sub-only
  153. // GPS specific error coces
  154. GPS_GLITCH = 2,
  155. };
  156. // fwd declarations to avoid include errors
  157. class AC_AttitudeControl;
  158. class AC_PosControl;
  159. class AP_Logger
  160. {
  161. friend class AP_Logger_Backend; // for _num_types
  162. public:
  163. FUNCTOR_TYPEDEF(vehicle_startup_message_Writer, void);
  164. AP_Logger(const AP_Int32 &log_bitmask);
  165. /* Do not allow copies */
  166. AP_Logger(const AP_Logger &other) = delete;
  167. AP_Logger &operator=(const AP_Logger&) = delete;
  168. // get singleton instance
  169. static AP_Logger *get_singleton(void) {
  170. return _singleton;
  171. }
  172. // initialisation
  173. void Init(const struct LogStructure *structure, uint8_t num_types);
  174. void set_num_types(uint8_t num_types) { _num_types = num_types; }
  175. bool CardInserted(void);
  176. // erase handling
  177. void EraseAll();
  178. /* Write a block of data at current offset */
  179. void WriteBlock(const void *pBuffer, uint16_t size);
  180. /* Write an *important* block of data at current offset */
  181. void WriteCriticalBlock(const void *pBuffer, uint16_t size);
  182. // high level interface
  183. uint16_t find_last_log() const;
  184. void get_log_boundaries(uint16_t log_num, uint32_t & start_page, uint32_t & end_page);
  185. uint16_t get_num_logs(void);
  186. void setVehicle_Startup_Writer(vehicle_startup_message_Writer writer);
  187. void PrepForArming();
  188. void EnableWrites(bool enable) { _writes_enabled = enable; }
  189. bool WritesEnabled() const { return _writes_enabled; }
  190. void StopLogging();
  191. void Write_Parameter(const char *name, float value);
  192. void Write_Event(Log_Event id);
  193. void Write_Error(LogErrorSubsystem sub_system,
  194. LogErrorCode error_code);
  195. void Write_GPS(uint8_t instance, uint64_t time_us=0);
  196. void Write_IMU();
  197. void Write_IMUDT(uint64_t time_us, uint8_t imu_mask);
  198. bool Write_ISBH(uint16_t seqno,
  199. AP_InertialSensor::IMU_SENSOR_TYPE sensor_type,
  200. uint8_t instance,
  201. uint16_t multiplier,
  202. uint16_t sample_count,
  203. uint64_t sample_us,
  204. float sample_rate_hz);
  205. bool Write_ISBD(uint16_t isb_seqno,
  206. uint16_t seqno,
  207. const int16_t x[32],
  208. const int16_t y[32],
  209. const int16_t z[32]);
  210. void Write_Vibration();
  211. void Write_RCIN(void);
  212. void Write_RCOUT(void);
  213. void Write_RSSI();
  214. void Write_Rally();
  215. void Write_Baro(uint64_t time_us=0);
  216. void Write_Power(void);
  217. void Write_AHRS2(AP_AHRS &ahrs);
  218. void Write_POS(AP_AHRS &ahrs);
  219. void Write_Radio(const mavlink_radio_t &packet);
  220. void Write_Message(const char *message);
  221. void Write_MessageF(const char *fmt, ...);
  222. void Write_CameraInfo(enum LogMessages msg, const Location &current_loc, uint64_t timestamp_us=0);
  223. void Write_Camera(const Location &current_loc, uint64_t timestamp_us=0);
  224. void Write_Trigger(const Location &current_loc);
  225. void Write_ESC(uint8_t id, uint64_t time_us, int32_t rpm, uint16_t voltage, uint16_t current, int16_t temperature, uint16_t current_tot);
  226. void Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets);
  227. void Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets);
  228. void Write_Current();
  229. void Write_Compass(uint64_t time_us=0);
  230. void Write_Mode(uint8_t mode, uint8_t reason);
  231. void Write_EntireMission();
  232. void Write_Command(const mavlink_command_int_t &packet, MAV_RESULT result, bool was_command_long=false);
  233. void Write_Mission_Cmd(const AP_Mission &mission,
  234. const AP_Mission::Mission_Command &cmd);
  235. void Write_Origin(uint8_t origin_type, const Location &loc);
  236. void Write_RPM(const AP_RPM &rpm_sensor);
  237. void Write_Rate(const AP_AHRS_View *ahrs,
  238. const AP_Motors &motors,
  239. const AC_AttitudeControl &attitude_control,
  240. const AC_PosControl &pos_control);
  241. void Write_RallyPoint(uint8_t total,
  242. uint8_t sequence,
  243. const RallyLocation &rally_point);
  244. void Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence);
  245. void Write_AOA_SSA(AP_AHRS &ahrs);
  246. void Write_Beacon(AP_Beacon &beacon);
  247. void Write_Proximity(AP_Proximity &proximity);
  248. void Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f& point);
  249. void Write_OABendyRuler(bool active, float target_yaw, float margin, const Location &final_dest, const Location &oa_dest);
  250. void Write_OADijkstra(uint8_t state, uint8_t curr_point, uint8_t tot_points, const Location &final_dest, const Location &oa_dest);
  251. void Write(const char *name, const char *labels, const char *fmt, ...);
  252. void Write(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...);
  253. void WriteCritical(const char *name, const char *labels, const char *fmt, ...);
  254. void WriteCritical(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...);
  255. 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);
  256. // This structure provides information on the internal member data of a PID for logging purposes
  257. struct PID_Info {
  258. float target;
  259. float actual;
  260. float error;
  261. float P;
  262. float I;
  263. float D;
  264. float FF;
  265. };
  266. void Write_PID(uint8_t msg_type, const PID_Info &info);
  267. // returns true if logging of a message should be attempted
  268. bool should_log(uint32_t mask) const;
  269. bool logging_started(void);
  270. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
  271. // currently only AP_Logger_File support this:
  272. void flush(void);
  273. #endif
  274. void handle_mavlink_msg(class GCS_MAVLINK &, const mavlink_message_t &msg);
  275. void periodic_tasks(); // may want to split this into GCS/non-GCS duties
  276. // number of blocks that have been dropped
  277. uint32_t num_dropped(void) const;
  278. // accesss to public parameters
  279. void set_force_log_disarmed(bool force_logging) { _force_log_disarmed = force_logging; }
  280. bool log_while_disarmed(void) const;
  281. uint8_t log_replay(void) const { return _params.log_replay; }
  282. vehicle_startup_message_Writer _vehicle_messages;
  283. // parameter support
  284. static const struct AP_Param::GroupInfo var_info[];
  285. struct {
  286. AP_Int8 backend_types;
  287. AP_Int8 file_bufsize; // in kilobytes
  288. AP_Int8 file_disarm_rot;
  289. AP_Int8 log_disarmed;
  290. AP_Int8 log_replay;
  291. AP_Int8 mav_bufsize; // in kilobytes
  292. AP_Int16 file_timeout; // in seconds
  293. } _params;
  294. const struct LogStructure *structure(uint16_t num) const;
  295. const struct UnitStructure *unit(uint16_t num) const;
  296. const struct MultiplierStructure *multiplier(uint16_t num) const;
  297. // methods for mavlink SYS_STATUS message (send_sys_status)
  298. // these methods cover only the first logging backend used -
  299. // typically AP_Logger_File.
  300. bool logging_present() const;
  301. bool logging_enabled() const;
  302. bool logging_failed() const;
  303. // notify logging subsystem of an arming failure. This triggers
  304. // logging for HAL_LOGGER_ARM_PERSIST seconds
  305. void arming_failure() { _last_arming_failure_ms = AP_HAL::millis(); }
  306. void set_vehicle_armed(bool armed_state);
  307. bool vehicle_is_armed() const { return _armed; }
  308. void handle_log_send();
  309. bool in_log_download() const { return transfer_activity != IDLE; }
  310. float quiet_nanf() const { return nanf("0x4152"); } // "AR"
  311. double quiet_nan() const { return nan("0x4152445550490a"); } // "ARDUPI"
  312. // returns true if msg_type is associated with a message
  313. bool msg_type_in_use(uint8_t msg_type) const;
  314. protected:
  315. const struct LogStructure *_structures;
  316. uint8_t _num_types;
  317. const struct UnitStructure *_units = log_Units;
  318. const struct MultiplierStructure *_multipliers = log_Multipliers;
  319. const uint8_t _num_units = (sizeof(log_Units) / sizeof(log_Units[0]));
  320. const uint8_t _num_multipliers = (sizeof(log_Multipliers) / sizeof(log_Multipliers[0]));
  321. /* Write a block with specified importance */
  322. /* might be useful if you have a boolean indicating a message is
  323. * important... */
  324. void WritePrioritisedBlock(const void *pBuffer, uint16_t size,
  325. bool is_critical);
  326. private:
  327. #define LOGGER_MAX_BACKENDS 2
  328. uint8_t _next_backend;
  329. AP_Logger_Backend *backends[LOGGER_MAX_BACKENDS];
  330. const AP_Int32 &_log_bitmask;
  331. enum class Backend_Type : uint8_t {
  332. NONE = 0,
  333. FILESYSTEM = (1<<0),
  334. MAVLINK = (1<<1),
  335. BLOCK = (1<<2),
  336. };
  337. /*
  338. * support for dynamic Write; user-supplies name, format,
  339. * labels and values in a single function call.
  340. */
  341. // this structure looks much like struct LogStructure in
  342. // LogStructure.h, however we need to remember a pointer value for
  343. // efficiency of finding message types
  344. struct log_write_fmt {
  345. struct log_write_fmt *next;
  346. uint8_t msg_type;
  347. uint8_t msg_len;
  348. uint8_t sent_mask; // bitmask of backends sent to
  349. const char *name;
  350. const char *fmt;
  351. const char *labels;
  352. const char *units;
  353. const char *mults;
  354. } *log_write_fmts;
  355. // return (possibly allocating) a log_write_fmt for a name
  356. struct log_write_fmt *msg_fmt_for_name(const char *name, const char *labels, const char *units, const char *mults, const char *fmt);
  357. const struct log_write_fmt *log_write_fmt_for_msg_type(uint8_t msg_type) const;
  358. const struct LogStructure *structure_for_msg_type(uint8_t msg_type);
  359. // return a msg_type which is not currently in use (or -1 if none available)
  360. int16_t find_free_msg_type() const;
  361. // fill LogStructure with information about msg_type
  362. bool fill_log_write_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const;
  363. // calculate the length of a message using fields specified in
  364. // fmt; includes the message header
  365. int16_t Write_calc_msg_len(const char *fmt) const;
  366. bool _armed;
  367. void Write_Baro_instance(uint64_t time_us, uint8_t baro_instance, enum LogMessages type);
  368. void Write_IMU_instance(uint64_t time_us,
  369. uint8_t imu_instance,
  370. enum LogMessages type);
  371. void Write_Compass_instance(uint64_t time_us,
  372. uint8_t mag_instance,
  373. enum LogMessages type);
  374. void Write_Current_instance(uint64_t time_us,
  375. uint8_t battery_instance,
  376. enum LogMessages type,
  377. enum LogMessages celltype);
  378. void Write_IMUDT_instance(uint64_t time_us,
  379. uint8_t imu_instance,
  380. enum LogMessages type);
  381. void backend_starting_new_log(const AP_Logger_Backend *backend);
  382. static AP_Logger *_singleton;
  383. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  384. bool validate_structure(const struct LogStructure *logstructure, int16_t offset);
  385. void validate_structures(const struct LogStructure *logstructures, const uint8_t num_types);
  386. void dump_structure_field(const struct LogStructure *logstructure, const char *label, const uint8_t fieldnum);
  387. void dump_structures(const struct LogStructure *logstructures, const uint8_t num_types);
  388. void assert_same_fmt_for_name(const log_write_fmt *f,
  389. const char *name,
  390. const char *labels,
  391. const char *units,
  392. const char *mults,
  393. const char *fmt) const;
  394. const char* unit_name(const uint8_t unit_id);
  395. double multiplier_name(const uint8_t multiplier_id);
  396. bool seen_ids[256] = { };
  397. #endif
  398. // possibly expensive calls to start log system:
  399. void Prep();
  400. bool _writes_enabled:1;
  401. bool _force_log_disarmed:1;
  402. /* support for retrieving logs via mavlink: */
  403. enum transfer_activity_t : uint8_t {
  404. IDLE, // not doing anything, all file descriptors closed
  405. LISTING, // actively sending log_entry packets
  406. SENDING, // actively sending log_sending packets
  407. } transfer_activity = IDLE;
  408. // next log list entry to send
  409. uint16_t _log_next_list_entry;
  410. // last log list entry to send
  411. uint16_t _log_last_list_entry;
  412. // number of log files
  413. uint16_t _log_num_logs;
  414. // log number for data send
  415. uint16_t _log_num_data;
  416. // offset in log
  417. uint32_t _log_data_offset;
  418. // size of log file
  419. uint32_t _log_data_size;
  420. // number of bytes left to send
  421. uint32_t _log_data_remaining;
  422. // start page of log data
  423. uint32_t _log_data_page;
  424. GCS_MAVLINK *_log_sending_link;
  425. HAL_Semaphore_Recursive _log_send_sem;
  426. // last time arming failed, for backends
  427. uint32_t _last_arming_failure_ms;
  428. bool should_handle_log_message();
  429. void handle_log_message(class GCS_MAVLINK &, const mavlink_message_t &msg);
  430. void handle_log_request_list(class GCS_MAVLINK &, const mavlink_message_t &msg);
  431. void handle_log_request_data(class GCS_MAVLINK &, const mavlink_message_t &msg);
  432. void handle_log_request_erase(class GCS_MAVLINK &, const mavlink_message_t &msg);
  433. void handle_log_request_end(class GCS_MAVLINK &, const mavlink_message_t &msg);
  434. void handle_log_send_listing(); // handle LISTING state
  435. void handle_log_sending(); // handle SENDING state
  436. bool handle_log_send_data(); // send data chunk to client
  437. void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
  438. int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
  439. /* end support for retrieving logs via mavlink: */
  440. };
  441. namespace AP {
  442. AP_Logger &logger();
  443. };