2013-01-12 02:21:04 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
2011-11-12 23:29:07 -04:00
|
|
|
/* ************************************************************ */
|
|
|
|
/* Test for DataFlash Log library */
|
|
|
|
/* ************************************************************ */
|
|
|
|
#ifndef DataFlash_h
|
|
|
|
#define DataFlash_h
|
|
|
|
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
|
|
|
#include <AP_GPS/AP_GPS.h>
|
|
|
|
#include <AP_InertialSensor/AP_InertialSensor.h>
|
2015-09-04 12:50:23 -03:00
|
|
|
#include <AP_RSSI/AP_RSSI.h>
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_Baro/AP_Baro.h>
|
|
|
|
#include <AP_AHRS/AP_AHRS.h>
|
|
|
|
#include <AP_Vehicle/AP_Vehicle.h>
|
|
|
|
#include <AP_Mission/AP_Mission.h>
|
2015-08-15 19:53:26 -03:00
|
|
|
#include <AP_Airspeed/AP_Airspeed.h>
|
|
|
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
|
|
|
#include <AP_RPM/AP_RPM.h>
|
2015-09-14 03:44:45 -03:00
|
|
|
#include <AP_RangeFinder/AP_RangeFinder.h>
|
2015-11-05 19:50:54 -04:00
|
|
|
#include <DataFlash/LogStructure.h>
|
2011-11-12 23:29:07 -04:00
|
|
|
#include <stdint.h>
|
|
|
|
|
2014-11-20 23:48:44 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
2014-11-13 06:38:33 -04:00
|
|
|
#include <uORB/topics/esc_status.h>
|
2014-11-20 23:48:44 -04:00
|
|
|
#endif
|
2014-11-13 06:38:33 -04:00
|
|
|
|
2015-08-06 09:18:28 -03:00
|
|
|
#include "DFMessageWriter.h"
|
2014-11-13 06:38:33 -04:00
|
|
|
|
2015-06-25 10:53:20 -03:00
|
|
|
class DataFlash_Backend;
|
2015-11-09 18:14:22 -04:00
|
|
|
|
|
|
|
enum DataFlash_Backend_Type {
|
|
|
|
DATAFLASH_BACKEND_NONE = 0,
|
|
|
|
DATAFLASH_BACKEND_FILE = 1,
|
2015-11-10 02:34:31 -04:00
|
|
|
DATAFLASH_BACKEND_MAVLINK = 2,
|
|
|
|
DATAFLASH_BACKEND_BOTH = 3,
|
2015-11-09 18:14:22 -04:00
|
|
|
};
|
2014-08-01 02:57:15 -03:00
|
|
|
|
2011-11-12 23:29:07 -04:00
|
|
|
class DataFlash_Class
|
|
|
|
{
|
2015-11-09 18:14:22 -04:00
|
|
|
friend class DataFlash_Backend; // for _num_types
|
2015-08-06 09:18:28 -03:00
|
|
|
|
2013-02-22 20:17:34 -04:00
|
|
|
public:
|
2015-05-24 18:55:06 -03:00
|
|
|
FUNCTOR_TYPEDEF(print_mode_fn, void, AP_HAL::BetterStream*, uint8_t);
|
2015-08-06 09:18:28 -03:00
|
|
|
FUNCTOR_TYPEDEF(vehicle_startup_message_Log_Writer, void);
|
2015-10-26 08:25:44 -03:00
|
|
|
DataFlash_Class(const char *firmware_string) :
|
2015-11-09 18:14:22 -04:00
|
|
|
_firmware_string(firmware_string)
|
|
|
|
{
|
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
}
|
2015-08-06 09:18:28 -03:00
|
|
|
|
|
|
|
void set_mission(const AP_Mission *mission);
|
2015-05-12 03:59:55 -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);
|
|
|
|
bool CardInserted(void);
|
2013-02-22 20:17:34 -04:00
|
|
|
|
|
|
|
// erase handling
|
2015-06-25 10:53:20 -03:00
|
|
|
bool NeedErase(void);
|
|
|
|
void EraseAll();
|
2013-02-22 20:17:34 -04:00
|
|
|
|
2015-08-08 03:13:38 -03:00
|
|
|
// possibly expensive calls to start log system:
|
|
|
|
bool NeedPrep();
|
|
|
|
void Prep();
|
|
|
|
|
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;
|
2015-06-25 10:53:20 -03:00
|
|
|
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
|
|
|
|
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
|
|
|
|
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
|
|
|
uint16_t get_num_logs(void);
|
|
|
|
void LogReadProcess(uint16_t log_num,
|
2013-04-19 04:49:16 -03:00
|
|
|
uint16_t start_page, uint16_t end_page,
|
2015-05-12 03:59:55 -03:00
|
|
|
print_mode_fn printMode,
|
2015-06-25 10:53:20 -03:00
|
|
|
AP_HAL::BetterStream *port);
|
|
|
|
void DumpPageInfo(AP_HAL::BetterStream *port);
|
|
|
|
void ShowDeviceInfo(AP_HAL::BetterStream *port);
|
|
|
|
void ListAvailableLogs(AP_HAL::BetterStream *port);
|
2013-02-22 20:17:34 -04:00
|
|
|
|
2015-08-06 09:18:28 -03:00
|
|
|
void setVehicle_Startup_Log_Writer(vehicle_startup_message_Log_Writer writer);
|
|
|
|
|
2015-11-09 18:14:22 -04:00
|
|
|
void StartNewLog(void);
|
2015-06-25 10:53:20 -03:00
|
|
|
void EnableWrites(bool enable);
|
2015-11-09 18:14:22 -04:00
|
|
|
void Log_Write_Format(const struct LogStructure *structure);
|
|
|
|
void Log_Write_Parameter(const char *name, float value);
|
2014-04-09 21:29:30 -03:00
|
|
|
void Log_Write_GPS(const AP_GPS &gps, uint8_t instance, int32_t relative_alt);
|
2015-09-10 07:27:47 -03:00
|
|
|
void Log_Write_RFND(const RangeFinder &rangefinder);
|
2013-11-03 23:36:14 -04:00
|
|
|
void Log_Write_IMU(const AP_InertialSensor &ins);
|
2015-06-13 10:06:49 -03:00
|
|
|
void Log_Write_IMUDT(const AP_InertialSensor &ins);
|
2015-06-11 10:26:45 -03:00
|
|
|
void Log_Write_Vibration(const AP_InertialSensor &ins);
|
2013-11-25 17:44:00 -04:00
|
|
|
void Log_Write_RCIN(void);
|
2013-11-27 07:14:17 -04:00
|
|
|
void Log_Write_RCOUT(void);
|
2015-09-04 12:50:23 -03:00
|
|
|
void Log_Write_RSSI(AP_RSSI &rssi);
|
2014-01-27 19:35:18 -04:00
|
|
|
void Log_Write_Baro(AP_Baro &baro);
|
2014-02-13 07:07:32 -04:00
|
|
|
void Log_Write_Power(void);
|
2014-01-03 01:01:08 -04:00
|
|
|
void Log_Write_AHRS2(AP_AHRS &ahrs);
|
2015-05-14 22:59:40 -03:00
|
|
|
void Log_Write_POS(AP_AHRS &ahrs);
|
2014-01-03 20:51:22 -04:00
|
|
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
2014-12-23 16:39:23 -04:00
|
|
|
void Log_Write_EKF(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled);
|
2015-09-22 23:09:48 -03:00
|
|
|
void Log_Write_EKF2(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled);
|
2014-01-03 20:51:22 -04:00
|
|
|
#endif
|
2015-08-06 09:18:28 -03:00
|
|
|
bool Log_Write_MavCmd(uint16_t cmd_total, const mavlink_mission_item_t& mav_cmd);
|
2014-03-11 14:05:02 -03:00
|
|
|
void Log_Write_Radio(const mavlink_radio_t &packet);
|
2015-11-09 18:14:22 -04:00
|
|
|
void Log_Write_Message(const char *message);
|
2014-06-10 23:55:04 -03:00
|
|
|
void Log_Write_Camera(const AP_AHRS &ahrs, const AP_GPS &gps, const Location ¤t_loc);
|
2014-11-13 06:38:33 -04:00
|
|
|
void Log_Write_ESC(void);
|
2015-01-19 18:10:33 -04:00
|
|
|
void Log_Write_Airspeed(AP_Airspeed &airspeed);
|
2015-01-20 15:44:39 -04:00
|
|
|
void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets);
|
2015-05-21 22:42:08 -03:00
|
|
|
void Log_Write_Current(const AP_BattMonitor &battery, int16_t throttle);
|
2015-01-16 18:27:01 -04:00
|
|
|
void Log_Write_Compass(const Compass &compass);
|
2015-11-09 18:14:22 -04:00
|
|
|
void Log_Write_Mode(uint8_t mode);
|
2013-04-19 04:49:16 -03:00
|
|
|
|
2015-06-30 01:33:50 -03:00
|
|
|
void Log_Write_EntireMission(const AP_Mission &mission);
|
2015-11-09 18:14:22 -04:00
|
|
|
void Log_Write_Mission_Cmd(const AP_Mission &mission,
|
2015-06-30 01:33:50 -03:00
|
|
|
const AP_Mission::Mission_Command &cmd);
|
2015-07-03 08:49:45 -03:00
|
|
|
void Log_Write_Origin(uint8_t origin_type, const Location &loc);
|
2015-08-07 07:34:14 -03:00
|
|
|
void Log_Write_RPM(const AP_RPM &rpm_sensor);
|
2015-06-30 01:33:50 -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 {
|
2015-05-22 19:56:05 -03:00
|
|
|
float desired;
|
2015-05-21 22:42:08 -03:00
|
|
|
float P;
|
|
|
|
float I;
|
|
|
|
float D;
|
|
|
|
float FF;
|
2015-05-22 20:57:49 -03:00
|
|
|
float AFF;
|
2015-05-21 22:42:08 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
void Log_Write_PID(uint8_t msg_type, const PID_Info &info);
|
|
|
|
|
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
|
|
|
|
// currently only DataFlash_File support this:
|
|
|
|
void flush(void);
|
|
|
|
#endif
|
|
|
|
|
2015-11-10 02:34:31 -04:00
|
|
|
// for DataFlash_MAVLink:
|
|
|
|
void remote_log_block_status_msg(mavlink_channel_t chan,
|
|
|
|
mavlink_message_t* msg);
|
|
|
|
// end for DataFlash_MAVLink:
|
|
|
|
|
2015-08-06 09:18:28 -03:00
|
|
|
void periodic_tasks(); // may want to split this into GCS/non-GCS duties
|
|
|
|
|
|
|
|
// this is out here for the trickle-startup-messages logging.
|
|
|
|
// Think before calling.
|
|
|
|
bool Log_Write_Parameter(const AP_Param *ap, const AP_Param::ParamToken &token,
|
|
|
|
enum ap_var_type type);
|
|
|
|
|
|
|
|
vehicle_startup_message_Log_Writer _vehicle_messages;
|
|
|
|
|
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
|
2015-11-09 18:14:22 -04:00
|
|
|
} _params;
|
|
|
|
|
|
|
|
const struct LogStructure *structure(uint16_t num) const;
|
|
|
|
|
2013-04-19 04:49:16 -03:00
|
|
|
protected:
|
2013-12-16 20:12:42 -04:00
|
|
|
void Log_Fill_Format(const struct LogStructure *structure, struct log_Format &pkt);
|
2013-04-19 21:25:10 -03:00
|
|
|
|
2015-08-06 09:18:28 -03:00
|
|
|
void WroteStartupFormat();
|
|
|
|
void WroteStartupParam();
|
|
|
|
|
2013-12-16 20:12:42 -04:00
|
|
|
const struct LogStructure *_structures;
|
|
|
|
uint8_t _num_types;
|
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:
|
2015-11-09 18:14:22 -04:00
|
|
|
#define DATAFLASH_MAX_BACKENDS 2
|
|
|
|
uint8_t _next_backend;
|
|
|
|
DataFlash_Backend *backends[DATAFLASH_MAX_BACKENDS];
|
|
|
|
const char *_firmware_string;
|
2011-11-12 23:29:07 -04:00
|
|
|
};
|
|
|
|
|
2011-11-07 07:21:29 -04:00
|
|
|
#endif
|