APM:Libraries
|
#include <DataFlash.h>
Classes | |
struct | log_write_fmt |
struct | PID_Info |
Public Member Functions | |
FUNCTOR_TYPEDEF (vehicle_startup_message_Log_Writer, void) | |
DataFlash_Class (const char *firmware_string, const AP_Int32 &log_bitmask) | |
DataFlash_Class (const DataFlash_Class &other)=delete | |
DataFlash_Class & | operator= (const DataFlash_Class &)=delete |
void | set_mission (const AP_Mission *mission) |
void | Init (const struct LogStructure *structure, uint8_t num_types) |
bool | CardInserted (void) |
void | EraseAll () |
void | WriteBlock (const void *pBuffer, uint16_t size) |
void | WriteCriticalBlock (const void *pBuffer, uint16_t size) |
uint16_t | find_last_log () const |
void | get_log_boundaries (uint16_t log_num, uint16_t &start_page, uint16_t &end_page) |
uint16_t | get_num_logs (void) |
void | setVehicle_Startup_Log_Writer (vehicle_startup_message_Log_Writer writer) |
void | PrepForArming () |
void | EnableWrites (bool enable) |
bool | WritesEnabled () const |
void | StopLogging () |
void | Log_Write_Parameter (const char *name, float value) |
void | Log_Write_GPS (uint8_t instance, uint64_t time_us=0) |
void | Log_Write_RFND (const RangeFinder &rangefinder) |
void | Log_Write_IMU () |
void | Log_Write_IMUDT (uint64_t time_us, uint8_t imu_mask) |
bool | Log_Write_ISBH (uint16_t seqno, AP_InertialSensor::IMU_SENSOR_TYPE sensor_type, uint8_t instance, uint16_t multiplier, uint16_t sample_count, uint64_t sample_us, float sample_rate_hz) |
bool | Log_Write_ISBD (uint16_t isb_seqno, uint16_t seqno, const int16_t x[32], const int16_t y[32], const int16_t z[32]) |
void | Log_Write_Vibration () |
void | Log_Write_RCIN (void) |
void | Log_Write_RCOUT (void) |
void | Log_Write_RSSI (AP_RSSI &rssi) |
void | Log_Write_Baro (uint64_t time_us=0) |
void | Log_Write_Power (void) |
void | Log_Write_AHRS2 (AP_AHRS &ahrs) |
void | Log_Write_POS (AP_AHRS &ahrs) |
bool | Log_Write_MavCmd (uint16_t cmd_total, const mavlink_mission_item_t &mav_cmd) |
void | Log_Write_Radio (const mavlink_radio_t &packet) |
void | Log_Write_Message (const char *message) |
void | Log_Write_MessageF (const char *fmt,...) |
void | Log_Write_CameraInfo (enum LogMessages msg, const AP_AHRS &ahrs, const Location ¤t_loc) |
void | Log_Write_Camera (const AP_AHRS &ahrs, const Location ¤t_loc) |
void | Log_Write_Trigger (const AP_AHRS &ahrs, const Location ¤t_loc) |
void | Log_Write_ESC (void) |
void | Log_Write_Airspeed (AP_Airspeed &airspeed) |
void | Log_Write_Attitude (AP_AHRS &ahrs, const Vector3f &targets) |
void | Log_Write_AttitudeView (AP_AHRS_View &ahrs, const Vector3f &targets) |
void | Log_Write_Current () |
void | Log_Write_Compass (const Compass &compass, uint64_t time_us=0) |
void | Log_Write_Mode (uint8_t mode, uint8_t reason) |
void | Log_Write_EntireMission (const AP_Mission &mission) |
void | Log_Write_Mission_Cmd (const AP_Mission &mission, const AP_Mission::Mission_Command &cmd) |
void | Log_Write_Origin (uint8_t origin_type, const Location &loc) |
void | Log_Write_RPM (const AP_RPM &rpm_sensor) |
void | Log_Write_Rate (const AP_AHRS &ahrs, const AP_Motors &motors, const AC_AttitudeControl &attitude_control, const AC_PosControl &pos_control) |
void | Log_Write_Rally (const AP_Rally &rally) |
void | Log_Write_VisualOdom (float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence) |
void | Log_Write_AOA_SSA (AP_AHRS &ahrs) |
void | Log_Write_Beacon (AP_Beacon &beacon) |
void | Log_Write_Proximity (AP_Proximity &proximity) |
void | Log_Write_SRTL (bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f &point) |
void | Log_Write (const char *name, const char *labels, const char *fmt,...) |
void | Log_Write (const char *name, const char *labels, const char *units, const char *mults, const char *fmt,...) |
void | Log_WriteV (const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list) |
void | Log_Write_PID (uint8_t msg_type, const PID_Info &info) |
bool | should_log (uint32_t mask) const |
bool | logging_started (void) |
void | flush (void) |
void | handle_mavlink_msg (class GCS_MAVLINK &, mavlink_message_t *msg) |
void | periodic_tasks () |
uint32_t | num_dropped (void) const |
bool | log_while_disarmed (void) const |
uint8_t | log_replay (void) const |
const struct LogStructure * | structure (uint16_t num) const |
const struct UnitStructure * | unit (uint16_t num) const |
const struct MultiplierStructure * | multiplier (uint16_t num) const |
bool | logging_present () const |
bool | logging_enabled () const |
bool | logging_failed () const |
void | set_vehicle_armed (bool armed_state) |
bool | vehicle_is_armed () const |
void | handle_log_send () |
bool | in_log_download () const |
float | quiet_nanf () const |
double | quiet_nan () const |
Static Public Member Functions | |
static DataFlash_Class * | instance (void) |
Public Attributes | |
vehicle_startup_message_Log_Writer | _vehicle_messages |
struct { | |
AP_Int8 backend_types | |
AP_Int8 file_bufsize | |
AP_Int8 file_disarm_rot | |
AP_Int8 log_disarmed | |
AP_Int8 log_replay | |
AP_Int8 mav_bufsize | |
} | _params |
Static Public Attributes | |
static const struct AP_Param::GroupInfo | var_info [] |
Protected Member Functions | |
void | WritePrioritisedBlock (const void *pBuffer, uint16_t size, bool is_critical) |
Protected Attributes | |
const struct LogStructure * | _structures |
uint8_t | _num_types |
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])) |
Private Member Functions | |
void | internal_error () const |
struct log_write_fmt * | msg_fmt_for_name (const char *name, const char *labels, const char *units, const char *mults, const char *fmt) |
bool | msg_type_in_use (uint8_t msg_type) const |
int16_t | find_free_msg_type () const |
bool | fill_log_write_logstructure (struct LogStructure &logstruct, const uint8_t msg_type) const |
int16_t | Log_Write_calc_msg_len (const char *fmt) const |
void | Log_Write_Baro_instance (uint64_t time_us, uint8_t baro_instance, enum LogMessages type) |
void | Log_Write_IMU_instance (uint64_t time_us, uint8_t imu_instance, enum LogMessages type) |
void | Log_Write_Compass_instance (const Compass &compass, uint64_t time_us, uint8_t mag_instance, enum LogMessages type) |
void | Log_Write_Current_instance (uint64_t time_us, uint8_t battery_instance, enum LogMessages type, enum LogMessages celltype) |
void | Log_Write_IMUDT_instance (uint64_t time_us, uint8_t imu_instance, enum LogMessages type) |
void | backend_starting_new_log (const DataFlash_Backend *backend) |
bool | validate_structure (const struct LogStructure *logstructure, int16_t offset) |
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) |
pretty-print field information from a log structure More... | |
void | dump_structures (const struct LogStructure *logstructures, const uint8_t num_types) |
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 |
const char * | unit_name (const uint8_t unit_id) |
return a unit name given its ID More... | |
double | multiplier_name (const uint8_t multiplier_id) |
return a multiplier value given its ID More... | |
void | Log_Write_EKF_Timing (const char *name, uint64_t time_us, const struct ekf_timing &timing) |
void | Prep () |
bool | should_handle_log_message () |
void | handle_log_message (class GCS_MAVLINK &, mavlink_message_t *msg) |
void | handle_log_request_list (class GCS_MAVLINK &, mavlink_message_t *msg) |
void | handle_log_request_data (class GCS_MAVLINK &, mavlink_message_t *msg) |
void | handle_log_request_erase (class GCS_MAVLINK &, mavlink_message_t *msg) |
void | handle_log_request_end (class GCS_MAVLINK &, mavlink_message_t *msg) |
void | handle_log_send_listing () |
bool | handle_log_send_data () |
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) |
Private Attributes | |
uint8_t | _next_backend |
DataFlash_Backend * | backends [DATAFLASH_MAX_BACKENDS] |
const char * | _firmware_string |
const AP_Int32 & | _log_bitmask |
struct DataFlash_Class::log_write_fmt * | log_write_fmts |
bool | _armed |
bool | seen_ids [256] = { } |
bool | _writes_enabled:1 |
uint8_t | _log_listing:1 |
uint8_t | _log_sending:1 |
bool | _in_log_download:1 |
uint16_t | _log_next_list_entry |
uint16_t | _log_last_list_entry |
uint16_t | _log_num_logs |
uint16_t | _log_num_data |
uint32_t | _log_data_offset |
uint32_t | _log_data_size |
uint32_t | _log_data_remaining |
uint16_t | _log_data_page |
GCS_MAVLINK * | _log_sending_link |
Static Private Attributes | |
static DataFlash_Class * | _instance |
Friends | |
class | DataFlash_Backend |
Definition at line 48 of file DataFlash.h.
DataFlash_Class::DataFlash_Class | ( | const char * | firmware_string, |
const AP_Int32 & | log_bitmask | ||
) |
|
delete |
|
private |
Definition at line 676 of file DataFlash.cpp.
Referenced by msg_fmt_for_name().
|
private |
Definition at line 403 of file DataFlash.cpp.
Referenced by DataFlash_Backend::start_new_log_reset_variables().
bool DataFlash_Class::CardInserted | ( | void | ) |
Definition at line 498 of file DataFlash.cpp.
Referenced by instance().
|
private |
pretty-print field information from a log structure
Definition at line 209 of file DataFlash.cpp.
Referenced by dump_structures().
|
private |
pretty-print log structures
Definition at line 216 of file DataFlash.cpp.
Referenced by Init().
|
inline |
Definition at line 90 of file DataFlash.h.
Referenced by Init().
void DataFlash_Class::EraseAll | ( | ) |
Definition at line 494 of file DataFlash.cpp.
Referenced by handle_log_request_erase(), and instance().
|
private |
Definition at line 835 of file DataFlash.cpp.
Referenced by DataFlash_Backend::Log_Write_Emit_FMT().
|
private |
Definition at line 820 of file DataFlash.cpp.
Referenced by msg_fmt_for_name().
uint16_t DataFlash_Class::find_last_log | ( | ) | const |
Definition at line 516 of file DataFlash.cpp.
Referenced by instance().
void DataFlash_Class::flush | ( | void | ) |
Definition at line 582 of file DataFlash.cpp.
Referenced by DataFlashTest_AllTypes::flush_dataflash().
DataFlash_Class::FUNCTOR_TYPEDEF | ( | vehicle_startup_message_Log_Writer | , |
void | |||
) |
void DataFlash_Class::get_log_boundaries | ( | uint16_t | log_num, |
uint16_t & | start_page, | ||
uint16_t & | end_page | ||
) |
Definition at line 522 of file DataFlash.cpp.
Referenced by handle_log_request_data(), and instance().
|
private |
Definition at line 534 of file DataFlash.cpp.
Referenced by handle_log_send_data().
|
private |
Definition at line 528 of file DataFlash.cpp.
Referenced by handle_log_request_data(), and handle_log_send_listing().
uint16_t DataFlash_Class::get_num_logs | ( | void | ) |
Definition at line 540 of file DataFlash.cpp.
Referenced by handle_log_request_data(), handle_log_request_list(), and instance().
|
private |
handle all types of log download requests from the GCS
Definition at line 43 of file DataFlash_MAVLinkLogTransfer.cpp.
Referenced by handle_mavlink_msg().
|
private |
handle request for log data
Definition at line 105 of file DataFlash_MAVLinkLogTransfer.cpp.
Referenced by handle_log_message().
|
private |
handle request to stop transfer and resume normal logging
Definition at line 170 of file DataFlash_MAVLinkLogTransfer.cpp.
Referenced by handle_log_message().
|
private |
handle request to erase log data
Definition at line 159 of file DataFlash_MAVLinkLogTransfer.cpp.
Referenced by handle_log_message().
|
private |
handle all types of log download requests from the GCS
Definition at line 67 of file DataFlash_MAVLinkLogTransfer.cpp.
Referenced by handle_log_message().
void DataFlash_Class::handle_log_send | ( | ) |
trigger sending of log messages if there are some pending
Definition at line 182 of file DataFlash_MAVLinkLogTransfer.cpp.
Referenced by GCS_MAVLINK::data_stream_send(), handle_log_request_data(), periodic_tasks(), and vehicle_is_armed().
|
private |
trigger sending of log data if there are some pending
Definition at line 260 of file DataFlash_MAVLinkLogTransfer.cpp.
Referenced by handle_log_send().
|
private |
trigger sending of log messages if there are some pending
Definition at line 225 of file DataFlash_MAVLinkLogTransfer.cpp.
Referenced by handle_log_request_list(), and handle_log_send().
void DataFlash_Class::handle_mavlink_msg | ( | class GCS_MAVLINK & | link, |
mavlink_message_t * | msg | ||
) |
Definition at line 557 of file DataFlash.cpp.
Referenced by GCS_MAVLINK::handle_common_message().
|
inline |
Definition at line 219 of file DataFlash.h.
Referenced by should_log(), and DataFlash_Backend::StartNewLogOK().
void DataFlash_Class::Init | ( | const struct LogStructure * | structure, |
uint8_t | num_types | ||
) |
Definition at line 77 of file DataFlash.cpp.
Referenced by instance().
|
inlinestatic |
Definition at line 62 of file DataFlash.h.
Referenced by AP_Compass_MMC3416::accumulate_field(), AP_Arming::arm_checks(), NavEKF3::check_log_write(), NavEKF2::check_log_write(), AC_AttitudeControl::control_monitor_log(), GCS_MAVLINK::data_stream_send(), GCS_MAVLINK::handle_common_message(), GCS_MAVLINK::handle_common_mission_message(), AP_Follow::handle_msg(), GCS_MAVLINK::handle_param_set(), SoloGimbal_Parameters::handle_param_value(), GCS_MAVLINK::handle_statustext(), GCS_MAVLINK::handle_timesync(), NavEKF3::InitialiseFilter(), NavEKF2::InitialiseFilter(), AP_Landing_Deepstall::Log(), AP_InertialSensor_Backend::log_accel_raw(), AP_SmartRTL::log_action(), AP_GPS_SBF::log_ExtEventPVTGeodetic(), AP_InertialSensor_Backend::log_gyro_raw(), AP_GPS_UBLOX::log_mon_hw(), AP_GPS_UBLOX::log_mon_hw2(), AP_Camera::log_picture(), AP_GPS_UBLOX::log_rxm_raw(), AP_GPS_UBLOX::log_rxm_rawx(), GCS_MAVLINK::log_vision_position_estimate_data(), AP_AHRS::Log_Write_Home_And_Origin(), Log_Write_ISBH(), AP_Tuning::Log_Write_Parameter_Tuning(), AP_Scheduler::Log_Write_Performance(), AP_Arming::logging_checks(), AP_GPS_SBP2::logging_ext_event(), AP_GPS_SBP::logging_log_full_update(), AP_GPS_SBP2::logging_log_full_update(), AP_GPS_SBP::logging_log_raw_sbp(), AP_GPS_SBP2::logging_log_raw_sbp(), AP_InertialSensor::BatchSampler::push_data_to_log(), AP_BattMonitor::read(), GCS::send_parameter_value(), AP_Baro::should_df_log(), AP_GPS::should_df_log(), AP_InertialSensor::BatchSampler::should_log(), AP_InertialSensor_Backend::should_log_imu_raw(), SITL::Aircraft::smooth_sensors(), AP_Compass_MMC3416::timer(), AP_Landing::type_slope_log(), CompassLearn::update(), AP_Baro_ICM20789::update(), Variometer::update(), AP_Baro::update(), AP_GPS::update_instance(), AP_Scheduler::update_logging(), AP_TECS::update_pitch_throttle(), SITL::Aircraft::update_position(), SoaringController::update_thermalling(), AP_Camera::update_trigger(), AP_GPS_Backend::Write_DataFlash_Log_Startup_messages(), AP_GPS_UBLOX::Write_DataFlash_Log_Startup_messages(), AC_PosControl::write_log(), and WritesEnabled().
|
private |
Definition at line 625 of file DataFlash.cpp.
Referenced by Log_WriteV().
|
inline |
Definition at line 189 of file DataFlash.h.
|
inline |
Definition at line 188 of file DataFlash.h.
Referenced by should_log(), and DataFlash_Backend::ShouldLog().
void DataFlash_Class::Log_Write | ( | const char * | name, |
const char * | labels, | ||
const char * | fmt, | ||
... | |||
) |
Definition at line 632 of file DataFlash.cpp.
Referenced by AP_Compass_MMC3416::accumulate_field(), AC_AttitudeControl::control_monitor_log(), AP_Follow::handle_msg(), GCS_MAVLINK::handle_timesync(), GCS_MAVLINK::log_vision_position_estimate_data(), AP_Tuning::Log_Write_Parameter_Tuning(), SITL::Aircraft::smooth_sensors(), AP_Compass_MMC3416::timer(), AP_Landing::type_slope_log(), CompassLearn::update(), AP_Baro_ICM20789::update(), Variometer::update(), AP_TECS::update_pitch_throttle(), SITL::Aircraft::update_position(), SoaringController::update_thermalling(), AC_PosControl::write_log(), and WritesEnabled().
void DataFlash_Class::Log_Write | ( | const char * | name, |
const char * | labels, | ||
const char * | units, | ||
const char * | mults, | ||
const char * | fmt, | ||
... | |||
) |
void DataFlash_Class::Log_Write_AHRS2 | ( | AP_AHRS & | ahrs | ) |
Definition at line 458 of file LogFile.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_Write_Airspeed | ( | AP_Airspeed & | airspeed | ) |
Definition at line 1551 of file LogFile.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_Write_AOA_SSA | ( | AP_AHRS & | ahrs | ) |
Definition at line 1685 of file LogFile.cpp.
Referenced by WritesEnabled().
Definition at line 1360 of file LogFile.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_Write_AttitudeView | ( | AP_AHRS_View & | ahrs, |
const Vector3f & | targets | ||
) |
Definition at line 1378 of file LogFile.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_Write_Baro | ( | uint64_t | time_us = 0 | ) |
Definition at line 279 of file LogFile.cpp.
Referenced by NavEKF3::check_log_write(), NavEKF2::check_log_write(), AP_Baro::update(), and WritesEnabled().
|
private |
void DataFlash_Class::Log_Write_Beacon | ( | AP_Beacon & | beacon | ) |
Definition at line 1698 of file LogFile.cpp.
Referenced by WritesEnabled().
|
private |
Definition at line 879 of file DataFlash.cpp.
Referenced by msg_fmt_for_name(), and validate_structure().
Definition at line 1348 of file LogFile.cpp.
Referenced by AP_Camera::log_picture(), AP_Camera::update_trigger(), and WritesEnabled().
void DataFlash_Class::Log_Write_CameraInfo | ( | enum LogMessages | msg, |
const AP_AHRS & | ahrs, | ||
const Location & | current_loc | ||
) |
Definition at line 1313 of file LogFile.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_Write_Compass | ( | const Compass & | compass, |
uint64_t | time_us = 0 |
||
) |
Definition at line 1479 of file LogFile.cpp.
Referenced by NavEKF3::check_log_write(), NavEKF2::check_log_write(), and WritesEnabled().
|
private |
void DataFlash_Class::Log_Write_Current | ( | ) |
Definition at line 1436 of file LogFile.cpp.
Referenced by AP_BattMonitor::read(), and WritesEnabled().
|
private |
|
private |
void DataFlash_Class::Log_Write_EntireMission | ( | const AP_Mission & | mission | ) |
Definition at line 588 of file DataFlash.cpp.
Referenced by GCS_MAVLINK::handle_common_mission_message(), and WritesEnabled().
void DataFlash_Class::Log_Write_ESC | ( | void | ) |
Definition at line 1509 of file LogFile.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_Write_GPS | ( | uint8_t | instance, |
uint64_t | time_us = 0 |
||
) |
Definition at line 136 of file LogFile.cpp.
Referenced by NavEKF3::check_log_write(), NavEKF2::check_log_write(), AP_GPS::update_instance(), and WritesEnabled().
void DataFlash_Class::Log_Write_IMU | ( | ) |
Definition at line 320 of file LogFile.cpp.
Referenced by WritesEnabled().
|
private |
void DataFlash_Class::Log_Write_IMUDT | ( | uint64_t | time_us, |
uint8_t | imu_mask | ||
) |
Definition at line 367 of file LogFile.cpp.
Referenced by NavEKF3::check_log_write(), NavEKF2::check_log_write(), and WritesEnabled().
|
private |
bool DataFlash_Class::Log_Write_ISBD | ( | uint16_t | isb_seqno, |
uint16_t | seqno, | ||
const int16_t | x[32], | ||
const int16_t | y[32], | ||
const int16_t | z[32] | ||
) |
Definition at line 952 of file DataFlash.cpp.
Referenced by AP_InertialSensor::BatchSampler::push_data_to_log(), and WritesEnabled().
bool DataFlash_Class::Log_Write_ISBH | ( | uint16_t | seqno, |
AP_InertialSensor::IMU_SENSOR_TYPE | sensor_type, | ||
uint8_t | instance, | ||
uint16_t | multiplier, | ||
uint16_t | sample_count, | ||
uint64_t | sample_us, | ||
float | sample_rate_hz | ||
) |
Definition at line 919 of file DataFlash.cpp.
Referenced by AP_InertialSensor::BatchSampler::push_data_to_log(), and WritesEnabled().
bool DataFlash_Class::Log_Write_MavCmd | ( | uint16_t | cmd_total, |
const mavlink_mission_item_t & | mav_cmd | ||
) |
void DataFlash_Class::Log_Write_Message | ( | const char * | message | ) |
Definition at line 593 of file DataFlash.cpp.
Referenced by GCS_MAVLINK::handle_statustext(), Log_Write_MessageF(), AP_GPS_Backend::Write_DataFlash_Log_Startup_messages(), and WritesEnabled().
void DataFlash_Class::Log_Write_MessageF | ( | const char * | fmt, |
... | |||
) |
Definition at line 391 of file DataFlash.cpp.
Referenced by AP_GPS_UBLOX::Write_DataFlash_Log_Startup_messages(), and WritesEnabled().
void DataFlash_Class::Log_Write_Mission_Cmd | ( | const AP_Mission & | mission, |
const AP_Mission::Mission_Command & | cmd | ||
) |
Definition at line 608 of file DataFlash.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_Write_Mode | ( | uint8_t | mode, |
uint8_t | reason | ||
) |
Definition at line 598 of file DataFlash.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_Write_Origin | ( | uint8_t | origin_type, |
const Location & | loc | ||
) |
Definition at line 1594 of file LogFile.cpp.
Referenced by AP_AHRS::Log_Write_Home_And_Origin(), and WritesEnabled().
void DataFlash_Class::Log_Write_Parameter | ( | const char * | name, |
float | value | ||
) |
Definition at line 603 of file DataFlash.cpp.
Referenced by GCS_MAVLINK::handle_param_set(), SoloGimbal_Parameters::handle_param_value(), AP_AutoTune::log_param_change(), GCS::send_parameter_value(), and WritesEnabled().
void DataFlash_Class::Log_Write_PID | ( | uint8_t | msg_type, |
const PID_Info & | info | ||
) |
void DataFlash_Class::Log_Write_POS | ( | AP_AHRS & | ahrs | ) |
Definition at line 485 of file LogFile.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_Write_Power | ( | void | ) |
Definition at line 437 of file LogFile.cpp.
Referenced by AP_BattMonitor::read(), and WritesEnabled().
void DataFlash_Class::Log_Write_Proximity | ( | AP_Proximity & | proximity | ) |
Definition at line 1725 of file LogFile.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_Write_Radio | ( | const mavlink_radio_t & | packet | ) |
Definition at line 1296 of file LogFile.cpp.
Referenced by GCS_MAVLINK::handle_radio_status(), and WritesEnabled().
void DataFlash_Class::Log_Write_Rally | ( | const AP_Rally & | rally | ) |
Definition at line 1647 of file LogFile.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_Write_Rate | ( | const AP_AHRS & | ahrs, |
const AP_Motors & | motors, | ||
const AC_AttitudeControl & | attitude_control, | ||
const AC_PosControl & | pos_control | ||
) |
Definition at line 1620 of file LogFile.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_Write_RCIN | ( | void | ) |
Definition at line 199 of file LogFile.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_Write_RCOUT | ( | void | ) |
Definition at line 223 of file LogFile.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_Write_RFND | ( | const RangeFinder & | rangefinder | ) |
Definition at line 182 of file LogFile.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_Write_RPM | ( | const AP_RPM & | rpm_sensor | ) |
Definition at line 1608 of file LogFile.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_Write_RSSI | ( | AP_RSSI & | rssi | ) |
Definition at line 248 of file LogFile.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_Write_SRTL | ( | bool | active, |
uint16_t | num_points, | ||
uint16_t | max_points, | ||
uint8_t | action, | ||
const Vector3f & | point | ||
) |
Definition at line 1762 of file LogFile.cpp.
Referenced by AP_SmartRTL::log_action(), and WritesEnabled().
Definition at line 1354 of file LogFile.cpp.
Referenced by AP_Camera::log_picture(), and WritesEnabled().
void DataFlash_Class::Log_Write_Vibration | ( | ) |
Definition at line 390 of file LogFile.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_Write_VisualOdom | ( | float | time_delta, |
const Vector3f & | angle_delta, | ||
const Vector3f & | position_delta, | ||
float | confidence | ||
) |
Definition at line 1667 of file LogFile.cpp.
Referenced by WritesEnabled().
void DataFlash_Class::Log_WriteV | ( | const char * | name, |
const char * | labels, | ||
const char * | units, | ||
const char * | mults, | ||
const char * | fmt, | ||
va_list | arg_list | ||
) |
Definition at line 650 of file DataFlash.cpp.
Referenced by Log_Write(), and WritesEnabled().
bool DataFlash_Class::logging_enabled | ( | ) | const |
Definition at line 365 of file DataFlash.cpp.
bool DataFlash_Class::logging_failed | ( | ) | const |
Definition at line 377 of file DataFlash.cpp.
bool DataFlash_Class::logging_present | ( | ) | const |
Definition at line 361 of file DataFlash.cpp.
bool DataFlash_Class::logging_started | ( | void | ) |
Definition at line 548 of file DataFlash.cpp.
Referenced by AP_Arming::arm_checks(), AP_AutoTune::log_param_change(), and AP_AutoTune::write_log().
|
private |
Definition at line 722 of file DataFlash.cpp.
Referenced by Log_WriteV().
|
private |
Definition at line 799 of file DataFlash.cpp.
Referenced by find_free_msg_type().
const struct MultiplierStructure * DataFlash_Class::multiplier | ( | uint16_t | num | ) | const |
Definition at line 438 of file DataFlash.cpp.
Referenced by Log_Write_ISBH(), DataFlash_Backend::multiplier(), and WritesEnabled().
|
private |
return a multiplier value given its ID
Definition at line 197 of file DataFlash.cpp.
Referenced by dump_structure_field().
uint32_t DataFlash_Class::num_dropped | ( | void | ) | const |
|
delete |
void DataFlash_Class::periodic_tasks | ( | ) |
|
private |
Definition at line 507 of file DataFlash.cpp.
Referenced by Init().
void DataFlash_Class::PrepForArming | ( | ) |
Definition at line 450 of file DataFlash.cpp.
Referenced by AP_Arming::arm_checks(), and instance().
|
inline |
Definition at line 222 of file DataFlash.h.
|
inline |
Definition at line 221 of file DataFlash.h.
void DataFlash_Class::set_mission | ( | const AP_Mission * | mission | ) |
Definition at line 476 of file DataFlash.cpp.
Referenced by instance().
void DataFlash_Class::set_vehicle_armed | ( | bool | armed_state | ) |
Definition at line 460 of file DataFlash.cpp.
void DataFlash_Class::setVehicle_Startup_Log_Writer | ( | vehicle_startup_message_Log_Writer | writer | ) |
Definition at line 455 of file DataFlash.cpp.
Referenced by instance().
|
private |
Definition at line 28 of file DataFlash_MAVLinkLogTransfer.cpp.
Referenced by handle_log_message().
bool DataFlash_Class::should_log | ( | uint32_t | mask | ) | const |
Definition at line 416 of file DataFlash.cpp.
Referenced by AP_Camera::log_picture(), AP_BattMonitor::read(), AP_Baro::should_df_log(), AP_GPS::should_df_log(), AP_InertialSensor::BatchSampler::should_log(), AP_InertialSensor_Backend::should_log_imu_raw(), and AP_Camera::update_trigger().
void DataFlash_Class::StopLogging | ( | ) |
Definition at line 511 of file DataFlash.cpp.
Referenced by WritesEnabled().
const struct LogStructure * DataFlash_Class::structure | ( | uint16_t | num | ) | const |
Definition at line 356 of file DataFlash.cpp.
Referenced by instance(), msg_type_in_use(), and DataFlash_Backend::structure().
const struct UnitStructure * DataFlash_Class::unit | ( | uint16_t | num | ) | const |
Definition at line 433 of file DataFlash.cpp.
Referenced by DataFlash_Backend::unit().
|
private |
return a unit name given its ID
Definition at line 186 of file DataFlash.cpp.
Referenced by dump_structure_field().
|
private |
Definition at line 245 of file DataFlash.cpp.
Referenced by msg_fmt_for_name(), and validate_structures().
|
private |
Definition at line 339 of file DataFlash.cpp.
Referenced by Init().
|
inline |
Definition at line 216 of file DataFlash.h.
Referenced by should_handle_log_message(), should_log(), and DataFlash_Backend::ShouldLog().
void DataFlash_Class::WriteBlock | ( | const void * | pBuffer, |
uint16_t | size | ||
) |
Definition at line 481 of file DataFlash.cpp.
Referenced by instance(), AP_Landing_Deepstall::Log(), AP_InertialSensor_Backend::log_accel_raw(), AP_GPS_SBF::log_ExtEventPVTGeodetic(), AP_InertialSensor_Backend::log_gyro_raw(), AP_GPS_UBLOX::log_mon_hw(), AP_GPS_UBLOX::log_mon_hw2(), AP_GPS_UBLOX::log_rxm_raw(), AP_GPS_UBLOX::log_rxm_rawx(), SITL::SITL::Log_Write_SIMSTATE(), AP_GPS_SBP2::logging_ext_event(), AP_GPS_SBP::logging_log_full_update(), AP_GPS_SBP2::logging_log_full_update(), AP_GPS_SBP::logging_log_raw_sbp(), AP_GPS_SBP2::logging_log_raw_sbp(), and AP_AutoTune::write_log().
void DataFlash_Class::WriteCriticalBlock | ( | const void * | pBuffer, |
uint16_t | size | ||
) |
Definition at line 485 of file DataFlash.cpp.
Referenced by instance(), and AP_Scheduler::Log_Write_Performance().
|
protected |
Definition at line 489 of file DataFlash.cpp.
|
inline |
Definition at line 91 of file DataFlash.h.
Referenced by should_handle_log_message(), and DataFlash_Backend::ShouldLog().
|
friend |
Definition at line 50 of file DataFlash.h.
|
private |
Definition at line 284 of file DataFlash.h.
Referenced by set_vehicle_armed(), and vehicle_is_armed().
|
private |
Definition at line 243 of file DataFlash.h.
Referenced by Init().
|
private |
Definition at line 340 of file DataFlash.h.
Referenced by handle_log_request_data(), handle_log_request_end(), and in_log_download().
|
staticprivate |
Definition at line 310 of file DataFlash.h.
Referenced by DataFlash_Class(), and instance().
|
private |
Definition at line 244 of file DataFlash.h.
Referenced by should_log(), and DataFlash_Backend::StartNewLogOK().
|
private |
Definition at line 355 of file DataFlash.h.
Referenced by handle_log_request_data(), and handle_log_send_data().
|
private |
Definition at line 364 of file DataFlash.h.
Referenced by handle_log_request_data(), and handle_log_send_data().
|
private |
Definition at line 361 of file DataFlash.h.
Referenced by handle_log_request_data(), and handle_log_send_data().
|
private |
Definition at line 358 of file DataFlash.h.
Referenced by handle_log_request_data().
|
private |
Definition at line 346 of file DataFlash.h.
Referenced by handle_log_request_list(), and handle_log_send_listing().
|
private |
Definition at line 336 of file DataFlash.h.
Referenced by handle_log_request_data(), handle_log_request_list(), handle_log_send(), and handle_log_send_listing().
|
private |
Definition at line 343 of file DataFlash.h.
Referenced by handle_log_request_list(), and handle_log_send_listing().
|
private |
Definition at line 352 of file DataFlash.h.
Referenced by handle_log_request_data(), and handle_log_send_data().
|
private |
Definition at line 349 of file DataFlash.h.
Referenced by handle_log_request_list(), and handle_log_send_listing().
|
private |
Definition at line 337 of file DataFlash.h.
Referenced by handle_log_request_data(), handle_log_request_end(), handle_log_request_list(), handle_log_send(), and handle_log_send_data().
|
private |
Definition at line 366 of file DataFlash.h.
Referenced by handle_log_request_data(), handle_log_request_end(), handle_log_request_list(), handle_log_send(), handle_log_send_data(), and handle_log_send_listing().
|
protected |
Definition at line 229 of file DataFlash.h.
Referenced by multiplier_name(), and validate_structure().
|
private |
Definition at line 241 of file DataFlash.h.
Referenced by backend_starting_new_log(), CardInserted(), find_last_log(), get_log_boundaries(), get_log_data(), get_log_info(), get_num_logs(), Init(), Log_Write_ISBD(), Log_Write_ISBH(), Log_WriteV(), logging_enabled(), logging_failed(), logging_present(), logging_started(), num_dropped(), and should_log().
|
protected |
Definition at line 231 of file DataFlash.h.
Referenced by DataFlash_Backend::num_multipliers(), and validate_structure().
|
protected |
Definition at line 227 of file DataFlash.h.
Referenced by Init(), msg_type_in_use(), and DataFlash_Backend::num_types().
Definition at line 230 of file DataFlash.h.
Referenced by DataFlash_Backend::num_units(), and validate_structure().
struct { ... } DataFlash_Class::_params |
Referenced by DataFlash_MAVLink::DataFlash_MAVLink(), Init(), log_replay(), log_while_disarmed(), and DataFlash_Backend::ShouldLog().
|
protected |
Definition at line 226 of file DataFlash.h.
Referenced by Init(), and structure().
|
protected |
Definition at line 228 of file DataFlash.h.
Referenced by unit(), unit_name(), and validate_structure().
vehicle_startup_message_Log_Writer DataFlash_Class::_vehicle_messages |
Definition at line 191 of file DataFlash.h.
Referenced by setVehicle_Startup_Log_Writer(), and DataFlash_Backend::vehicle_message_writer().
|
private |
Definition at line 333 of file DataFlash.h.
Referenced by EnableWrites(), and WritesEnabled().
AP_Int8 DataFlash_Class::backend_types |
Definition at line 196 of file DataFlash.h.
|
private |
Definition at line 242 of file DataFlash.h.
Referenced by backend_starting_new_log(), CardInserted(), find_last_log(), get_log_boundaries(), get_log_data(), get_log_info(), get_num_logs(), Init(), Log_Write_ISBD(), Log_Write_ISBH(), Log_WriteV(), logging_enabled(), logging_failed(), logging_started(), and num_dropped().
AP_Int8 DataFlash_Class::file_bufsize |
Definition at line 197 of file DataFlash.h.
AP_Int8 DataFlash_Class::file_disarm_rot |
Definition at line 198 of file DataFlash.h.
Referenced by DataFlash_Backend::ShouldLog().
AP_Int8 DataFlash_Class::log_disarmed |
Definition at line 199 of file DataFlash.h.
AP_Int8 DataFlash_Class::log_replay |
Definition at line 200 of file DataFlash.h.
Referenced by NavEKF3::InitialiseFilter(), and NavEKF2::InitialiseFilter().
|
private |
AP_Int8 DataFlash_Class::mav_bufsize |
Definition at line 201 of file DataFlash.h.
Referenced by DataFlash_MAVLink::DataFlash_MAVLink().
|
private |
Definition at line 325 of file DataFlash.h.
Referenced by validate_structure().
|
static |
Definition at line 194 of file DataFlash.h.
Referenced by DataFlash_Class().