26 virtual void Prep() = 0;
42 virtual void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) = 0;
43 virtual int16_t
get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) = 0;
69 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX 76 mavlink_message_t* msg) { }
92 bool Log_Write_MavCmd(uint16_t cmd_total,
const mavlink_mission_item_t& mav_cmd);
115 bool Log_Write(uint8_t msg_type, va_list arg_list,
bool is_critical=
false);
143 virtual bool ReadBlock(
void *pkt, uint16_t size) = 0;
virtual void stop_logging(void)=0
virtual void WriteMoreStartupMessages()
bool Log_Write_Message(const char *message)
uint32_t num_dropped(void) const
bool Log_Write_Emit_FMT(uint8_t msg_type)
DFMessageWriter_DFLogStart * _startup_messagewriter
vehicle_startup_message_Log_Writer vehicle_message_writer()
bool Log_Write_Format_Units(const struct LogStructure *structure)
bool Log_Write_Format(const struct LogStructure *structure)
uint8_t num_types() const
virtual bool CardInserted(void) const =0
bool Log_Write_Parameter(const char *name, float value)
virtual bool StartNewLogOK() const
virtual void periodic_tasks()
virtual void start_new_log_reset_variables()
bool _writing_startup_messages
bool WriteCriticalBlock(const void *pBuffer, uint16_t size)
virtual void get_log_boundaries(uint16_t log_num, uint16_t &start_page, uint16_t &end_page)=0
const struct UnitStructure * unit(uint8_t unit) const
uint8_t num_units() const
bool Log_Write_Unit(const struct UnitStructure *s)
uint8_t num_multipliers() const
bool Log_Write_Mission_Cmd(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd)
virtual void remote_log_block_status_msg(mavlink_channel_t chan, mavlink_message_t *msg)
const struct LogStructure * structure(uint8_t structure) const
virtual void vehicle_was_disarmed()
bool Log_Write_MavCmd(uint16_t cmd_total, const mavlink_mission_item_t &mav_cmd)
virtual int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)=0
virtual bool _WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)=0
FUNCTOR_TYPEDEF(vehicle_startup_message_Log_Writer, void)
virtual bool WritesOK() const =0
virtual uint16_t find_last_log()=0
virtual bool WriteBlockCheckStartupMessages()
bool WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
void Log_Fill_Format_Units(const struct LogStructure *s, struct log_Format_Units &pkt)
virtual void EraseAll()=0
virtual void periodic_10Hz(const uint32_t now)
virtual void periodic_fullrate(const uint32_t now)
virtual bool logging_enabled() const =0
void set_mission(const AP_Mission *mission)
virtual bool logging_failed() const =0
const struct MultiplierStructure * multiplier(uint8_t multiplier) const
DataFlash_Backend(DataFlash_Class &front, class DFMessageWriter_DFLogStart *writer)
void Log_Write_EntireMission(const AP_Mission &mission)
virtual uint16_t get_num_logs()=0
bool ShouldLog(bool is_critical)
void Log_Fill_Format(const struct LogStructure *structure, struct log_Format &pkt)
virtual void periodic_1Hz(const uint32_t now)
AP_HAL::AnalogSource * chan
virtual uint32_t bufferspace_available()=0
virtual void PrepForArming()
uint32_t _last_periodic_1Hz
virtual uint16_t start_new_log(void)=0
bool Log_Write(uint8_t msg_type, va_list arg_list, bool is_critical=false)
bool WriteBlock(const void *pBuffer, uint16_t size)
virtual bool NeedPrep()=0
uint32_t _last_periodic_10Hz
virtual void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc)=0
virtual void push_log_blocks()
bool Log_Write_Multiplier(const struct MultiplierStructure *s)
virtual bool logging_started(void) const =0
bool Log_Write_Mode(uint8_t mode, uint8_t reason=0)
virtual bool ReadBlock(void *pkt, uint16_t size)=0