29 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 30 #include <uORB/topics/esc_status.h> 77 void WriteBlock(
const void *pBuffer, uint16_t size);
104 uint16_t sample_count,
106 float sample_rate_hz);
111 const int16_t z[32]);
120 #if AP_AHRS_NAVEKF_AVAILABLE 123 bool Log_Write_MavCmd(uint16_t cmd_total,
const mavlink_mission_item_t& mav_cmd);
154 void Log_Write(
const char *name,
const char *labels,
const char *fmt, ...);
155 void Log_Write(
const char *name,
const char *labels,
const char *units,
const char *mults,
const char *fmt, ...);
156 void Log_WriteV(
const char *name,
const char *labels,
const char *units,
const char *mults,
const char *fmt, va_list arg_list);
175 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX 222 double quiet_nan()
const {
return nan(
"0x4152445550490a"); }
240 #define DATAFLASH_MAX_BACKENDS 2 286 #if AP_AHRS_NAVEKF_AVAILABLE 293 uint8_t imu_instance,
297 uint8_t mag_instance,
300 uint8_t battery_instance,
304 uint8_t imu_instance,
312 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 322 const char *fmt)
const;
323 const char*
unit_name(
const uint8_t unit_id);
378 void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
380 int16_t
get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
uint8_t log_replay(void) const
void handle_mavlink_msg(class GCS_MAVLINK &, mavlink_message_t *msg)
void Log_Write_MessageF(const char *fmt,...)
void dump_structure_field(const struct LogStructure *logstructure, const char *label, const uint8_t fieldnum)
pretty-print field information from a log structure
void Log_Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets)
static DataFlash_Class * _instance
void Log_Write_AOA_SSA(AP_AHRS &ahrs)
Object managing Rally Points.
uint16_t _log_next_list_entry
int16_t find_free_msg_type() const
void Log_Write_Trigger(const AP_AHRS &ahrs, const Location ¤t_loc)
bool logging_enabled() const
struct log_write_fmt * next
struct log_write_fmt * msg_fmt_for_name(const char *name, const char *labels, const char *units, const char *mults, const char *fmt)
const uint8_t _num_multipliers
bool should_handle_log_message()
void internal_error() const
MAVLink transport control class.
uint8_t num_types() const
void Log_Write_Airspeed(AP_Airspeed &airspeed)
bool logging_started(void)
bool should_log(uint32_t mask) const
FUNCTOR_TYPEDEF(vehicle_startup_message_Log_Writer, void)
void Log_Write_Beacon(AP_Beacon &beacon)
void Log_Write_Mode(uint8_t mode, uint8_t reason)
struct DataFlash_Class::@194 _params
const struct UnitStructure log_Units[]
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_Message(const char *message)
void Log_Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f &point)
void Log_Write_Proximity(AP_Proximity &proximity)
void Log_Write_Parameter(const char *name, float value)
void handle_log_message(class GCS_MAVLINK &, mavlink_message_t *msg)
#define DATAFLASH_MAX_BACKENDS
void WriteBlock(const void *pBuffer, uint16_t size)
void Log_Write_IMUDT(uint64_t time_us, uint8_t imu_mask)
const struct LogStructure * structure(uint16_t num) const
void Log_Write_Radio(const mavlink_radio_t &packet)
void Log_Write_Compass_instance(const Compass &compass, uint64_t time_us, uint8_t mag_instance, enum LogMessages type)
DataFlash_Class & operator=(const DataFlash_Class &)=delete
void WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
const struct MultiplierStructure log_Multipliers[]
bool handle_log_send_data()
void Log_Write_PID(uint8_t msg_type, const PID_Info &info)
bool in_log_download() const
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)
void get_log_boundaries(uint16_t log_num, uint16_t &start_page, uint16_t &end_page)
AP_MotorsMatrix motors(400)
void backend_starting_new_log(const DataFlash_Backend *backend)
A system for managing and storing variables that are of general interest to the system.
void handle_log_send_listing()
Handles rally point storage and retrieval.
bool fill_log_write_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const
uint16_t _log_last_list_entry
void set_vehicle_armed(bool armed_state)
void Log_Write_RSSI(AP_RSSI &rssi)
void Log_Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence)
void Init(const struct LogStructure *structure, uint8_t num_types)
void dump_structures(const struct LogStructure *logstructures, const uint8_t num_types)
void Log_Write_Compass(const Compass &compass, uint64_t time_us=0)
static const struct AP_Param::GroupInfo var_info[]
void Log_Write(const char *name, const char *labels, const char *fmt,...)
void Log_Write_IMU_instance(uint64_t time_us, uint8_t imu_instance, enum LogMessages type)
void Log_Write_Rally(const AP_Rally &rally)
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)
void Log_Write_Camera(const AP_AHRS &ahrs, const Location ¤t_loc)
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_POS(AP_AHRS &ahrs)
void validate_structures(const struct LogStructure *logstructures, const uint8_t num_types)
const struct MultiplierStructure * _multipliers
void set_mission(const AP_Mission *mission)
bool msg_type_in_use(uint8_t msg_type) const
double multiplier_name(const uint8_t multiplier_id)
return a multiplier value given its ID
const AP_Int32 & _log_bitmask
bool log_while_disarmed(void) const
void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets)
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
static DataFlash_Class * instance(void)
void handle_log_request_list(class GCS_MAVLINK &, mavlink_message_t *msg)
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc)
bool WritesEnabled() const
void Log_Write_Current_instance(uint64_t time_us, uint8_t battery_instance, enum LogMessages type, enum LogMessages celltype)
uint16_t find_last_log() const
const struct MultiplierStructure * multiplier(uint16_t num) const
void Log_Write_RCOUT(void)
void Log_Write_AHRS2(AP_AHRS &ahrs)
void setVehicle_Startup_Log_Writer(vehicle_startup_message_Log_Writer writer)
bool validate_structure(const struct LogStructure *logstructure, int16_t offset)
bool logging_failed() const
void WriteCriticalBlock(const void *pBuffer, uint16_t size)
void Log_Write_Mission_Cmd(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd)
void Log_Write_GPS(uint8_t instance, uint64_t time_us=0)
bool logging_present() const
const struct UnitStructure * _units
const char * unit_name(const uint8_t unit_id)
return a unit name given its ID
void handle_log_request_data(class GCS_MAVLINK &, mavlink_message_t *msg)
Common definitions and utility routines for the ArduPilot libraries.
void Log_Write_RPM(const AP_RPM &rpm_sensor)
void handle_log_request_end(class GCS_MAVLINK &, mavlink_message_t *msg)
void Log_Write_EKF_Timing(const char *name, uint64_t time_us, const struct ekf_timing &timing)
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])
DataFlash_Class(const char *firmware_string, const AP_Int32 &log_bitmask)
void Log_Write_Power(void)
void Log_Write_Origin(uint8_t origin_type, const Location &loc)
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
void Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, const Location ¤t_loc)
void EnableWrites(bool enable)
const struct UnitStructure * unit(uint16_t num) const
const char * _firmware_string
GCS_MAVLINK * _log_sending_link
void Log_Write_EntireMission(const AP_Mission &mission)
uint32_t _log_data_offset
void handle_log_request_erase(class GCS_MAVLINK &, mavlink_message_t *msg)
void Log_Write_RFND(const RangeFinder &rangefinder)
Catch-all header that defines all supported RangeFinder classes.
void Log_Write_IMUDT_instance(uint64_t time_us, uint8_t imu_instance, enum LogMessages type)
void Log_Write_Vibration()
vehicle_startup_message_Log_Writer _vehicle_messages
void Log_Write_Baro_instance(uint64_t time_us, uint8_t baro_instance, enum LogMessages type)
const struct LogStructure * _structures
void Log_Write_RCIN(void)
bool Log_Write_MavCmd(uint16_t cmd_total, const mavlink_mission_item_t &mav_cmd)
uint32_t _log_data_remaining
void Log_Write_Baro(uint64_t time_us=0)
int16_t Log_Write_calc_msg_len(const char *fmt) const
bool vehicle_is_armed() const
uint16_t get_num_logs(void)
uint32_t num_dropped(void) const
DataFlash_Backend * backends[DATAFLASH_MAX_BACKENDS]
struct DataFlash_Class::log_write_fmt * log_write_fmts