* sih: Move sih out of work queue
This reverts commit bb7dd0cf00.
* sih-sim: Enable sih in sitl, together with lockstep
* sih-sim: new files for sih: quadx and airplane
* sih: Added tailsitter for sih-sitl simulation
* sitl_target: Added seperate target loop for sih
* jmavsim_run: Allow jmavsim to run in UDP mode
* lockstep: Post semaphore on last lockstep component removed
* sih-sim: Added display for effectively achieved speed
* sih: increase stack size
* sih-sim: Improved sleep time computation, fixes bug of running too fast
* sitl_target: place omnicopter in alphabethic order
Co-authored-by: romain-chiap <romain.chiap@gmail.com>
Co-authored-by: Matthias Grob <maetugr@gmail.com>
- documentation of units, params, returns, and descriptions for variables and methods
- rename ambiguous or erroneous state variables
- remove unused or unecessary input arguments to functions
- remove ugly header white space
The safetyButtonHandler() reports that the safety statatus
changed on the first loop iteration when safety is disabled which makes
sense to inform the system that safety is off but the tune for the user
should not be played because it interrupts the startup tune.
They cause problems with building px4_msgs in ROS2 Humble Hawksbill and removing them fixes the issue.
Co-authored-by: Agata Barcis <agata.barcis@tii.ae>
This corrects the board definition to use the proper polarity
for the brick power valid signal, thus allowing the board to
detect the battery and monitor it properly.
internal PX4IO safety_off state is removed and replaced with a normal safety button event. From this 'commit' commander is taking care of the PX4IO safety.
- 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
H7 Only supports 2 not 3 CAN interfaces.
CanInitHelper passes in in the run time configuration of
the number of interfaces. The code was ignoring these!
This type (23) doesn't specify a motor number, so it can't be properly handled.
There are duo (19) and quad (20) tailsitter types that still work in simulation.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Based on feedback that very often the battery is used down too low.
I observed this happens consistently when the cell voltage is properly
load compensated. The default load compensation before #19429 was very
inaccurate and resulted in unpredictable estimate.
After that if there is a usable current measurement and the battery is
within expected tolerances of the default internal resistance the
compensation is pretty good and 3.5V is too low for an empty compensated
cell voltage. That was seen in various logs where the compensated
cell voltage was already dropping fast after 3.6V.
In case the voltage is not load compensated the vehicle estimates the
state of charge a bit too low which is safer than to high
especially for a default configuration.
internal PX4IO safety_off state is removed and replaced with a normal safety button event. From this 'commit' commander is taking care of the PX4IO safety.
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.
The baro observation noise parameter is often over-estimated in order as
a measure to mitigate temporary offsets in the readings due to wind
gusts or poor pressure compensation tuning. The side effect is that the
innovation sequence monitoring based on normalized innovation struggles
to detect an offset in the state because the innovation isn't
statistically significant.
To counter this issue, a simpler check is added to trigger the process
noise boost when the innovation has the same sign for a long period of
time.
1. Change the paragraph headings to proper Markdown headings (easier to
link / structure the Markdown)
2. Move PULL_REQUEST_TEMPLATE into .github folder
3. Change description in Issue template and remove outdated DevGuide
Repository information
4. Add a bug emoji to bug report isue template
5. Support automatically adding labels 'bug-report' and
'feature-request' to easily sort / filter appropriate issues in Github
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.
I got multiple times the feedback now that a consistent delay
is helpful and makes sense but the default delay
is too long
for low battery action where you're trying to come back in time
and possibly the emergency reaction kicks in while the critical action
is executing which leads to a longer accumulated delay.
To return Exponential Values, which is helpful for reducing the
sensitivity of the stick around the centered value (0), since it's
exponential curve.
Useful for user adjustment implementations, where accidentally touching the stick
wouldn't have so much effect when using the Exponential value, compared
to using the raw position value.
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.
- limit to handling only 1 motor failure
- Log which motor failures are handled
- Remove motor from effectiveness matrix without
recomputing the scale / normalization
- 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.
This replaces the propeller_torque_disabled flag to disable yaw by differential thrust
for tiltrotor and tailsitter VTOLs, as propeller_torque_disabled is not enough to set
effectiveness of an acutator in the yaw axis to 0 in case it's tilted.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Special case tiltrotor: instead of passing a 3D thrust vector (that would mostly have a x-component in FW, and z in
MC), pass the vector magnitude as z-component, plus the collective tilt. Passing 3D thrust plus tilt is not feasible as they
can't be allocated independently, and with the current controller it's not possible to have collective tilt calculated
by the allocator directly.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
The flight termination action on geofence violation is described as only trigger, when the corresponding circuit breaker is not disabled. However, the description of the circuit breaker states, that the geofence action is not depedning on this circuit breaker. The implementation follows the description of the circuit breaker. Hence the GF_ACTION description is adapted.
- add logic for detecting high wind speed in Commander,
and handle it toghether with wind speed warning
- trigger and enforce RTL if COM_WIND_MAX is breached
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Adds COM_FLT_TIME_MAX param and logic in Commander to enforce RTL when
flight time is above this value. User can only override to LAND mode,
but not proceed flight beyond that.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
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
This is a combination of the originally introduced delay:
06c10f61c1
then the emergency failsafe being changed to not just land,
position control being rescheduled to not overwrite every setpoint in:
e502214429576ce68ac3fee9d2db19112f4604b9
and it being fixed by overwriting the setpoint but not removing
the long obsolete hystersis here:
114e85d260
- remove separate flaperon controls input to mixer instead enable spoiler support
- add slew rate limiting on both flap and spoiler controls
- add spoiler configuration for Landing and Descend
- add trimming from spoiler deflection
- FW Attitude control: remove FW_FLAPS_SCL param -->
The flap settings for takeoff and landing are now specified relative to full range.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
[4] is reserved for Flaps, so also having the tilt on it was preventing us from
using flaps on tiltrotors, and other ripple effects.
By using [8] the tilt is separated from all other channels - it requires to increase the size of
actuator_controls by 1 to 9.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
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
about: See https://github.com/PX4/Devguide for documentation issues
about: See https://github.com/PX4/px4_user_guide for documentation issues
---
PX4 has dedicated repositories for developer documentation (https://github.com/PX4/Devguide) and user documentation (https://github.com/PX4/px4_user_guide).
## Attention! Please read the note below
**Please submit the documentation issue to the [User Guide](https://github.com/PX4/px4_user_guide) repository.**
Please use [PX4 Discuss](http://discuss.px4.io/) or [Slack](http://slack.px4.io/) to align on pull requests if necessary. You can then open draft pull requests to get early feedback.
**Describe problem solved by this pull request**
A clear and concise description of the problem this proposed change will solve.
## Describe problem solved by this pull request
A clear and concise description of the problem this proposed change will solve. Or, what it will improve.
E.g. For this use case I ran into...
**Describe your solution**
## Describe your solution
A clear and concise description of what you have implemented.
**Describe possible alternatives**
## Describe possible alternatives
A clear and concise description of alternative solutions or features you've considered.
**Test data / coverage**
## Test data / coverage
How was it tested? What cases were covered? Logs uploaded to https://review.px4.io/ and screenshots of the important plot parts.
'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.