- on common IMUs like the mpu6000, mpu9250, icm20602, etc each FIFO
sample is only 12 bytes so this is still more than large enough for the
worst case transfer
- free memory is getting tight on these older boards (depending on
configuratoin) and the pixhawk 2 cube still has 2 other superior IMUs, so this is just
dropping dead weight
We use lockdown to prevent outputs like motors and servos from being
active in HITL simulation. This means that we can't treat the lockdown
flag as a flight_terminated, otherwise we can't arm in HITL at all.
Without this, uavcan creates MixingOutput classes which then create
empty actuator_outputs publications. This then prevents the motor
output in HITL to be forwarded to the simulator via mavlink.
This fixes an invalid memory access when exiting the module:
exit_and_cleanup destroys the object, but lock_guard is destructed after
and accesses the lock.
- this allows jumping straight to a non-SBUS RC protocol
- increased the scan time per protocol 300->500 ms, which the newer DSM parser seems to need in some cases.
- only set RC_INPUT_PROTO if we've had a successful RC lock for > 3 seconds
Normally _should_run for mission is only ever true if _should_run for the
normal log is. There are exceptions though:
- the log buffer fails to allocate
- there was a write failure (e.g. due to SD card removal)
In that situation, the writer would not wait anymore but busy-loop.
If both local position and altitude were not valid, then both RC loss and
datalink loss would not trigger any failsafe at all, independently from
the configured action.
Calculating K(HP) takes less operations than (KH)P because K and H are
vectors.
Without considering the sparsity optimization:
- KH (24*24 operations) is then a 24x24 matrix an it takes
24^3 operations to multiply it with P. Total: 14400 op
- HP (24*(24+24-1) operations) is a row vector
and it takes 24 operations to left-multiply it by K. Total:1152 op
when the vertical pos or vel innov ratio is above the threshold, the
other one needs to be significant too and not just positive to trigger
the failure
- on some H7 boards (cuav x7pro tested) there's an occasional hard fault when starting the mavlink shell that is no longer reproducible with the slightly expanded locking
- this is likely just changing the timing (holding the sched lock for longer), but this should be harmless for now until we can identify the root cause
Weather vane should only set a yawrate setpoint, but no yaw setpoint.
Setting it to NAN when WV is active makes sure that whatever _yaw_setpoint
is set previously (e.g. through Waypoint) is not used.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
- set local home using global pos and global home
- set local home using GNSS pos and global home
- set global home using global ref of local frame and local home
This is to make clear that the relevant part of the home position
message for navigator is the global one. Local home position isn't
required as everything is done in global coordinates.
The specific home_alt_valid is used when lat/lon are not used
- always try to set local or global home position when possible
- set global home with GNSS position if global pos from EKF isn't
available
- reset home when significantly moved from home before takeoff (checking
lpos or gpos or GNSS)
- reset home on takeoff transition
- reset home on mavlink arm command
- remove "home required accuracy" parameters, rely on validity flags
- fixes the deadlock in px4io ioctl mixer reset
- px4io Run() locks (CDev semaphore)
- mixer load goes through px4io ioctl MIXERIOCRESET which calls MixingOutput::resetMixerThreadSafe()
- MixingOutput::resetMixerThreadSafe() stores a Command::Type::resetMixer command in an atomic variable, schedules a work queue cycle, then sleep spins until the command is cleared
- the execution of the cycle eventually calls back into PX4IO::updateOutputs(), which tries to lock (and waits forever)
- most px4_io-v2 boards have a blue LED that breathes for status
- the pixhawk 2.1 (hex) re-used this blue LED for as an IMU heater (active low), but kept the same board id (so we have to detect at runtime)
- the new cubepilot boards (yellow, orange) inverted the polarity of this heater pin
- untangle the mess slightly so that things we know statically (eg cubepilot cubeorange LEDs and heater polarity) are handled at build time.
To pass from invalid to valid:
- time hysteresis
- some vertical velocity
- test ratio < 1
- low-passed signed test ratio < 1
To pass from valid to invalid:
- low-passed signed test ratio >= 1
At each new valid range measurement, the time derivative of the distance
to the ground is computed and compared with the estimated velocity.
The average of a normalized innovation squared statistic check is used
to detect a bias in the derivative of distance measurement,
indicating that the distance measurements are kinematically inconsistent
with the filter.
- mavlink in PX4/Firmware (a1530591764f0c694560e4bb6ae41c15d3e35c9b): 0133e5db7f
- mavlink current upstream: 56a5110d38
- Changes: 0133e5db7f...56a5110d38
56a5110d 2022-04-09 Tom Pittenger - Add radius to DO_REPOSITION (#1825)
3b5959bd 2022-04-07 Thomas Debrunner - Option to not reset non-configurable params in preflight storage (#1826)
For many VTOLs/fixed-wing drones a 50m loiter radius is too tight, and
going to 80m is a better and safer default.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
- In this case, no action is configured for datalink lost. Action is configured for RC lost.
- In case of no data link and no rc failsafe is enabled but reporting a "no_datalink" reason but "no_rc_and_no_datalink" seems more explicit.
- previously an invalid decode would continue to be transferred to the FMU (at 50 Hz) and published to the rest of the system as successfully decoded new RC data
- by only publishing new successful decodes we can more effectively discard invalid data in downstream consumers
PX4 supports int32 parameter types by interpreting the 32 bits in
the float field as an int32 field. To signal this behaviour, it should
set the bit which is described as PARAM_ENCODE_BYTEWISE.
PX4 had always handled parameters this way but never actually sent the
capability (which back then was called PARAM_UNION), however, it should
have. This came up recently in the MAVLink devcall when these flags were
discussed. The takeaway was to remove the flags to make it clearer and
to make sure the projects (like PX4) send them out correctly.
mathlib: add second order reference model filter with optional rate feedback (#19246)
Reference models can be used as filters which exhibit a particular, chosen (reference) dynamic behavior. This PR implements a simple second order transfer function which can be used as such a reference model, additionally with rate feedback. The system is parameterized by explicitly set natural frequency and damping ratio. Another nice externality is that the output state and rate are kinematically consistent. Forward-euler and bilinear transform discretizations for the state space integration step are available.
- introduce BAT_AVRG_CURRENT param that is used for init of average current estimate
- increase filtering of average current estimation
- only update average current filter when armed
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This fixes unspecified behaviour due to evaluation order of args.
It's up to the compiler whether next_number() or next_dots() is executed
first which means that the behaviour is not properly specified.
- sensor_baro.msg use SI (pressure in Pascals)
- update all barometer drivers to publish directly and remove PX4Barometer helper
- introduce baro cal (offset) mainly as a mechanism to adjust
relative priority
- commander: add simple baro cal that sets baro offsets to align with
GPS altitude (if available)
- create new sensors_status.msg to generalize sensor reporting
- things like arming requests can be dependent on current nav state
that might requested by a previous command, but the state machine
transition will only happen after command processing
New parameter for actions after a quadchute (COM_QC_ACT)
Co-authored-by: Jonas <jonas.perolini@rigi.tech>
Co-authored-by: Matthias Grob <maetugr@gmail.com>
- new static notch filter configured via IMU_GYRO_NF1_FRQ and IMU_GYRO_NF1_BW
- existing notch parameters IMU_GYRO_NF_FREQ and IMU_GYRO_NF_BW become
IMU_GYRO_NF0_FRQ and IMU_GYRO_NF0_BW
- when estimating the peak frequency the magnitude of side buckets will
be factored in, so it doesn't make sense to potentially treat them as
separatey detected peaks
- set MAV_TYPE as a parameter default per vehicle type, or airframe if necessary
- cleanup MAV_TYPE param metadata and commander helper to only include
what's currently used in PX4
It accesses kernel internal structures directly; this needs to be
worked out with some proper userspace-kernel interface
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
This is needed for DMA capable memory for fat also in the user side;
the file system doesn't seem to work reliably without.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
For protected/kernel builds the cxx static initializations
needs to be done also in kernel side, since px4 creates
c++ objects in kernel
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Implement an interface for protected build to access parameters.
The implementation only does IOCTL calls to the kernel, where the parameters
live.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Put all functions which are commont to flat build and protected kernel and
userspace to an own source file
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
- the estimated mag bias was requiring > 30 seconds of continuous 3d
mag fusion to be reported stable (and saved back to mag cal), this
restores the original intent requiring 30 seconds of accumulated valid
3d mag fusion
Need to log both, because on some systems the
information will come in directly as a
landing_target_pose message, and on others
it's coming in as irlock_report and then filtered
in PX4 to produce the landing_target_pose message.
- this was an experiment to casually monitor sensor offsets relative to temperature, but now that all calibration offsets can be adjusted post-flight the stored temperature can be misleading
- deleting to save a little bit of flash (and storing the temperature wasn't useful)
Otherwise the setpoint from weather vane is constantly overwritten by it,
even if the yaw stick is not moved.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
'hgt_sensor_status':['Pass','Height sensor check summary. This sensor data can be sourced from either Baro, GPS, range fidner or external vision system. A Fail result indicates a significant error that caused a significant reduction in vehicle navigation performance was detected. A Warning result indicates that error levels higher than normal were detected but these errors did not significantly impact navigation performance. A Pass result indicates that no amonalies were detected and no further investigation is required'],
'hgt_test_max':[float('NaN'),'The maximum in-flight value of the height sensor innovation consistency test ratio.'],
'hgt_test_mean':[float('NaN'),'The mean in-flight value of the height sensor innovation consistency test ratio.'],
'imu_coning_mean':[float('NaN'),'Mean in-flight value of the IMU delta angle coning vibration metric (rad)'],
'imu_coning_peak':[float('NaN'),'Peak in-flight value of the IMU delta angle coning vibration metric (rad)'],
'imu_hfdang_mean':[float('NaN'),'Mean in-flight value of the IMU delta angle high frequency vibration metric (rad)'],
'imu_hfdang_peak':[float('NaN'),'Peak in-flight value of the IMU delta angle high frequency vibration metric (rad)'],
'imu_hfdvel_mean':[float('NaN'),'Mean in-flight value of the IMU delta velocity high frequency vibration metric (m/s)'],
'imu_hfdvel_peak':[float('NaN'),'Peak in-flight value of the IMU delta velocity high frequency vibration metric (m/s)'],
'imu_coning_mean':[float('NaN'),'Mean in-flight value of the IMU delta angle coning vibration metric (rad^2)'],
'imu_coning_peak':[float('NaN'),'Peak in-flight value of the IMU delta angle coning vibration metric (rad^2)'],
'imu_hfgyro_mean':[float('NaN'),'Mean in-flight value of the IMU gyro high frequency vibration metric (rad/s)'],
'imu_hfgyro_peak':[float('NaN'),'Peak in-flight value of the IMU gyro high frequency vibration metric (rad/s)'],
'imu_hfaccel_mean':[float('NaN'),'Mean in-flight value of the IMU accel high frequency vibration metric (m/s/s)'],
'imu_hfaccel_peak':[float('NaN'),'Peak in-flight value of the IMU accel high frequency vibration metric (m/s/s)'],
'imu_sensor_status':['Pass','IMU sensor check summary. A Fail result indicates a significant error that caused a significant reduction in vehicle navigation performance was detected. A Warning result indicates that error levels higher than normal were detected but these errors did not significantly impact navigation performance. A Pass result indicates that no amonalies were detected and no further investigation is required'],
'in_air_transition_time':[float('NaN'),'The time in seconds measured from startup that the EKF transtioned into in-air mode. Set to a nan if a transition event is not detected.'],
'mag_percentage_amber':[float('NaN'),'The percentage of in-flight consolidated magnetic field sensor innovation consistency test values > 0.5.'],
@ -49,12 +49,12 @@ hagl_test_mean, The mean in-flight value of the height above ground sensor innov
@@ -49,12 +49,12 @@ hagl_test_mean, The mean in-flight value of the height above ground sensor innov
ofx_fail_percentage, The percentage of in-flight recorded failure events for the optical flow sensor X-axis innovation consistency test.
ofy_fail_percentage, The percentage of in-flight recorded failure events for the optical flow sensor Y-axis innovation consistency test.
filter_faults_max, Largest recorded value of the filter internal fault bitmask. Should always be zero.
imu_coning_peak, Peak in-flight value of the IMU delta angle coning vibration metric (rad)
imu_coning_mean, Mean in-flight value of the IMU delta angle coning vibration metric (rad)
imu_hfdang_peak, Peak in-flight value of the IMU delta angle high frequency vibration metric (rad)
imu_hfdang_mean, Mean in-flight value of the IMU delta angle high frequency vibration metric (rad)
imu_hfdvel_peak, Peak in-flight value of the IMU delta velocity high frequency vibration metric (m/s)
imu_hfdvel_mean, Mean in-flight value of the IMU delta velocity high frequency vibration metric (m/s)
imu_coning_peak, Peak in-flight value of the IMU delta angle coning vibration metric (rad^2)
imu_coning_mean, Mean in-flight value of the IMU delta angle coning vibration metric (rad^2)
imu_hfgyro_peak, Peak in-flight value of the IMU accel high frequency vibration metric (rad/s)
imu_hfgyro_mean, Mean in-flight value of the IMU accel high frequency vibration metric (rad/s)
imu_hfaccel_peak, Peak in-flight value of the IMU accel high frequency vibration metric (m/s/s)
imu_hfaccel_mean, Mean in-flight value of the IMU accel high frequency vibration metric (m/s/s)
output_obs_ang_err_median, Median in-flight value of the output observer angular error (rad)
output_obs_vel_err_median, Median in-flight value of the output observer velocity error (m/s)
output_obs_pos_err_median, Median in-flight value of the output observer position error (m)
1
check_id
check_description
49
ofx_fail_percentage
The percentage of in-flight recorded failure events for the optical flow sensor X-axis innovation consistency test.
50
ofy_fail_percentage
The percentage of in-flight recorded failure events for the optical flow sensor Y-axis innovation consistency test.
51
filter_faults_max
Largest recorded value of the filter internal fault bitmask. Should always be zero.
52
imu_coning_peak
Peak in-flight value of the IMU delta angle coning vibration metric (rad)Peak in-flight value of the IMU delta angle coning vibration metric (rad^2)
53
imu_coning_mean
Mean in-flight value of the IMU delta angle coning vibration metric (rad)Mean in-flight value of the IMU delta angle coning vibration metric (rad^2)
54
imu_hfdang_peakimu_hfgyro_peak
Peak in-flight value of the IMU delta angle high frequency vibration metric (rad)Peak in-flight value of the IMU accel high frequency vibration metric (rad/s)
55
imu_hfdang_meanimu_hfgyro_mean
Mean in-flight value of the IMU delta angle high frequency vibration metric (rad)Mean in-flight value of the IMU accel high frequency vibration metric (rad/s)
56
imu_hfdvel_peakimu_hfaccel_peak
Peak in-flight value of the IMU delta velocity high frequency vibration metric (m/s)Peak in-flight value of the IMU accel high frequency vibration metric (m/s/s)
57
imu_hfdvel_meanimu_hfaccel_mean
Mean in-flight value of the IMU delta velocity high frequency vibration metric (m/s)Mean in-flight value of the IMU accel high frequency vibration metric (m/s/s)
58
output_obs_ang_err_median
Median in-flight value of the output observer angular error (rad)
59
output_obs_vel_err_median
Median in-flight value of the output observer velocity error (m/s)
60
output_obs_pos_err_median
Median in-flight value of the output observer position error (m)