There was a time window where if a task with higher priority than the main
logger thread would busy-loop, it would block both logging threads and the
watchdog would not trigger if the writer was in idle state.
This can happen for fast SD card writes.
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.
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 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>
This adds a nuttx userspace interface for hrt driver, communicating with
the actual px4 hrt driver via BOARDCTL IOCTLs
This is be used when running PX4 in NuttX protected or kernel builds
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Before, adding the pusher to the same matrix as the upwards motors affected
the scaling for the upwards motors, resulting in values not equal to -1
anymore.
Move some logic from Subscriber into uORBManager. This reduces calls from the
modules to the uORB manager, improving performance in protected build.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
- this is a more conservative default if a vehicle isn't set (no land detector running)
- handled horizontal preflight failures in commander when disarmed
rather than overloading xy_valid and v_xy_valid flags
- ekf2 no longer depend on arming or standby status
- ekf2: expose dead reckoning as control status flags
- commander:
- add GPS validity check
- in AUTO MISSION if dependent on GPS then a loss of GPS will
- Also use the delayed current data instead of newest that might not be
available (gps buffer is sometimes empty if the dt between samples is
larger than the delayed horizon).
- Separate "baro fault" from "baro intermittent": intermittent is a
temporary failure and should prevent from switching to baro right now,
but "fault" means that it should never be used anymore
- In case of height timeout, check for metrics but not for consistency
as the filter is likely to have diverged already.
* Adds Timer15 to stm32_common, if the timer base is defined
* Adds Timer15 logic for DMA and AltFunc config on stm32h7 boards
* Adds TIM15 BDTR->MOE support in stm32_common timer init
* Adds support for TIM15 pwm channels on Matek H743 Slim
If the hardware support RESET lockout that has nArmed ANDed with VBUS
vbus_sense may drop during a param save which uses
BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE to prevent external resets
while writing the params. If we are not armed and nARMRED is low
we are in such a lock out so ignore changes on VBUS_SENSE during this
time.
Once we have valid input we should use that and not overwrite our
update_result with the result from other inputs, otherwise the
automatic selection does not actually work.
This behavior means that only the first update will be used if there are
several sources updating in the same cycle.
It was a mistake to mix these two together, it is simpler to implement the boardctl interface
for the protected build, if the boardctl ioctls are different
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
This adds an ioctl interface for NuttX protected build, allowing
system calls from user space to kernel for uORB, HRT and crypto
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Weak authority on a axis is currently defined as: none of the actuators have an
effectivness on this particular axis larger than 0.05.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
* Navigator: enable DO_CHANGE_SPEED for outside of mission
- update _mission_cruising_speed_mc/_fw also if DO_CHANGE_SPEED command
is received outside of mission (e.g. while Loitering doing an Orbit)
- if vehicle is in AUTO_LOITER when receiving the change speed, then immediately
apply it by doing a reposition without updating any other field than cruising_speed
and cruising_throttle
-when RTL is activated reset the cruising speed and throttle
* Navigator: reset cruise speed and throttle to default when VTOL-transitioning
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
-pass flag EffectivenessUpdateReason into effectiveness, indicating if there was an external
update or not. Reasons for external updates are:
-config changes (parameter)
-motor failure detected or certain redundant motors are switched off to save energy
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
When building uORB for NuttX flat build, or for some other target, everything
works as before.
When building uORB for NuttX protected or kernel build, this does the following:
- The kernel side uORB library reigsters a boardctl handler for calls from userspace
and services the boardctl_ioctls by calling the actual uORB functions
- For user mode binaries, the uORBManager acts as a proxy, making boardctl_ioctl calls to the
kernel side
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
This fixes the issue when changing the altitude during a goto for
example, where the vehicle was going backwards and upwards to reach the
closest point to the line. Now the vehicle simply goes towards the
target waypoint.
- RC_PORT_CONFIG is disabled by default if the board doesn't have
CONFIG_BOARD_SERIAL_RC set
- allows user facing custom RC configuration that overrides board
defaults
This is the case for boards with digital readout, like v5x, but still
enable the battery_status module for external analog driver options.
An alternative would be to not run battery_status depending on config.
This saves a lot of flash space, in case functions from libtomcrypt
are not used (currently only RSA related).
When RSA is not used, the linker can now drop all libtomcrypt related things.
This is especially relevant for bootloaders using the SW crypto.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
* Make board_id compatible with ardupilot
* Initialize outputs for CAM1/CAM2 and Vsw pad
* Correct board type 1013 in bootloader to match AP
* Change usb vendor string to "Matek"
* Change cdcacm pid to 1013
* Comment out FLASH_BASED_PARAMS because of #15331
This is a bigger refactor of vmount to clean it up and plug some holes
in functionality.
The changes include:
- Fixing/simplifying the test command.
- Changing the dependencies of the input and output classes to just the
parameter list.
- Adding a separate topic to publish gimbal v1 commands to avoid
polluting the vehicle_command topic.
- Removing outdated comments and author lists.
- Extracting the gimbal v2 "in control" notion outside into control_data
rather than only the v2 input.
If we receive gimbal_device_attitude_status by mavlink we should not
re-send it as we are already supposed to be forwarding mavlink traffic
from the gimbal to the ground station.
For fixedwings, the orbit status was publishing zero radius when a goto waypoint was being passed.
This commit corrects this by passing the default loiter radius as the guidance logic was using
This addes the command serial_passthru which will pass data from one
device to another. This can be used to use u-center connected to USB
with a GPS on a serial port.
Usage: serial_passthru [arguments...]
-e <val> External device path
values: <file:dev>
-d <val> Internal device path
values: <file:dev>
[-b <val>] Baudrate
default: 115200
[-t] Track the External devices baudrate on internal device
With the -t option baudrate changes made on the PC connected to the USB
will be set to the intrenal device.
SD is on SPI3 - correct pin mapping
Fix DMA Mapping for all SPI and RX DMA on U[S]ART RX
Fix Memory MAP SRAM size
Removed unused GPIO
Used proper I2C definitions
Ensure Watchdog is configured for debugging
Fixed FLASH param definitions
Removed unedded SPI init
matek_gnss-m9n-f4:Correct Board ID and Size
Build order SJF
Added Support for F40x
- move vehicle at reset detection ekf2 -> land_detector
- ekf_unit: reduce init period
- Fake fusion is when at rest is quite strong and makes the variance reduce rapidly. Reduce the amount of time we wait before checking if the variances are still large enough.
- ekf_unit: reduce minimum vel/pos variance required after init
- Fake pos fusion has a low observation noise, making the vel/pos variances reduce quickly.
Co-authored-by:: bresch <brescianimathieu@gmail.com>
The stackcheck build flash space overflows after adding hygrometers.
Also follow the naming convention of other similar config flags, and rename the
config.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Split the px4_layer into user and kernel space libraries. Add some stubs for
user-space (e.g. version) where an interface to the kernel needs to be added
Use posix-versions for cpuload.cpp and print_load.cpp for userspace; these link to nuttx internals. This functinality could be built on top of posix (e.g. procfs) interfaces
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
- remove class _mag_sample_delayed
- update mag fusion call graph to use mag sample delayed functionally
- Ekf::resetMagHeading()
- use low pass mag directly, but check if valid (magnitude)
- MAG_FUSE_TYPE_INDOOR treat like auto if heading required
If the board supports encrypting logfiles, but the parameter SDCARD_ALGORITHM is set to NONE,
the log should be written to the sdcard in plaintext format. This fixes a bug which caused
logger to hang in mutex instead.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
- Don't link to px4_layer
- Don't link to flashparams; flashparams would work only in kernel side
- Add missing link to px4_platform
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
This goes the other way around; arch_io_pins is using the pin
definitions from drivers_board, so the drivers_board needs to be linked
into arch_io_pins
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Since uORB is split into kernel and userspace parts, it is no longer possible to just
link uORB into px4_platform, which is used in both kernel and user side.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Define __KERNEL__ macro during compilation and place the module in separate library
Remove default library linking to m or libc on NuttX. Add these in platform layer instead, since
they are different on kernel and user side
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
The needed version specific things come from px4 layer. Since version
is used both in kernel an user sides in protected build, it can't directly
link to drivers_board
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
For NuttX protected or kernel build, the prebuilds can't contain libraries which are
different for kernel and user-space in protected/kerenl builds
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
- introduces new parameter EKF2_PREDICT_US to configure the filter
update period in microseconds
- actual filter update period will be an integer multiple of IMU
This is done by inheriting from FlightTaskManualAltitudeSmoothVel again.
The altitude change by command is taken care of by switching
to the apporach when the altitude difference is big enough and
switching back once the altitude is close enough.
The altitude of the command is not perfectly reached but this can
only be done smoothly when the Orbit has full control over the
altitude smoothing. The independent altitude smoothing is not kept
because it was lacking stick handling like altitude lock and smooth
transitions when opening and closing the vertical position loop.
I think they were forgotten and it leads to side effects:
- The acceleration feed-forward does not get executed
- The acceleration setpoint is NAN when initializing the altitude
smoothing when arriving at the circle
'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
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)
Some files were not shown because too many files have changed in this diff
Show More
Reference in New Issue
Block a user
Blocking a user prevents them from interacting with repositories, such as opening or commenting on pull requests or issues. Learn more about blocking a user.