31 memset(&pkt, 0,
sizeof(pkt));
47 memset(&pkt, 0,
sizeof(pkt));
119 strncpy(pkt.
name, name,
sizeof(pkt.
name));
162 float hacc = 0, vacc = 0, sacc = 0;
170 hacc : (uint16_t)
MIN((hacc*100), UINT16_MAX),
270 climbrate : climbrate,
347 Vector3f delta_angle, delta_velocity;
412 mavlink_mission_item_t mav_cmd = {};
433 strncpy(pkt.
msg, message,
sizeof(pkt.
msg));
439 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS 443 safety_and_armed |= 1U<<2;
505 #if AP_AHRS_NAVEKF_AVAILABLE 510 Log_Write_EKF2(ahrs);
514 Log_Write_EKF3(ahrs);
525 "TimeUS,Cnt,IMUMin,IMUMax,EKFMin,EKFMax,AngMin,AngMax,VMin,VMax",
565 velN : (float)(velNED.
x),
566 velE : (float)(velNED.
y),
567 velD : (float)(velNED.
z),
569 posN : (float)(posNE.
x),
570 posE : (float)(posNE.
y),
571 posD : (float)(posD),
594 AZbias : (int8_t)(100*azbias),
595 scaleX : (int16_t)(100*gyroScaleFactor.
x),
596 scaleY : (int16_t)(100*gyroScaleFactor.
y),
597 scaleZ : (int16_t)(100*gyroScaleFactor.
z),
598 windN : (int16_t)(100*wind.
x),
599 windE : (int16_t)(100*wind.
y),
600 magN : (int16_t)(magNED.
x),
601 magE : (int16_t)(magNED.
y),
602 magD : (int16_t)(magNED.
z),
603 magX : (int16_t)(magXYZ.
x),
604 magY : (int16_t)(magXYZ.
y),
605 magZ : (int16_t)(magXYZ.
z),
606 index : (uint8_t)(magIndex)
620 innovVN : (int16_t)(100*velInnov.
x),
621 innovVE : (int16_t)(100*velInnov.
y),
622 innovVD : (int16_t)(100*velInnov.
z),
623 innovPN : (int16_t)(100*posInnov.
x),
624 innovPE : (int16_t)(100*posInnov.
y),
625 innovPD : (int16_t)(100*posInnov.
z),
630 innovVT : (int16_t)(100*tasInnov)
641 uint16_t faultStatus=0;
642 uint8_t timeoutStatus=0;
646 float tempVar = fmaxf(fmaxf(magVar.
x,magVar.
y),magVar.
z);
665 faults : (uint16_t)(faultStatus),
666 timeouts : (uint8_t)(timeoutStatus),
667 solution : (uint16_t)(solutionStatus.value),
668 gps : (uint16_t)(gpsStatus.value),
676 float flowInnovX=0, flowInnovY=0;
677 float auxFlowInnov=0;
681 float gndOffsetErr=0;
683 ahrs.
get_NavEKF2().
getFlowDebug(-1,normInnov, gndOffset, flowInnovX, flowInnovY, auxFlowInnov, HAGL, rngInnov, range, gndOffsetErr);
689 FIX : (int16_t)(1000*flowInnovX),
690 FIY : (int16_t)(1000*flowInnovY),
691 AFI : (int16_t)(1000*auxFlowInnov),
692 HAGL : (int16_t)(100*
HAGL),
693 offset : (int16_t)(100*gndOffset),
694 RI : (int16_t)(100*rngInnov),
695 meaRng : (uint16_t)(100*range),
696 errHAGL : (uint16_t)(100*gndOffsetErr),
697 angErr : (
float)predictorErrors.
x,
698 velErr : (float)predictorErrors.
y,
699 posErr : (
float)predictorErrors.
z 734 velN : (float)(velNED.
x),
735 velE : (float)(velNED.
y),
736 velD : (float)(velNED.
z),
738 posN : (float)(posNE.
x),
739 posE : (float)(posNE.
y),
740 posD : (float)(posD),
758 AZbias : (int8_t)(100*azbias),
759 scaleX : (int16_t)(100*gyroScaleFactor.
x),
760 scaleY : (int16_t)(100*gyroScaleFactor.
y),
761 scaleZ : (int16_t)(100*gyroScaleFactor.
z),
762 windN : (int16_t)(100*wind.
x),
763 windE : (int16_t)(100*wind.
y),
764 magN : (int16_t)(magNED.
x),
765 magE : (int16_t)(magNED.
y),
766 magD : (int16_t)(magNED.
z),
767 magX : (int16_t)(magXYZ.
x),
768 magY : (int16_t)(magXYZ.
y),
769 magZ : (int16_t)(magXYZ.
z),
770 index : (uint8_t)(magIndex)
779 innovVN : (int16_t)(100*velInnov.
x),
780 innovVE : (int16_t)(100*velInnov.
y),
781 innovVD : (int16_t)(100*velInnov.
z),
782 innovPN : (int16_t)(100*posInnov.
x),
783 innovPE : (int16_t)(100*posInnov.
y),
784 innovPD : (int16_t)(100*posInnov.
z),
789 innovVT : (int16_t)(100*tasInnov)
795 tempVar = fmaxf(fmaxf(magVar.
x,magVar.
y),magVar.
z);
812 faults : (uint16_t)(faultStatus),
813 timeouts : (uint8_t)(timeoutStatus),
814 solution : (uint16_t)(solutionStatus.value),
815 gps : (uint16_t)(gpsStatus.value),
840 float bcnPosOffsetHigh;
841 float bcnPosOffsetLow;
848 rng : (int16_t)(100*
rng),
849 innov : (int16_t)(100*
innov),
856 offsetLow : (int16_t)(100*bcnPosOffsetLow),
867 static uint32_t lastTimingLogTime_ms = 0;
873 Log_Write_EKF_Timing(i==0?
"NKT1":
"NKT2", time_us, timing);
905 velN : (float)(velNED.
x),
906 velE : (float)(velNED.
y),
907 velD : (float)(velNED.
z),
909 posN : (float)(posNE.
x),
910 posE : (float)(posNE.
y),
911 posD : (float)(posD),
935 windN : (int16_t)(100*wind.
x),
936 windE : (int16_t)(100*wind.
y),
937 magN : (int16_t)(magNED.
x),
938 magE : (int16_t)(magNED.
y),
939 magD : (int16_t)(magNED.
z),
940 magX : (int16_t)(magXYZ.
x),
941 magY : (int16_t)(magXYZ.
y),
942 magZ : (int16_t)(magXYZ.
z),
943 index : (uint8_t)(magIndex)
957 innovVN : (int16_t)(100*velInnov.
x),
958 innovVE : (int16_t)(100*velInnov.
y),
959 innovVD : (int16_t)(100*velInnov.
z),
960 innovPN : (int16_t)(100*posInnov.
x),
961 innovPE : (int16_t)(100*posInnov.
y),
962 innovPD : (int16_t)(100*posInnov.
z),
967 innovVT : (int16_t)(100*tasInnov)
978 uint16_t faultStatus=0;
979 uint8_t timeoutStatus=0;
983 float tempVar = fmaxf(fmaxf(magVar.
x,magVar.
y),magVar.
z);
1002 faults : (uint16_t)(faultStatus),
1003 timeouts : (uint8_t)(timeoutStatus),
1004 solution : (uint16_t)(solutionStatus.value),
1005 gps : (uint16_t)(gpsStatus.value),
1006 primary : (int8_t)primaryIndex
1013 float flowInnovX=0, flowInnovY=0;
1014 float auxFlowInnov=0;
1018 float gndOffsetErr=0;
1020 ahrs.
get_NavEKF3().
getFlowDebug(-1,normInnov, gndOffset, flowInnovX, flowInnovY, auxFlowInnov, HAGL, rngInnov, range, gndOffsetErr);
1026 FIX : (int16_t)(1000*flowInnovX),
1027 FIY : (int16_t)(1000*flowInnovY),
1028 AFI : (int16_t)(1000*auxFlowInnov),
1029 HAGL : (int16_t)(100*
HAGL),
1030 offset : (int16_t)(100*gndOffset),
1031 RI : (int16_t)(100*rngInnov),
1032 meaRng : (uint16_t)(100*range),
1033 errHAGL : (uint16_t)(100*gndOffsetErr),
1034 angErr : (
float)predictorErrors.
x,
1035 velErr : (float)predictorErrors.
y,
1036 posErr : (
float)predictorErrors.
z 1071 velN : (float)(velNED.
x),
1072 velE : (float)(velNED.
y),
1073 velD : (float)(velNED.
z),
1075 posN : (float)(posNE.
x),
1076 posE : (float)(posNE.
y),
1077 posD : (float)(posD),
1097 windN : (int16_t)(100*wind.
x),
1098 windE : (int16_t)(100*wind.
y),
1099 magN : (int16_t)(magNED.
x),
1100 magE : (int16_t)(magNED.
y),
1101 magD : (int16_t)(magNED.
z),
1102 magX : (int16_t)(magXYZ.
x),
1103 magY : (int16_t)(magXYZ.
y),
1104 magZ : (int16_t)(magXYZ.
z),
1105 index : (uint8_t)(magIndex)
1114 innovVN : (int16_t)(100*velInnov.
x),
1115 innovVE : (int16_t)(100*velInnov.
y),
1116 innovVD : (int16_t)(100*velInnov.
z),
1117 innovPN : (int16_t)(100*posInnov.
x),
1118 innovPE : (int16_t)(100*posInnov.
y),
1119 innovPD : (int16_t)(100*posInnov.
z),
1124 innovVT : (int16_t)(100*tasInnov)
1130 tempVar = fmaxf(fmaxf(magVar.
x,magVar.
y),magVar.
z);
1147 faults : (uint16_t)(faultStatus),
1148 timeouts : (uint8_t)(timeoutStatus),
1149 solution : (uint16_t)(solutionStatus.value),
1150 gps : (uint16_t)(gpsStatus.value),
1151 primary : (int8_t)primaryIndex
1174 float bcnPosOffsetHigh;
1175 float bcnPosOffsetLow;
1183 rng : (int16_t)(100*
rng),
1184 innov : (int16_t)(100*
innov),
1190 offsetHigh : (int16_t)(100*bcnPosOffsetHigh),
1191 offsetLow : (int16_t)(100*bcnPosOffsetLow),
1192 posN : (int16_t)(100*posNED.
x),
1193 posE : (int16_t)(100*posNED.
y),
1194 posD : (int16_t)(100*posNED.
z)
1201 Vector3f velBodyInnov,velBodyInnovVar;
1202 static uint32_t lastUpdateTime_ms = 0;
1204 if (updateTime_ms > lastUpdateTime_ms) {
1216 lastUpdateTime_ms = updateTime_ms;
1220 static uint32_t lastEkfStateVarLogTime_ms = 0;
1263 static uint32_t lastTimingLogTime_ms = 0;
1269 Log_Write_EKF_Timing(i==0?
"XKT1":
"XKT2", time_us, timing);
1283 command : (uint16_t)mav_cmd.command,
1284 param1 : (
float)mav_cmd.param1,
1285 param2 : (float)mav_cmd.param2,
1286 param3 : (
float)mav_cmd.param3,
1287 param4 : (float)mav_cmd.param4,
1291 frame : (uint8_t)mav_cmd.frame
1303 txbuf : packet.txbuf,
1304 noise : packet.noise,
1307 fixed : packet.fixed
1315 int32_t altitude, altitude_rel, altitude_gps;
1318 altitude_rel = current_loc.
alt;
1320 altitude = current_loc.
alt;
1396 const uint8_t battery_instance,
1411 temperature : (int16_t)(has_temp ? (temp * 100) : 0),
1431 "Battery cell number doesn't match in library and log structure");
1440 if (num_instances >= 1) {
1441 Log_Write_Current_instance(time_us,
1447 if (num_instances >= 2) {
1448 Log_Write_Current_instance(time_us,
1463 mag_x : (int16_t)mag_field.
x,
1464 mag_y : (int16_t)mag_field.
y,
1465 mag_z : (int16_t)mag_field.
z,
1511 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 1512 static int _esc_status_sub = -1;
1513 struct esc_status_s esc_status;
1515 if (_esc_status_sub == -1) {
1517 _esc_status_sub = orb_subscribe(ORB_ID(esc_status));
1521 bool esc_updated =
false;
1522 orb_check(_esc_status_sub, &esc_updated);
1523 if (esc_updated && (OK == orb_copy(ORB_ID(esc_status), _esc_status_sub, &esc_status))) {
1524 if (esc_status.esc_count > 8) {
1525 esc_status.esc_count = 8;
1528 for (uint8_t i = 0; i < esc_status.esc_count; i++) {
1532 if (esc_status.esc[i].esc_address != 0) {
1536 rpm : (int32_t)(esc_status.esc[i].esc_rpm/10),
1537 voltage : (uint16_t)(esc_status.esc[i].esc_voltage*100.0f + .5f),
1538 current : (uint16_t)(esc_status.esc[i].esc_current*100.0f + .5f),
1539 temperature : (int16_t)(esc_status.esc[i].esc_temperature*100.0f + .5f),
1547 #endif // CONFIG_HAL_BOARD 1705 float accuracy = 0.0f;
1740 float close_ang = 0.0f, close_dist = 0.0f;
1747 dist0 : dist_array.distance[0],
1748 dist45 : dist_array.distance[1],
1749 dist90 : dist_array.distance[2],
1750 dist135 : dist_array.distance[3],
1751 dist180 : dist_array.distance[4],
1752 dist225 : dist_array.distance[5],
1753 dist270 : dist_array.distance[6],
1754 dist315 : dist_array.distance[7],
1759 WriteBlock(&pkt_proximity,
sizeof(pkt_proximity));
void getFlowDebug(int8_t instance, float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
bool get_soft_armed() const
uint8_t get_primary(void) const
AP_RangeFinder_Backend * get_backend(uint8_t id) const
float get_climb_rate(void)
void getTiltError(int8_t instance, float &ang) const
bool enabled(uint8_t i) const
void Log_Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets)
void getInnovations(int8_t index, Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
uint8_t num_instances(void) const
bool Log_Write_Message(const char *message)
uint8_t get_rally_total() const
void Log_Write_AOA_SSA(AP_AHRS &ahrs)
Object managing Rally Points.
bool getRangeBeaconDebug(int8_t instance, uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow, Vector3f &posNED) const
uint8_t getActiveMag(int8_t instance) const
void getTiltError(int8_t instance, float &ang) const
void Log_Write_Trigger(const AP_AHRS &ahrs, const Location ¤t_loc)
void getMagNED(int8_t instance, Vector3f &magNED) const
virtual float board_voltage(void)=0
float safe_sqrt(const T v)
const Vector3f & get_accel_target() const
float get_rpm(uint8_t instance) const
virtual const Vector3f & get_accel_ef_blended(void) const
void getFilterGpsStatus(int8_t instance, nav_gps_status &faults) const
bool Log_Write_Format_Units(const struct LogStructure *structure)
bool getPosNE(int8_t instance, Vector2f &posNE) const
enum Rotation orientation() const
virtual const Vector3f & get_gyro(void) const =0
bool Log_Write_Format(const struct LogStructure *structure)
float beacon_distance(uint8_t beacon_instance) const
void getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void Log_Write_Airspeed(AP_Airspeed &airspeed)
uint8_t activeCores(void) const
virtual uint16_t read(uint8_t ch)=0
void getGyroScaleErrorPercentage(int8_t instance, Vector3f &gyroScale) const
bool Log_Write_Parameter(const char *name, float value)
uint16_t distance_cm() const
const Vector3f & get_motor_offsets(uint8_t i) const
const Vector3f & get_gyro(uint8_t i) const
float get_temperature(void) const
bool get_upward_distance(uint8_t instance, float &distance) const
float get_baro_drift_offset(void)
virtual bool get_position(struct Location &loc) const =0
auto wrap_360_cd(const T angle) -> decltype(wrap_360(angle, 100.f))
uint32_t getBodyFrameOdomDebug(int8_t instance, Vector3f &velInnov, Vector3f &velInnovVar) const
void getOutputTrackingError(int8_t instance, Vector3f &error) const
void getFilterTimeouts(int8_t instance, uint8_t &timeouts) const
const struct Location & get_home(void) const
bool getOriginLLH(int8_t instance, struct Location &loc) const
uint16_t num_commands() const
void getGyroBias(int8_t instance, Vector3f &gyroBias) const
void Log_Write_Beacon(AP_Beacon &beacon)
float get_offset(uint8_t i) const
virtual float get_error_yaw(void) const =0
void getFilterStatus(int8_t instance, nav_filter_status &status) const
void Log_Write_Rate(const AP_AHRS &ahrs, const AP_Motors &motors, const AC_AttitudeControl &attitude_control, const AC_PosControl &pos_control)
uint16_t time_week(uint8_t instance) const
bool WriteCriticalBlock(const void *pBuffer, uint16_t size)
void Log_Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f &point)
void getEulerAngles(int8_t instance, Vector3f &eulers) const
bool getPosD(int8_t instance, float &posD) const
void Log_Write_Proximity(AP_Proximity &proximity)
const struct UnitStructure * unit(uint8_t unit) const
float get_temperature(uint8_t instance) const
void getMagXYZ(int8_t instance, Vector3f &magXYZ) const
void getGyroBias(int8_t instance, Vector3f &gyroBias) const
uint32_t last_message_time_ms(uint8_t instance) const
bool Log_Write_Unit(const struct UnitStructure *s)
void getFlowDebug(int8_t instance, float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
virtual bool get_secondary_quaternion(Quaternion &quat) const
bool get_delta_velocity(uint8_t i, Vector3f &delta_velocity) const
void Log_Write_IMUDT(uint64_t time_us, uint8_t imu_mask)
static void gps_time(uint16_t *time_week, uint32_t *time_week_ms)
void getTimingStatistics(int8_t instance, struct ekf_timing &timing) const
bool Log_Write_Mission_Cmd(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd)
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)
float ground_course(uint8_t instance) const
const Location & location(uint8_t instance) const
uint16_t last_message_delta_time_ms(uint8_t instance) const
bool Log_Write_MavCmd(uint16_t cmd_total, const mavlink_mission_item_t &mav_cmd)
uint16_t cells[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN]
float get_error_rp(void) const
void Log_Write_PID(uint8_t msg_type, const PID_Info &info)
uint8_t activeCores(void) const
int32_t lat
param 3 - Latitude * 10**7
virtual uint16_t power_status_flags(void)
void getQuaternion(int8_t instance, Quaternion &quat) const
AP_MotorsMatrix motors(400)
static AP_InertialSensor ins
const Vector3f & get_accel(uint8_t i) const
float consumed_wh(uint8_t instance) const
consumed_wh - returns total energy drawn since start-up in watt.hours
const Vector3f & get_field(uint8_t i) const
Return the current field as a Vector3f in milligauss.
NavEKF3 & get_NavEKF3(void)
A system for managing and storing variables that are of general interest to the system.
static bool mission_cmd_to_mavlink(const AP_Mission::Mission_Command &cmd, mavlink_mission_item_t &packet)
uint16_t get_gyro_rate_hz(uint8_t instance) const
bool get_delta_angle(uint8_t i, Vector3f &delta_angle) const
void getWind(int8_t instance, Vector3f &wind) const
bool get_closest_object(float &angle_deg, float &distance) const
const Vector3f & velocity(uint8_t instance) const
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 getVelNED(int8_t instance, Vector3f &vel) const
ArduCopter attitude control library.
void Log_Write_Compass(const Compass &compass, uint64_t time_us=0)
float voltage_resting_estimate(uint8_t instance) const
float ground_speed(uint8_t instance) const
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
void Log_Write_IMU_instance(uint64_t time_us, uint8_t imu_instance, enum LogMessages type)
bool use_gyro(uint8_t instance) const
void getInnovations(int8_t index, Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
bool speed_accuracy(uint8_t instance, float &sacc) const
void Log_Write_Rally(const AP_Rally &rally)
Proximity_Status get_status(uint8_t instance) const
bool get_vehicle_position_ned(Vector3f &pos, float &accuracy_estimate) const
void Log_Write_Camera(const AP_AHRS &ahrs, const Location ¤t_loc)
uint32_t get_accel_error_count(uint8_t i) const
void Log_Write_POS(AP_AHRS &ahrs)
void Log_Fill_Format_Units(const struct LogStructure *s, struct log_Format_Units &pkt)
bool getPosD(int8_t instance, float &posD) const
Vector3f rate_bf_targets() const
const Vector3f & get_offsets(uint8_t i) const
uint32_t time_week_ms(uint8_t instance) const
void getEulerAngles(int8_t instance, Vector3f &eulers) const
void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets)
float get_raw_airspeed(uint8_t i) const
virtual float servorail_voltage(void)
float get_corrected_pressure(uint8_t i) const
void getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
int8_t getPrimaryCoreIndex(void) const
virtual enum safety_state safety_switch_state(void)
void Log_Write_Current_instance(uint64_t time_us, uint8_t battery_instance, enum LogMessages type, enum LogMessages celltype)
bool healthy[COMPASS_MAX_INSTANCES]
uint32_t get_accel_clip_count(uint8_t instance) const
float current_amps(uint8_t instance) const
current_amps - returns the instantaneous current draw in amperes
void Log_Write_RCOUT(void)
virtual float get_error_rp(void) const =0
uint16_t get_hdop(uint8_t instance) const
void getFilterFaults(int8_t instance, uint16_t &faults) const
void Log_Write_AHRS2(AP_AHRS &ahrs)
float get_pressure(void) const
bool get_temperature(uint8_t i, float &temperature)
GPS_Status status(uint8_t instance) const
Query GPS status.
void set_mission(const AP_Mission *mission)
const struct MultiplierStructure * multiplier(uint8_t multiplier) const
float get_differential_pressure(uint8_t i) const
#define AIRSPEED_MAX_SENSORS
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
void Log_Write_EntireMission(const AP_Mission &mission)
float get_delta_time() const
AP_BattMonitor & battery()
void Log_Write_GPS(uint8_t instance, uint64_t time_us=0)
void getFilterGpsStatus(int8_t instance, nav_gps_status &faults) const
virtual void set_dataflash_backend(class DataFlash_Backend *backend)
uint16_t get_vdop(uint8_t instance) const
bool get_horizontal_distances(Proximity_Distance_Array &prx_dist_array) const
uint8_t get_count(void) const
void Log_Write_RPM(const AP_RPM &rpm_sensor)
void getFilterFaults(int8_t instance, uint16_t &faults) const
void Log_Write_EKF_Timing(const char *name, uint64_t time_us, const struct ekf_timing &timing)
void Log_Fill_Format(const struct LogStructure *structure, struct log_Format &pkt)
bool get_rally_point_with_index(uint8_t i, RallyLocation &ret) const
float constrain_float(const float amt, const float low, const float high)
float get_altitude(void) const
void Log_Write_Power(void)
int32_t lng
param 4 - Longitude * 10**7
void getMagNED(int8_t instance, Vector3f &magNED) const
uint8_t num_sats(uint8_t instance) const
uint32_t last_update_usec(void) const
float get_delta_angle_dt(uint8_t i) const
NavEKF2 & get_NavEKF2(void)
bool getPosNE(int8_t instance, Vector2f &posNE) const
float cast_to_float(enum ap_var_type type) const
cast a variable to a float given its type
void Log_Write_Origin(uint8_t origin_type, const Location &loc)
void getFilterTimeouts(int8_t instance, uint8_t &timeouts) const
float get_delta_velocity_dt(uint8_t i) const
void getQuaternion(int8_t instance, Quaternion &quat) const
int8_t getPrimaryCoreIndex(void) const
void getVelNED(int8_t instance, Vector3f &vel) const
void Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, const Location ¤t_loc)
bool getOriginLLH(int8_t instance, struct Location &loc) const
uint8_t primary_sensor(void) const
void getTimingStatistics(int8_t instance, struct ekf_timing &timing) const
static uint16_t get_radio_in(const uint8_t chan)
virtual bool get_secondary_attitude(Vector3f &eulers) const
void copy_name_token(const ParamToken &token, char *buffer, size_t bufferSize, bool force_scalar=false) const
float get_ground_temperature(void) const
virtual bool get_secondary_position(struct Location &loc) const
uint8_t get_gyro_count(void) const
const AP_Beacon * get_beacon(void) const
bool get_temperature(float &temperature) const
AP_InertialSensor & ins()
void getStateVariances(int8_t instance, float stateVar[24]) const
bool get_gyro_health(uint8_t instance) const
void Log_Write_RFND(const RangeFinder &rangefinder)
Receiving valid messages and 3D lock.
float getPosDownDerivative(int8_t instance) const
float get_throttle() const
float get_error_yaw(void) const
uint32_t get_gyro_error_count(uint8_t i) const
void getAccelBias(int8_t instance, Vector3f &accelBias) const
void getWind(int8_t instance, Vector3f &wind) const
float getPosDownDerivative(int8_t instance) const
bool Log_Write(uint8_t msg_type, va_list arg_list, bool is_critical=false)
void Log_Write_IMUDT_instance(uint64_t time_us, uint8_t imu_instance, enum LogMessages type)
bool vertical_accuracy(uint8_t instance, float &vacc) const
uint8_t num_instances(void) const
void getOutputTrackingError(int8_t instance, Vector3f &error) const
void Log_Write_Vibration()
bool WriteBlock(const void *pBuffer, uint16_t size)
float voltage(uint8_t instance) const
voltage - returns battery voltage in millivolts
float consumed_mah(uint8_t instance) const
consumed_mah - returns total current drawn since start-up in milliampere.hours
Vector3f get_vibration_levels() const
float get_resistance() const
void getFilterStatus(int8_t instance, nav_filter_status &status) const
void getAccelZBias(int8_t instance, float &zbias) const
bool healthy(uint8_t i) const
#define LOG_PACKET_HEADER_INIT(id)
void getMagXYZ(int8_t instance, Vector3f &magXYZ) const
bool horizontal_accuracy(uint8_t instance, float &hacc) const
void Log_Write_Baro_instance(uint64_t time_us, uint8_t baro_instance, enum LogMessages type)
uint16_t cell_voltages[10]
virtual void get_relative_position_D_home(float &posD) const =0
virtual bool get_relative_position_D_origin(float &posD) const
uint32_t get_last_update(void) const
void Log_Write_RCIN(void)
void Log_Write_Baro(uint64_t time_us=0)
bool getRangeBeaconDebug(int8_t instance, uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow) const
bool Log_Write_Multiplier(const struct MultiplierStructure *s)
uint8_t get_accel_count(void) const
uint8_t getActiveMag(int8_t instance) const
const cells & get_cell_voltages() const
bool get_accel_health(uint8_t instance) const
bool have_vertical_velocity(uint8_t instance) const
uint16_t get_accel_rate_hz(uint8_t instance) const
bool Log_Write_Mode(uint8_t mode, uint8_t reason=0)
AP_HAL::AnalogIn * analogin