- control allocation module with multirotor, VTOL standard, and tiltrotor support
- angular_velocity_controller
- See https://github.com/PX4/PX4-Autopilot/pull/13351 for details
Co-authored-by: Silvan Fuhrer <silvan@auterion.com>
Co-authored-by: Roman Bapst <bapstroman@gmail.com>
- commander preflightcheck use estimator_sensor_bias message instead of EKF state index magic number
- ekf2 publish estimated bias limits in estimator_sensor_bias
- preflightcheck only error if bias estimate exceeds half of configured limit (delete COM_ARM_EKF_AB and COM_ARM_EKF_GB parameters)
- handle saving the mag bias per sensor (across all estimator instances using that mag) in sensors/vehicle_magnetometer
- this is now saving back to the actual mag calibration CAL_MAGn_OFF{X,Y,Z}
- ekf2 reset mag mag bias on any magnetometer or calibration change
- use Kalman filter scheme to update stored mag bias parameters using all available bias estimates for that sensor
Co-authored-by: Paul Riseborough <gncsolns@gmail.com>
- log all estimator (ekf2) flags as separate booleans in a new dedicated low rate message (only publishes at 1 Hz or immediately on any change)
- this is a bit verbose, but it avoids the duplicate bit definitions we currently have across PX4 msgs, ecl analysis script, flight review, and many other custom tools and it's much easier for casual log review in FlightPlot, PlotJuggler, csv, etc
- for compatibility I've left estimator_status filter_fault_flags, innovation_check_flags, and solution_status_flags in place, but they can gradually be removed as tooling is updated
Co-authored-by: Mathieu Bresciani <brescianimathieu@gmail.com>
Changed all 'NED' references to 'FRD'. Also cleaned up mixing of m/s/s and m/s^2 to use the latter. Corrected m/s/s to Pascals. Plus minor typos. Also made some minor cosmetic clean ups.
Co-authored-by: Robin <robin@Robins-MacBook-Pro-Work.local>
Co-authored-by: Mathieu Bresciani <brescianimathieu@gmail.com>
- split out switches from manual_control_setpoint into new message manual_control_switches
- manual_control_switches published at minimal rate (~ 1 Hz) or immediately on change
- simple switch debounce in rc_update (2 consecutive identical decodes required)
- manual_control_switches logged at full rate rather than sampled at (5-10% of messages logged)
- manual_control_setpoint publish at minimal rate unless changing
- commander handle landing gear switch for manual modes
- processing of mode_slot and mode_switch is now split so we only do one or the other (not both)
- a future step will be to finally drop mode_switch and accompanying switches entirely
Co-authored-by: Matthias Grob <maetugr@gmail.com>
- saves a small amount of work for the ekf2 selector in multi-EKF mode (visual_odometry_aligned now ignored)
- helps to distinguish the origin/purpose from vehicle_odometry and vehicle_visual_odometry
- ekf2 can now run in multi-instance mode (currently up to 9 instances)
- in multi mode all estimates are published to alternate topics (eg estimator_attitude instead of vehicle_attitude)
- new ekf2 selector runs in multi-instance mode to monitor and compare all instances, selecting a primary (eg N x estimator_attitude => vehicle_attitude)
- sensors module accel & gyro inconsistency checks are now relative to the mean of all instances, rather than the current primary (when active ekf2 selector is responsible for choosing primary accel & gyro)
- existing consumers of estimator_status must check estimator_selector_status to select current primary instance status
- ekf2 single instance mode is still fully supported and the default
Co-authored-by: Paul Riseborough <gncsolns@gmail.com>
- add new parameter `IMU_GYRO_FFT_EN` to start
- add 75% overlap in buffer to increase FFT update rate
- space out FFT calls (no more than 1 per cycle)
- increase `IMU_GYRO_FFT_MIN` default
- decrease main stack usage
- mavlink messages DEBUG/DEBUG_FLOAT_ARRAY/DEBUG_VECT/NAMED_VALUE_FLOAT move to separate stream headers and don't include if CONSTRAINED_FLASH
- mavlink receiver DEBUG/DEBUG_FLOAT_ARRAY/DEBUG_VECT/NAMED_VALUE_FLOAT handling excluded if CONSTRAINED_FLASH
- msg: skip debug_array.msg, debug_key_value.msg, debug_value.msg, debug_vect.msg if CONSTRAINED_FLASH
- drivers/tone_alarm: move to ModuleBase and purge CDev (/dev/tone_alarm0)
- drivers/tone_alarm: only run on tune_control publication (or scheduled note) rather than continuously
- drivers/tone_alarm: use HRT to schedule tone stop (prevents potential disruption)
- msg/tune_control: add tune_id numbering
- systemcmds/tune_control: add "error" special case tune_id
- move all tune_control publication to new uORB::PublicationQueued<>
- start tone_alarm immediately after board defaults are loaded to fix potential startup issues
- for SITL (or other boards with no TONE output) print common messages (startup, error, etc)
- new sensors work item that subscribes to N x sensor_gps and publishes vehicle_gps_position
- blending is now configurable with SENS_GPS_MASK and SENS_GPS_TAU
Co-authored-by: Jacob Crabill <jacob@volans-i.com>
Co-authored-by: Jacob Dahl <dahl.jakejacob@gmail.com>
- vehicle_imu/vehicle_magnetometer add monotonically increasing `calibration_count` field so that downstream subscribers are aware of calibration changes
- inconsistency checks now run continuously instead of only preflight
- keep inconsistencies for all sensors
- add per sensor data validator state as overall health flag
- use proper Mavlink MAV_CMD_FIXED_MAG_CAL_YAW command for initiating magnetometer quick cal
- MAV_CMD_FIXED_MAG_CAL_YAW allows specifying the yaw and optionally latitude and longitude if the vehicle doesn't have GPS
- added support for BQ40Z80 based battery
- added performance counter for interface errors
- added SMART_BATTERY_INFO mavlink message
- general code cleanups and optimization
- fixed: void flooding the log in case of interface error
- fixed: using _batt_startup_capacity instead of _batt_capacity for discharged_mah
- update: read manufacture_date
- update: get _cell_count from parameter and not const 4
- update: avoid re-reading data that has already been read and stored on class already
- currently the battery type defined by BAT_SMBUS_MODEL parameter and not by auto detection
- track and publish validity based on hover thrust variance, innovation test ratio, and hysteresis
- only publish on actual updates or becoming inactive
- fix dt (previous timestamp wasn't being saved)
- use local position timestamp (corresponding) to accel data rather than current time to avoid unnecessary timing jitter
- check local position validity before using
- mc_hover_thrust_estimator: move from wq:lp_default -> wq:nav_and_controllers to ensure the hover thrust estimator runs after the position controller and uses the same vehicle_local_position data
- land_detector: check hover thrust estimate validity and adjust low throttle thresholds if hover thrust is available
- mc_pos_control: only use hover thrust estimate if valid
- always check system field for validity
- reject any data outside of "servo position" valid range from Spektrum specification
- properly support XPlus channels (12+)
- debug message if channel count changes
For the RC controlled yaw behaviour, we do a yaw setpoint according to
the stick expo. The uncontrolled yaw behaviour behaves undefined.
Switching between yaw behaviours makes the drone stand still for a
moment, which probably can be improved.
This Commit includes a update of the mavlink submodule
since the CELLULAR_STATUS message was updated, the necessary changes were done together
Add enums
- remove all remaining IOCTLs for accel and gyro and handle all calibration entirely in sensors module with parameters
- sensor_accel and sensor_gyro are now always raw sensor data
- calibration procedures no longer need to first clear existing values before starting
- temperature calibration (TC) remove all scale (SCL) parameters
- gyro and baro scale are completely unused
- regular accel calibration scale can be used (CAL_ACC*_xSCALE) instead of TC scale
- IMU integration move from drivers (PX4Accelerometer/PX4Gyroscope) to sensors/vehicle_imu
- sensors: voted_sensors_update now consumes vehicle_imu
- delete sensor_accel_integrated, sensor_gyro_integrated
- merge sensor_accel_status/sensor_gyro_status into vehicle_imu_status
- sensors status output minor improvements (ordering, whitespace, show selected sensor device id and instance)
This moves the handling of the BAT%d_SOURCE param inside of the battery
library. Users of the library now pass the source instead of the flag
whether to publish. The battery library then checks if the source is
selected using the param and publishes accordingly.
Since we removed the strange system_source flag, we now need to look at
all batteries in commander.
For current estimation - I think - it makes sense to sum them up.
* Enhancement: State of health, and max_error value is added. Both shows battery health of SMBUS smart battery.
* Enhancement: BAT_C_MULT parameter is introduced. This is for high-current capable SMBUS-based battery.
As SMBUS only provides 16-bit for current, it could only be +-32768mA which is about +-32A.
But with proper treatment, it could be extended with little accuracy loss.
This factor can be set for individual battery system with available information.
* Relative SOC introduced. Proper SMBUS battery should provide percentage of remaining battery
directly. Therefore it does not have to be computed like before.
* State of Health introduced. Proper SMBUS battery should provide SOH value.
* Max error: this shows estimation error of BMS.
* Enhancement: With smart battery, precise estimation of time remaining is provided
with impedance track. It is unit of minute, so 60 seconds multiplied.
Update rate of this is not fast, but very useful.
Co-authored-by: Hyon Lim <lim@uvify.com>
* msg: Add EKF-GSF yaw estimator logging data
* ecl: update to version with EKF-GSF yaw estimator
* ekf2: Add param control and logging for EKF-GSF yaw estimator
* logger: Add logging for EKF-GSF yaw esimtator
The implementation before this change had two timeouts, a hard-coded
timeout of 0.5 seconds as well as a by param configurable timeout with
certain failsafe actions set.
This change aims to fix two problems:
1. The hard-coded offboard timeout can be triggered easily with sped up
lockstep simulation. Since i t is hard-coded it can't be adapted to
the speed factor.
2. The offboard signal can time out but no action will be taken just
yet. This means we end up in an in-between stage where no warning or
failsafe action has happened yet, even though certain flags are set
to a timeout state.
This patch aims to fix this by unifying the two timeouts to the existing
configurable param. The convoluted double timeout logic is replaced by a
simple hysteresis.
For anyone that has previously not changed the default timeout param (0),
the param will now be changed to 0.5 seconds which reflects the
previously hardcoded time. For anyone with a specific timeout
configured, the behaviour should remain the same.
Also, going forward, timeouts lower than 0.5 seconds should be possible.
- checked register mechanism and simple watchdog
- driver checks for errors gradually and can reconfigure itself
- respect IMU_GYRO_RATEMAX at the driver level
- fixed sensor INT16_MIN and INT16_MAX handling (y & z axis are flipped before publishing)
- increased sensor_gyro_fifo max size (enables running the driver much slower, but still transferring all raw data)
- PX4Accelerometer/PX4Gyroscope remove unnecessary memsets
The problem with printing the exception was that starting with
Python 3.6 the ImportError is yet another (sub) exception called
ModuleNotFoundError which can't be printed as a string and then triggers
another exception:
```
Traceback (most recent call last):
File "/home/julianoes/src/Firmware/Tools/serial/generate_config.py", line 11, in <module>
import jinja2
ModuleNotFoundError: No module named 'jinja2'
During handling of the above exception, another exception occurred:
Traceback (most recent call last):
File "/home/julianoes/src/Firmware/Tools/serial/generate_config.py", line 13, in <module>
print("Failed to import jinja2: " + e)
TypeError: must be str, not ModuleNotFoundError
```
As per @bkueng's suggestion the easiest is to cast the exception to str
and that way prevent the second exception.
with measurement noise auto-tuning
The purpose of this estimator is to improve land detection and vertical
velocity feedforward
Recovery strategy:
This is required when the setpoint suddenly changes in air or that the
EKF is diverging. A lowpassed test ratio is used as a trigger for the recovery logic
Also, a lowpassed residual is used to estimate the steady-state value
and remove it when estimating the accel noise to avoid increasing the
accel noise when the redisual is caused by an offset.
* Add param for software flow ctl on 3DR radios
* Dont reset telemetry type on radio timeout
* Treat 3DR radio as generic link type
* Rename 3DR to SiK radio
I've added a queue depth of 4 for sensor_accel and sensor_gyro. This is initially added because it's not always possible for the `vehicle_acceleration` to keep up with every publication of the primary accelerator as it runs in the same thread as ekf2, various controllers, etc.
Later this mechanism will be used in a few areas
- rate limit `vehicle_angular_velocity` and `vehicle_acceleration` without missing any raw data
- move IMU integration to `vehicle_imu` and out of the actual driver threads, eliminating the need for sensor_accel_integrated and sensor_gyro_integrated
- integrate raw gyro synchronized with optical flow measurements
- introduces parameter IMU_DGYRO_CUTOFF to configure the angular acceleration low pass filter
- the angular acceleration is computed by differentiating angular velocity after the notch filter (IMU_GYRO_NF_FREQ & IMU_GYRO_NF_BW) is applied
Co-authored-by: Julien Lecoeur <jlecoeur@users.noreply.github.com>
- gyro filtering (low-pass and notch) only performed on primary gyro in `sensors/vehicle_angular_velocity` instead of every gyro in `PX4Gyroscope`
- sample rate is calculated from actual updates (the fixed value was slightly wrong in many cases, and very wrong in a few)
- In the FIFO case the array is now averaged and published in `sensor_gyro` for filtering downstream. I'll update this in the future to use the full FIFO array (if available), but right now it should be fine.
- this is a new module for temperature compensation that consolidates the functionality previously handled in the sensors module (calculating runtime thermal corrections) and the events module (online thermal calibration)
- by collecting this functionality into a single module we can optionally disable it on systems where it's not used and save some flash (if disabled at build time) or memory (disabled at run time)
- split out integrated data into new standalone messages (sensor_accel_integrated and sensor_gyro_integrated)
- publish sensor_gyro at full rate and remove sensor_gyro_control
- limit sensor status publications to 10 Hz
- remove unused accel/gyro raw ADC fields
- add device IDs to sensor_bias and sensor_correction
- vehicle_angular_velocity/vehicle_acceleration: check device ids before using bias and corrections
- this provides some extra space when the FIFO transfers don't align perfectly
- I've also made an effort to keep the different drivers (icm20602, icm20608g, ism330ldc) in sync so we can factor out the common portions later once we've confident in the pattern.
* Treat UAVS diffrently from manned aviation
* Added fake_traffic testing functionality,
* Added NAV_TRAFF_AVOID Hold and Landmode
* Added Behavior: HOLD Position to collision avoidance mode and implemented Landmode to collision avoidance.
Boards where no Hardware GUID is defined will send 0 as GUID.
Right now collision avoidance for more than one FMU without Hardware GUID is not possible.
We should consider adding a randomly generated HW GUID as a placeholder for legacy Boards
We now check individually for empy and genmsg.
Also, my recommendation is to use pip3 as a user to install the
dependencies as this is least intrusive and should work on all
platforms.
* parameter and logic to commander for triggering failsafe from external automatic trigger system.
* logic to startup script for enabling ATS. Added uORB publishing to pwm_input module.
* Refactored out CDev usage from pwm_input and ll40ls. Refactored out ll40ls specifics from pwm_input and cleaned up dead code.
- rename of flag in position sp: from allow_weather_vane to disable_weather_vane
- flag now doesn't have to be set for all auto modes, meaning that weather vane is also active outside of mission
- flag is set before front transition to align with wp, and unset after alignment is over
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
- uses the FIFO and SPI DMA to transfer full raw data (8 kHz gyro, 4 kHz accel)
- new sensor messages for better visibility
- sensor_{accel, gyro}_fifo: full raw data for optional logging and analysis
- sensor_{accel, gyro}_status: metadata, clipping, etc
- currently not enabled by default
- gencpp in PX4/Firmware (d5fb89ee02): 7e446a9976
- gencpp current upstream: ff6c9f3e8e
- Changes: 7e446a9976...ff6c9f3e8e
ff6c9f3 2019-11-11 Jochen Sprickerhof - Two patches to make the generated headers reproducible (#42)
e12443e 2019-03-18 Dirk Thomas - 0.6.2
d227d17 2019-03-18 Dirk Thomas - update changelog
e233144 2019-03-15 Martin Pecka - Added plugins the ability to also generate free functions. (#40)
40559af 2019-03-04 Dirk Thomas - 0.6.1
96ec7f1 2019-03-04 Dirk Thomas - update changelog
* FW attitude controller, FW position controller and VTOL attitude controller subscribe to airspeed_validated topic
* add possibility to switch off the airspeed valid checks
* remove airspeed valid checks from commander
* clean up of VTOL transition logic
* Airspeed Selector: remove dynamic allocation of airspeed validators (depending on number of connected sensors) but do it statically for the maximum number allowed. Check for number of connected sensors not only during start up, but always when vehicle is disarmed.
* Airspeed Selector: change work queue from lp to att_pos_ctrl as this module is safety-critical
* add airspeed selector to px4_fmu-v2 defaults
esc_setpoint in UAVCAN was just wrong, this is what it really is:
uint7 power_rating_pct # Instant demand factor in percent
(percent of maximum power); range 0% to 127%.