Analyzer Class Reference

Analyzer

class Analyzer

Base class for all analyzers.

@description Extend this class to create a new analyzer.

An Analyzer tracks changes to a vehicle model over time to determine if anything untoward is happening. “evaluate()” is called repeatedly when the model’s state changes, and “end_of_log” is called when no more input will be forthcoming. An Analyzer is expected to output Analyzer_Result objects through the “add_result” object.

Public Functions

inline Analyzer(AnalyzerVehicle::Base *&vehicle, Data_Sources &data_sources)

Constructor for Analyzer.

Parameters
  • vehicle – The vehicle model to be analyzed.

  • data_sources – A mapping of abstract data source names to their concrete data sources (e.g. ATTITUDE -> [ ATT.Pitch, ATT.Roll ]).

inline virtual ~Analyzer()
inline virtual bool configure (INIReader *config UNUSED)

Configure an analyzer from a .ini config file.

Parameters

config – The configuration source.

Returns

true if configuration succeeded.

virtual const std::string name() const = 0

a simple name that used to refer to this Analyzer.

virtual const std::string description() const = 0

Outlines the reason this test exists.

virtual void results_json_results(Json::Value &root) const

Provide analyzer output in the provided Json::Value.

Parameters

root[out] Object to populate with output

inline const char *status_as_string() const

Return the analyzer’s status represented as a string.

inline void set_pure_output(bool pure)

Set whether to produce output compatible with older versions.

Parameters

purity – True if compatability fields should not be produced

inline bool pure_output() const

Returns true if compatability fields will not be produced.

Returns

true if compatability fields will not be produced.

inline std::vector<Analyzer_Result*> results() const

Return all results this analyzer has produced.

inline uint16_t result_count() const

Return the number of results this analyzer has produced.

virtual uint32_t severity_score() const

Returns a number “score” indicating how significant this result may be.

virtual void evaluate() = 0

Called whenever the vehicle’s state changes.

inline virtual void end_of_log (uint32_t packet_count UNUSED)

Called when no more input will be forthcoming.

Parameters

packet_count – The number of packets processed to update the model.

analyzer_status status() const

Provide the Analyzer’s overall status.

Returns

The Analyzer overall status.

Protected Functions

inline virtual void add_result(Analyzer_Result *result)
std::string to_string(double x)

Provide the Analyzer Result’s status.

Returns

The Analyzer_Result’s status.

Protected Attributes

AnalyzerVehicle::Base *&_vehicle

Vehicle model.

Updated by LA_MsgHandler* and analyzing_mavlink_message_handler, analyzed by analyzer_*.

Data_Sources &_data_sources

Map from abstract data source to concrete data source.

e.g. BATTERY_REMAINING -> SYS_STATUS.battery_remaining.

bool _pure = false

Result Classes

class Analyzer_Result

Base class for analyzer results; extend this to provide a custom result object.

You probably do not want to directly extend Analyzer_Result, but one of its immediate subclasses.

Subclassed by Analyzer_Result_Event, Analyzer_Result_Period, Analyzer_Result_Summary

Public Functions

inline virtual ~Analyzer_Result()

Construct an Analyzer_Result.

inline const char *status_as_string() const

Provides a textual description of the Analyzer Result’s status.

Returns

A text string e.g. “OK” or “FAIL”.

inline analyzer_status status()

Provide the Analyzer_Result’s status.

Returns

The Analyzer_Result’s status.

inline void set_status(analyzer_status status)

Set the Analyzer Result’s status.

Parameters

status – The new status for this Result.

inline void set_reason(const std::string reason)

Set a simple, human-readable explanation of the result.

Parameters

reason – The reason for the existence of this result.

inline const std::string *reason() const

Provide a simple, human-readable explanation if the result.

virtual void to_json(Json::Value &root) const

Provide analyzer output in the provided Json::Value.

Parameters

Root[out] object to populate with output.

inline void add_evidence(const std::string f)

Provide textual free-form evidence for the “reason”.

Parameters

f – Textual free-form evidence.

inline void add_source(const Data_Source *f)

Indicate that a particular data source was used to come to the conclusion returned by reason().

Parameters

f – A Data_Source relevant to the conclusion in reason().

inline void increase_severity_score(uint32_t evilness)

Indicate the result is incrementally more significant.

Parameters

evilness – Degree to which this result is more significant.

inline void set_severity_score(uint32_t evilness)

Indicate how significant this result is.

Parameters

evilness – Degree of significance of this result.

inline uint32_t severity_score() const

Return a number indicating the relative significance of this result.

Returns

The relative significance of this result.

inline void set_pure_output(bool pure)
inline bool pure_output() const

class Analyzer_Result_Event : public Analyzer_Result

Base class for an Analyzer Result which does not span any time.

Examples would include a “Crash” event present in a log.

Public Functions

inline Analyzer_Result_Event()
virtual void to_json(Json::Value &root) const

Provide analyzer output in the provided Json::Value.

Parameters

Root[out] object to populate with output.

inline void set_T(uint64_t timestamp)
inline uint64_t T() const

class Analyzer_Result_Period : public Analyzer_Result

Base class for an Analyzer Result which spans a period.

Examples would include a momentary attitude control loss.

Public Functions

inline Analyzer_Result_Period()
virtual void to_json(Json::Value &root) const override

Provide analyzer output in the provided Json::Value.

Parameters

Root[out] object to populate with output.

inline void set_T_start(const uint64_t start)
inline uint64_t T_start() const
inline void set_T_stop(const uint64_t stop)
inline uint64_t T_stop() const
inline uint64_t duration() const

class Analyzer_Result_Summary : public Analyzer_Result

Base class for an Analyzer Result which provides information derived over the entire period of data input.

Examples would include “How many bytes of the input were processed”.

Public Functions

inline Analyzer_Result_Summary()

enum analyzer_status

Enumeration of possible states for both an Analyzer_Result and Analyzer.

Values:

enumerator analyzer_status_warn
enumerator analyzer_status_fail
enumerator analyzer_status_ok

Vehicle Model

class AnalyzerVehicle::Base

Base class from which all vehicles inherit.

Subclassed by AnalyzerVehicle::Copter, AnalyzerVehicle::Plane, AnalyzerVehicle::Rover

Public Types

enum vehicletype_t

All the different vehicles we have specific tests for.

Values:

enumerator invalid
enumerator copter
enumerator plane
enumerator rover

Public Functions

inline Base()
inline virtual ~Base()
inline virtual const std::string typeString() const

Returns a short string describing the vehicle.

Returns

A short string describing the vehicle e.g. “Copter”.

inline uint64_t time_since_boot() const

Time since autopilot boot (microseconds).

Returns

Time since autopilot boot (microseconds).

inline uint64_t time_since_boot_T() const

The timestamp at which the “time_since_boot()” timestamp was updated.

This timestamp may reflect time on a different system - for example, a MAVLink tlog often uses a Ground Control Station’s concept of time.

Returns

Timestamp that the autopilot boot time was last changed.

inline void set_time_since_boot(const uint64_t time_since_boot)

Set the number of microseconds the autopilot has been booted.

Parameters

time_since_boot – Microseconds since autopilot boot.

inline virtual bool is_flying() const

Evaluation of whether the vehicle is flying.

Returns

true if it is believed the vehicle is flying.

inline virtual bool is_armed() const

Vehicle arm status.

Returns

true if it believed the vehicle is armed.

inline virtual void set_armed(bool value)

Set the vehicle arm status.

Parameters

value – The new vehicle arm status.

inline bool vehicletype_is_forced() const

Vehicle type forced status. @detail Sometimes the vehicle type can not be determined from a log and must be forced.

Returns

true if the vehicle type has been forced.

inline void set_vehicletype_is_forced(bool value)

Indicates that the vehicle type has been forced.

Parameters

valuetrue if the vehicle type has been forced.

inline virtual vehicletype_t vehicletype() const

Vehicle type. @detail Until the vehicle type is determined, this returns invalid. After the vehicle type is determined (e.g. from a log), this will return a specific value from the vehicletype_t enumeration indication the vehicle type.

Returns

The current vehicle type.

inline void ekf_set_variance(const char *name, double value)

Set a variance value by name.

Parameters
  • name – Name of variance to set (e.g. “pos_horiz”).

  • value – New value of the variance.

inline uint64_t ekf_variance_T(std::string name) const

Variance modification time.

Parameters

name – Name of variance to retrieve modification time for.

Returns

timestamp Timestamp at which variance was last changed (microseconds).

inline void ekf_set_flags(uint16_t flags)

Set EKF status flags.

Parameters

flagsEKF self-assessment status flags.

inline uint16_t ekf_flags() const

EKF status flags.

Returns

EKF self-assessment status flags.

inline uint64_t ekf_flags_T() const

EKF status flags modification time.

Returns

timestamp Timestamp at which the EKF self-assessment flags were last changed (microseconds).

inline std::map<const std::string, double> ekf_variances()

All EKF variances.

Returns

Returns all EKF variances as a map from name to value.

inline void nkf_set_variance(const char *name, double value)

Set a variance value by name.

Parameters
  • name – Name of variance to set (e.g. “pos_horiz”).

  • value – New value of the variance.

inline uint64_t nkf_variance_T(std::string name) const
inline void nkf_set_flags(uint16_t flags)

Set NKF (EKFv2) status flags.

Parameters

flags – NKF (EKFv2 self-assessment status flags.

inline uint16_t nkf_flags() const

NKF status flags.

Returns

NKF self-assessment status flags.

inline uint64_t nkf_flags_T() const

NKF (EKF2) status flags modification time.

Returns

timestamp Timestamp at which the NKF self-assessment flags were last changed (microseconds).

inline std::map<const std::string, double> nkf_variances()

All NKF (EKF2) variances.

Returns

Returns all NKF (EKF2) variances as a map from name to value.

inline void xkf_set_variance(const char *name, double value)

Set a variance value by name.

Parameters
  • name – Name of variance to set (e.g. “pos_horiz”).

  • value – New value of the variance.

inline uint64_t xkf_variance_T(std::string name) const
inline void xkf_set_flags(uint16_t flags)

Set XKF (EKF3) status flags.

Parameters

flags – XKF (EKF3 self-assessment status flags.

inline uint16_t xkf_flags() const

XKF status flags.

Returns

XKF self-assessment status flags.

inline uint64_t xkf_flags_T() const

XKF (EKF3) status flags modification time.

Returns

timestamp Timestamp at which the XKF self-assessment flags were last changed (microseconds).

inline std::map<const std::string, double> xkf_variances()

All XKF (EKF3) variances.

Returns

Returns all XKF (EKF3) variances as a map from name to value.

float param(const std::string name) const

Retrieve parameter value.

Parameters

name – Parameter value to retrieve. @detail This function will abort if the parameter has not been seen and no default is known.

Returns

Parameter value from log or defaults.

bool param(const char *name, float &ret) const

Retrieve parameter value. @detail Returns parameter value ONLY from input, not from defaults.

Parameters
  • name – Parameter value to retrieve.

  • ret[out] Parameter value.

Returns

true if the parameter has been seen in the log.

bool param(const std::string name, float &ret) const

Retrieve parameter value. @detail Returns parameter value ONLY from input, not from defaults.

Parameters
  • name – Parameter value to retrieve.

  • ret[out] Parameter value.

Returns

true if the parameter has been seen in the log.

inline uint16_t param_count() const

Number of parameters seen.

Returns

Number of parameters seen in input.

bool param_seen(const std::string name) const

Parameter status.

Returns

true if the parameter has been seen in the log.

uint64_t param_T(const std::string name) const

Timestamp at which a parameter was last modified (microseconds).

Parameters

name – Parameter modification time to retrieve.

Returns

Parameter modification time (microseconds).

void param_set(const char *name, const float value)

Set a parameter.

Parameters
  • name – Parameter to set.

  • value – New value of parameter.

virtual bool param_default(const char *name, float &ret) const

Return the default value for a parameter. @detail Default parameters are supplied so that some analysis can be done even in the absence of parameters in the logs.

Parameters
  • name – Parameter to retrieve default value for.

  • ret[out] Value of parameter.

Returns

true if a default was found for the parameters.

bool param_with_defaults(const char *name, float &ret) const

Retrieve a parameter value. @detail Returns the value last set for this parameter, or a default if it has not been set yet.

Parameters
  • name – Parameter to retrieve default value for.

  • ret[out] Value of parameter.

Returns

true if the parameter value was found.

float require_param_with_defaults(const char *name) const

Retrieves a parameter value and abort()s if it not found. @detail Returns the value last set for this parameter, or a default if it has not been set yet.

Parameters

name – Parameter to retrieve default value for.

Returns

Value of parameter.

void set_servo_output(uint16_t ch1, uint16_t ch2, uint16_t ch3, uint16_t ch4, uint16_t ch5, uint16_t ch6, uint16_t ch7, uint16_t ch8)

Set outputs for all servos.

Parameters
  • ch1 – current output for servo 1 (ppm).

  • ch2 – current output for servo 2 (ppm).

  • ch3 – current output for servo 3 (ppm).

  • ch4 – current output for servo 4 (ppm).

  • ch5 – current output for servo 5 (ppm).

  • ch6 – current output for servo 6 (ppm).

  • ch7 – current output for servo 7 (ppm).

  • ch8 – current output for servo 8 (ppm).

void set_servo_output(uint8_t channel_number, uint16_t value)

Set outputs for single servo.

Parameters
  • channel_number – Servo to set value for.

  • value – New value for servo output (ppm).

inline uint16_t servo_output(uint8_t channel_number) const

Return current output for a specific servo.

Parameters

channel_number – Servo number.

Returns

Current servo output (ppm).

void set_T(const uint64_t time_us)

Set timestamp distinguishing logging events. @detail This may or may not be a real wall-clock time.

Parameters

time_us – New timestamp (microseconds).

inline uint64_t T()

Current timestamp.

Returns

Current universe timestamp.

inline float roll() const

Canonical vehicle attitude - roll.

Returns

Canonical attitude - roll (degrees).

inline float pitch() const

Canonical vehicle attitude - pitch (degrees).

Returns

Canonical attitude - pitch.

inline float yaw() const

Canonical vehicle attitude - yaw.

Returns

Canonical attitude - yaw (degrees).

inline uint64_t roll_modtime() const

Modification time - roll.

Returns

Timestamp roll was last modified (microseconds).

inline uint64_t pitch_modtime() const

Modification time - pitch.

Returns

Timestamp pitch was last modified (microseconds).

inline uint64_t yaw_modtime() const

Modification time - yaw.

Returns

Timestamp yaw was last modified (microseconds).

inline void set_roll(float roll)

Set canonical vehicle atttiude - roll.

Parameters

new – Canonical attitude - roll (degrees).

inline void set_pitch(float roll)

Set canonical vehicle atttiude - pitch.

Parameters

new – Canonical attitude - pitch (degrees).

inline void set_yaw(float roll)

Set canonical vehicle atttiude - yaw.

Parameters

new – Canonical attitude - yaw (degrees).

inline void set_desroll(float roll)

set Navigation Controller desired attitude - roll.

Parameters

roll – New desired attitude - roll.

inline void set_despitch(float pitch)

Set Navigation Controller desired attitude - pitch.

Parameters

roll – New desired attitude - pitch.

inline void set_desyaw(float yaw)

Set Navigation Controller desired attitude - yaw.

Parameters

roll – New desired attitude - yaw.

inline float desroll() const

Navigation Controller desired attitude - roll.

inline float despitch() const

Navigation Controller desired attitude - pitch.

inline float desyaw() const

Navigation Controller desired attitude - yaw.

inline void set_altitude(float value)

Set canonical vehicle altitude.

Parameters

value – New vehicle altitude.

inline float altitude() const

Canonical vehicle altitude.

Returns

The vehicle’s canonical altitude.

inline uint64_t alt_modtime() const

Canonical vehicle altitude modification time.

Returns

Timestamp The canonical vehicle altitude was modified (microseconds).

inline void set_lat(double lat)

Set vehicle canonical latitude.

Parameters

lat – New vehicle canonical latitude.

inline void set_lon(double lon)

Set vehicle canonical longitude.

Parameters

lat – New vehicle canonical latitude.

inline double lat()
inline double lon()
inline PositionEstimate *position_estimate(const std::string name)

Retrieve named position estimate.

Parameters

name – Name of position estimate to retrieve.

Returns

A position estimate.

inline AttitudeEstimate *attitude_estimate(const std::string name)

Retrieve named attitude estimate.

Parameters

name – Name of attitude estimate to retrieve.

Returns

An attitude estimate.

inline AltitudeEstimate *altitude_estimate(const std::string name)

Retrieve named altitude estimate.

Parameters

name – Name of altitude estimate to retrieve.

Returns

An altitude estimate.

inline VelocityEstimate *velocity_estimate(const std::string name)

Retrieve named velocity estimate.

Parameters

name – Name of velocity estimate to retrieve.

Returns

A velocity estimate.

double distance_from_origin()

Distance from canonical vehicle position to canonical origin.

Returns

Distance from origin, or -1 if we just don’t know.

inline std::map<const std::string, bool> sensors_health()

Hardware diagnostics.

Returns

Map of sensor name to its boolean health.

inline void sensor_set_healthy(std::string name, bool value)

Set the health status of a sensor by name.

Parameters
  • name – Name of sensor.

  • value – New health value of sensor.

inline std::map<uint32_t, uint32_t> subsys_errors()

Subsystem health.

Returns

Map of subsystem ID to its status

inline void set_subsys_error_code(uint32_t subsys, uint32_t code)

Set an error flag value.

Parameters
  • subsys – subsystem ID

  • code – error code

inline void set_battery_remaining(float percent)

Indicate amount of flight battery remaining.

Parameters

percent – Percentage of charge remaining.

inline float battery_remaining()

Amount of battery remaining.

Returns

Amount of battery remaining (percentage).

inline uint64_t battery_remaining_T()

Battery remaining modification time.

Returns

Timestamp when battery remaining was last modified (microseconds).

inline void set_battery_in_failsafe(bool in_failsafe)

Indicate a battery is in failsafe.

Parameters

in_failsafetrue if battery is in failsafe.

inline bool battery_in_failsafe()

Battery failsafe status.

Returns

true if the battery is in failsafe.

inline uint64_t battery_in_failsafe_T()

Battery in failsafe modification time.

Returns

Timestamp when battery failsafe was last modified (microseconds).

inline const std::map<const std::string, AttitudeEstimate*> &attitude_estimates()

Attitude estimates.

Returns

Map of attitude estimate name to attitude estimate.

inline const std::map<const std::string, AltitudeEstimate*> &altitude_estimates()

Altitude estimates.

Returns

Map of altitude estimate name to altitude estimate.

inline const std::map<const std::string, PositionEstimate*> &position_estimates()

Position estimates.

Returns

Map of position estimate name to position estimate.

inline const std::map<const std::string, VelocityEstimate*> &velocity_estimates()

Velocity estimates.

Returns

Map of velocity estimate name to velocity estimate.

inline AutoPilot &autopilot()

Autopilot status information.

Returns

Object containing autopilot status information.

inline void autopilot_set_overruns(uint16_t overruns)

Set number of autopilot scheduler overruns.

Parameters

scheduler – Overruns in last loopcount() loops.

inline void autopilot_set_loopcount(uint16_t count)

Set number of loops for scheduler data.

Parameters

count – Number of loops for scheduler data.

inline void autopilot_set_slices_max(uint16_t slices)

Maximum number of slices moved in a scheduler loop.

Parameters

slices – Maximum number of slices used.

inline void autopilot_set_slices_min(uint16_t slices)

Minimum number of slices moved in a scheduler loop.

Parameters

slices – Minimum number of slices used.

inline void autopilot_set_slices_avg(uint16_t slices)

Average number of slices moved in a scheduler loop.

Parameters

slices – Average number of slices used.

inline void autopilot_set_slices_stddev(uint16_t slices)

Stddev number of slices moved in a scheduler loop.

Parameters

slices – Stddev from average number of slices used.

inline void autopilot_set_vcc(double slices)

Set vcc of autopilot.

Parameters

vcc – vcc supplied to autopilot

inline const std::map<const std::string, GPSInfo*> &gpsinfos()

Information from global positioning systems.

Returns

Map from GPS name to GPS information object.

inline GPSInfo *gpsinfo(const std::string name)

Information from a specific global positioning system.

Parameters

name – Name of GPS unit to return information for.

inline const std::map<const std::string, Compass*> &compasses()

Magnetometer information.

Returns

Map from compass name to compass data.

inline Compass *compass(const std::string name)

Magnetometer information for specific named compass.

Parameters

nameCompass name to retrieve information for.

Returns

Compass information for named compass.

inline const std::map<const std::string, IMU*> &imus()

IMU information.

Returns

Map from IMU name to IMU data.

inline IMU *imu(const std::string name)

IMU information for specific named IMU.

Parameters

nameIMU to retrieve information for. return IMU information for named IMU.

inline const Attitude &att() const

Canonical vehicle attitude.

Returns

The vehicle’s current canonical attitude.

inline const AttitudeRate &rate() const

Canonical vehicle attitude rates.

Returns

The vehicle’s current canonical attitude rates.

inline const Position &pos() const

Canonical vehicle position.

Returns

The vehicle’s current canonical position.

inline const Altitude &alt() const

Canonical vehicle altitude.

Returns

The vehicle’s current canonical absolute altitude.

inline const Velocity &vel() const

Canonical vehicle velocity.

Returns

The vehicle’s current canonical velocity.

inline Attitude &att()

Canonical vehicle attitude.

Returns

The vehicle’s current canonical attitude.

inline AttitudeRate &rate()

Canonical vehicle attitude rates.

Returns

The vehicle’s current canonical attitude rates.

inline Position &pos()

Canonical vehicle position.

Returns

The vehicle’s current canonical position.

inline Altitude &alt()

Canonical vehicle altitude.

Returns

The vehicle’s current canonical absolute altitude.

inline Velocity &vel()

Canonical vehicle velocity.

Returns

The vehicle’s current canonical velocity.

inline double origin_lat() const

Vehicle origin position - latitude.

Returns

The vehicle’s original position - latitude.

inline uint64_t origin_lat_T() const

Modification time of the vehicle’s original latitude.

Returns

The modification time of the vehicle’s original latitude.

inline double origin_lon() const

Vehicle origin position - longitude.

Returns

The vehicle’s original position - longitude.

inline uint64_t origin_lon_T() const

Modification time of the vehicle’s original longitude.

Returns

The modification time of the vehicle’s original longitude.

inline void set_origin_lat(double value)

Set vehicle’s original latitude.

Parameters

value – New vehicle’s original latitude.

inline void set_origin_lon(double value)

Set vehicle’s original longitude.

Parameters

value – New vehicle’s original longitude.

inline Position &origin()

Vehicle origin.

Returns

The vehicle’s origin.

inline const Position &origin() const

Vehicle origin.

Returns

The vehicle’s origin.

inline const Altitude &origin_alt() const

Vehicle’s original altitude.

Returns

The vehicle’s original altitude (metres).

inline void set_origin_altitude(double value)

Set vehicle origin altitude.

Parameters

value – The vehicle’s origin altitude (metres).

inline double origin_altitude() const

Vehicle’s original altitude.

Returns

The vehicle’s original altitude (metres).

inline uint64_t origin_altitude_T() const

Modification time of vehicle’s original altitude.

Returns

Timestamp when origin altitude was last set (microseconds).

bool relative_alt(double &relative) const

vehicle’s altitude relative to origin altitude.

Parameters

relative[out] Vehicle’s altitude relative to its origin.

Returns

true if the relative value could e calculated.

inline bool crashed() const

Vehicle’s crash state.

Returns

true if the craft is believed to be in a crashed state.

inline void set_crashed(bool value)

Set the vehicle’s crash state. @value The vehicle’s new crash state.

bool any_acc_clipping() const

Accelerometer clipping state.

Returns

true if any accelerometer is clipping.

Public Static Functions

static void switch_vehicletype(Base *&_vehicle, vehicletype_t newtype)

Change the vehicle from one type to another. @detail A base vehicle is used to gather information until we determine what vehicle type we are actually analyzing. This call is used to switch to a more-specific vehicle type.

Parameters

_vehicle – Vehicle to change type of. @newtype New vehicle type.

Protected Functions

inline const AV_Nav &nav() const

Navigation state object.

Returns

Object representing Navigation Controller state.

Protected Attributes

uint16_t _servo_output[9] = {}

Current servo outputs (ppm).


class AnalyzerVehicle::Copter : public AnalyzerVehicle::Base

Public Types

enum copter_frame_type

all possible copter frame types

Values:

enumerator invalid
enumerator frame_type_quad
enumerator frame_type_y6
enumerator frame_type_hexa
enumerator frame_type_octa

Public Functions

inline Copter()

Construct a Copter object.

inline virtual const std::string typeString() const override

Returns a short string describing the vehicle.

Returns

A short string describing the vehicle e.g. “Copter”.

virtual bool is_flying() const override

Evaluation of whether the vehicle is flying.

Returns

true if it is believed the vehicle is flying.

virtual bool param_default(const char *name, float &ret) const override

Return the default value for a parameter. @detail Default parameters are supplied so that some analysis can be done even in the absence of parameters in the logs.

Parameters
  • name – Parameter to retrieve default value for.

  • ret[out] Value of parameter.

Returns

true if a default was found for the parameters.

inline virtual vehicletype_t vehicletype() const override

Vehicle type.

Returns

The current vehicle type.

inline uint8_t num_motors() const

Supply number of motors configured on this vehicle.

inline uint8_t servo_output(const uint8_t i) const

get current PWM output of motor i

bool any_motor_running_fast() const

Indicate if any of the vehicle motors appears to be running at flight speed.

Returns

True if any motor is running fast enough to indicate flight.

bool exceeding_angle_max() const

Indicate excessive lean angles of aircraft.

Returns

True if vehicle is past its configured maximum angle.

std::set<uint8_t> motors_clipping_low() const

Indicates if any motor appears to be running as slow as it can.

Returns

a set of motor numbers which appear to be running slowly

std::set<uint8_t> motors_clipping_high() const

Indicates if any motor appears to be running as fast as it can.

Returns

a set of motor numbers which appear to be running flat out

uint16_t is_flying_motor_threshold() const

Supply threshold over which a motor is considered to be running fast enough that it might cause flight.

Returns

a PWM output value

void set_frame_type(copter_frame_type frame_type)

set copter frame type

Parameters

frame_type – new copter frame type

void set_frame(const char *frame_config_string)

set copter frame type

Parameters

frame_config_string – new copter frame type, as a string as found in dataflash and mavlink logs

inline copter_frame_type frame_type()

retrieve copter frame type

Returns

the current copter frame type


class AnalyzerVehicle::Plane : public AnalyzerVehicle::Base

Public Types

enum flightmode_t

Values:

enumerator UNKNOWN
enumerator MANUAL
enumerator QSTABILIZE
enumerator QHOVER
enumerator QLOITER
enumerator QLAND
enumerator QRTL

Public Functions

inline Plane()

Construct a Plane object.

inline virtual const std::string typeString() const override

Returns a short string describing the vehicle.

Returns

A short string describing the vehicle e.g. “Copter”.

virtual bool is_flying() const override

Evaluation of whether the vehicle is flying.

Returns

true if it is believed the vehicle is flying.

virtual bool param_default(const char *name, float &ret) const override

Return the default value for a parameter. @detail Default parameters are supplied so that some analysis can be done even in the absence of parameters in the logs.

Parameters
  • name – Parameter to retrieve default value for.

  • ret[out] Value of parameter.

Returns

true if a default was found for the parameters.

inline virtual vehicletype_t vehicletype() const override

Vehicle type.

Returns

The current vehicle type.

inline flightmode_t mode() const

Return current flight mode.

Returns

current flight mode

inline void set_mode(const flightmode_t mode)

set current flight mode

inline bool in_q_mode() const

Return true currently in vertical flight mode.

Returns

true if in vertical flight mode, false otherwise


class AnalyzerVehicle::Attitude

Abstraction of a vehicle attitude.

Public Functions

inline float roll() const
inline float pitch() const
inline float yaw() const
inline uint64_t roll_modtime() const
inline uint64_t pitch_modtime() const
inline uint64_t yaw_modtime() const
inline void set_roll(uint64_t T, float roll)
inline void set_pitch(uint64_t T, float pitch)
inline void set_yaw(uint64_t T, float yaw)

class AnalyzerVehicle::Altitude

Abstraction of a vehicle altitude.

Public Functions

inline void set_alt(uint64_t T, double alt)
inline double alt() const
inline uint64_t alt_modtime() const

class AnalyzerVehicle::AltitudeEstimate

Altitude according to some sensor or algorithm.

Public Functions

inline AltitudeEstimate(const std::string name)
inline AltitudeEstimate()
inline const std::string name()
inline const Altitude altitude()
inline void set_alt(uint64_t T, float alt)
inline float alt()

class AnalyzerVehicle::Position

Abstraction of a vehicle global position (2D).

Public Functions

inline void set_lat(uint64_t T, double lat)
inline double lat() const
inline uint64_t lat_modtime() const
inline void set_lon(uint64_t T, double lon)
inline double lon() const
inline uint64_t lon_modtime() const
double horizontal_distance_to(Position otherpos) const
inline bool is_zero_zero()

class AnalyzerVehicle::Velocity

Abstraction of a vehicle velocity.

Public Functions

inline bool is_0d()
inline bool is_2d()
inline bool is_3d()
inline double size_2d()
inline double size()
inline void set_x(uint64_t T, double x)
inline void set_y(uint64_t T, double y)
inline void set_z(uint64_t T, double z)
inline void set_scalar(uint64_t T, double scalar)
inline uint64_t velocity_modtime()
inline void set_is2D_scalar(const bool value)
inline bool is2D_scalar()

class AnalyzerVehicle::EKF

State information for a base Extended Kalman Filter.

Subclassed by AnalyzerVehicle::NKF

Public Functions

inline void set_variance(uint64_t T, std::string name, double value)
uint64_t variance_T(std::string name) const
inline void set_flags(uint64_t T, uint16_t flags)
inline uint16_t flags() const
inline uint64_t flags_T() const
inline std::map<const std::string, double> variances()

class AnalyzerVehicle::AttitudeEstimate

Attitude according to some sensor or algorithm.

Public Functions

inline AttitudeEstimate(const std::string name)
inline AttitudeEstimate()
inline const std::string name()
inline const Attitude attitude()
inline void set_roll(uint64_t T, double roll)
inline void set_pitch(uint64_t T, double pitch)
inline void set_yaw(uint64_t T, double yaw)
inline double roll()
inline double pitch()
inline double yaw()

class AnalyzerVehicle::PositionEstimate

Position according to some sensor or algorithm.

Public Functions

inline PositionEstimate(const std::string name)
inline PositionEstimate()
inline const std::string name()
inline const Position position()
inline void set_lat(uint64_t T, double lat)
inline void set_lon(uint64_t T, double lon)
inline double lat()
inline double lon()

class AnalyzerVehicle::AV_Nav

Information about the Navigation Controller’s output.

Public Functions

inline void set_desroll(uint64_t T, float roll)
inline float desroll() const
inline void set_despitch(uint64_t T, float pitch)
inline float despitch() const
inline void set_desyaw(uint64_t T, float yaw)
inline float desyaw() const

class AnalyzerVehicle::Compass

A source of magnetic field information.

Public Functions

inline Compass(const std::string name)
inline const std::string name() const
inline Vector3f &field()
inline uint64_t field_T()
inline void set_field_T(uint64_t field_T)

class AnalyzerVehicle::GPSInfo

A source of GPS information (typically output from a GPS device).

Public Functions

inline GPSInfo(std::string name)
inline const std::string name()
inline uint8_t fix_type()
inline void set_fix_type(uint8_t fix_type)
inline double hdop()
inline void set_hdop(double hdop)
inline double sacc()
inline void set_sacc(double sacc)
inline uint8_t satellites()
inline void set_satellites(uint8_t satellites)

class AnalyzerVehicle::AutoPilot

Information about the AutoPilot.

Public Types

enum AutoPilotHardware

Values:

enumerator UNKNOWN
enumerator PX4V2

Public Functions

inline uint16_t overruns()
inline uint16_t overruns_T()
void set_overruns(uint64_t T, uint16_t)
inline uint16_t loopcount()
void set_loopcount(uint64_t T, uint16_t)
inline uint64_t slices_max_T()
inline uint16_t slices_max()
void set_slices_max(uint64_t T, uint16_t)
inline uint16_t slices_min()
void set_slices_min(uint64_t T, uint16_t)
inline uint16_t slices_avg()
void set_slices_avg(uint64_t T, uint16_t)
inline uint16_t slices_stddev()
void set_slices_stddev(uint64_t T, uint16_t)
inline double vcc()
inline uint64_t vcc_T()
void set_vcc(uint64_t T, double)
inline void set_hardware(const AutoPilotHardware hw)
inline AutoPilotHardware hardware() const

class AnalyzerVehicle::IMU

Accelerometer and gyroscope information from onboard IMUs.

Public Functions

inline IMU(const std::string name, uint64_t &T)
inline const std::string name() const
inline uint64_t T() const
inline Vector3f &acc()
inline Vector3f &gyr()
bool gyr_avg(const uint16_t count, Vector3f &ret) const

Retrieve average of gyroscopes by sample count.

Parameters
  • count – number of samples to average over.

  • ret[out] the returned average.

Returns

True if the average could be found.

bool gyr_avg(uint64_t T, uint64_t T_delta, Vector3f &ret) const

Retrieve average of gyroscopes by time.

Parameters
  • T – Highest timestamp to use (microseconds, typically _vehicle->T())

  • T_delta – Time span over which to take average (microseconds).

  • ret[out] The returned average.

Returns

True if the average could be found.

inline uint64_t acc_T()
inline uint64_t gyr_T()
inline void set_acc_T(uint64_t acc_T)
void set_gyr(uint64_t T, Vector3f values)
void set_acc_clip_count(uint16_t count)
uint64_t last_acc_clip_time() const
bool acc_is_clipping() const