Commit Graph

40845 Commits

Author SHA1 Message Date
Hamish Willee 30e2490d5b
Docs are now in user guide and main (#19977)
* Fix links to docs in source to point to docs on main not master

* More docs and scripts that need to point to main
2022-08-01 11:39:39 +10:00
Peter van der Perk c566fb414b S32K1XX add dummy iwdg driver 2022-07-31 11:21:41 -04:00
Beat Küng e7588d2da0 px4io+pwm_out: set the PWM rate and disarmed value when a channel is first set to a servo
This should simplify the first setup a bit.
2022-07-31 11:20:57 -04:00
Igor Mišić f929017618 boards: link missing arch_io_pins lib 2022-07-31 11:19:20 -04:00
Daniel Agar 41d9c3dd2a ekf2: add AUX velocity aid src status
- also includes velocity and position helpers for using estimator aid
   source status messages that will later be used for GPS, EV, etc
2022-07-29 12:02:31 -04:00
Daniel Agar a397c09e59 ekf2: use estimator_aid_src for all yaw sources (mag, gnss, ev) 2022-07-29 11:20:48 -04:00
Agata Barcis d5d88cba5b generate_microRTPS_bridge.py updated to support ROS2 humble
Signed-off-by: Agata Barcis <agata.barcis@tii.ae>
2022-07-29 15:21:05 +02:00
Silvan Fuhrer 638eff426a AirspeedValidator: increase max update step size of tas_scale_validated from 1% to 5%
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-07-29 09:29:27 +02:00
Beniamino Pozzan a20483ed11 msg/position_controller_landing_status.msg: fix constant name conventions
- msg constant names now comply with ROS conventions:
uppercase alphanumeric characters with underscores for separating words

partially fix #19917

Signed-off-by: Beniamino Pozzan <beniamino.pozzan@phd.unipd.it>
2022-07-28 11:29:03 -04:00
Daniel Agar 9ed861e0a3 lib/mixer_module: split functions into separate headers
- this arguably improves visibility/discoverability
2022-07-28 08:08:58 +02:00
bresch f7ff0a9961 WindEstimator: add test case for airspeed fusion singularity 2022-07-27 08:19:40 -04:00
Daniel Agar 38c02ea29a wind_estimator: cmake add symforce generation helper target (wind_estimator_generate_airspeed_fusion) 2022-07-27 08:19:40 -04:00
bresch 26190a7799 WindEstimator: use SymForce auto-generated function for airspeed fusion 2022-07-27 08:19:40 -04:00
Hamish Willee e6eed43648
Spelling errors (#19935) 2022-07-27 14:33:16 +10:00
RomanBapst 97f632a408 vtol_takeoff: reset reposition triplet before handing over to loiter mode
Signed-off-by: RomanBapst <bapstroman@gmail.com>
2022-07-25 14:48:18 +02:00
Igor Mišić d6488fafc3 serial_test: fix first write_count_value for next write 2022-07-25 11:48:36 +02:00
Igor Mišić 32ca7ad706 serial_test: fix write for max buffer size 2022-07-25 11:48:36 +02:00
Taylor Nelms 21cb0ef50f Component: flash parameter storage on stm32h7. Fixes #15331.
As per the discussion in #15331, fixed issue where stm32h7 chips
    use hardware ECC bits in program memory that disallow overwriting
    32-byte flash line that has already been written. As such,
    this change allows for a variant implementation of the flashfs system
    that uses more space in the flash entry header in order to
    allow an entire line to be reserved for erasing an entry.

Signed-off-by: Taylor Nelms <tnelms@roboticresearch.com>
2022-07-25 08:19:00 +02:00
Thomas Stastny 6a0f394d46 rtl: reset rtl state only on activation
rtl state was getting reset on inactive, which meant that the state which triggered resuming e.g. mission landing would be overwritten, and the navigator mode would switch back and forth between rtl and mission. this commit:
1. moves the reset of rtl state to the on activation function (removing it from the on inactive function)
2. functionalizes the rtl state input to the rtl time estimator so that rtl time can still be calculated from state=none while inactive
2022-07-22 14:59:20 +02:00
Thomas Stastny e512d77b89 RTL: expose RTL state 2022-07-22 14:59:20 +02:00
Silvan Fuhrer 85a621303d VtolLandDetector: remove airspeed check
This commit removes the additional airspeed check (airspeed for VTOLs in
hover below LNDFW_AIRSPD_MAX), as it is not a required condition in the
landed state (headwind blowing into the airspeed sensor won't stop
once on the gruond). In FW mode the check would make more sense, but there
the land detector is currently simply disabled.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-07-22 08:31:32 +02:00
Daniel Agar 32c6ec061e sensors: add kconfig options to skip angular velocity and acceleration 2022-07-21 11:27:09 -04:00
Silvan Fuhrer c9c62b860c ROMFS: add generic tiltrotor VTOL (13200)
Add geometry for a quad tiltrotor VTOL, with only front motors tiltable,
two ailerons and a V-tail.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-07-21 10:09:12 -04:00
Silvan Fuhrer 3ffc37d988 ROMFS: generic tailsitter VTOL: enable CA by default and remove legacy mixer
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-07-21 10:09:12 -04:00
Silvan Fuhrer ab58717313 ROMFS: standard VTOL: enable CA by default and remove legacy mixer
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-07-21 10:09:12 -04:00
Silvan Fuhrer 607c53e873 ROMFS: flying wing: enable CA by default and remove legacy mixer
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-07-21 10:09:12 -04:00
Silvan Fuhrer 4dabc8b7ed ROMFS: standard plane: enable CA by default and remove legacy mixer
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-07-21 10:09:12 -04:00
Daniel Agar 70e95812e7 ekf2: reset mag_lpf (by zeroing _mag_counter) when resetting mag bias (or changing mags)
- so that there's new filtered data avaiable for reset
2022-07-21 09:24:28 -04:00
Daniel Agar ecdade3638 ekf2: mag in air reset fall back to regular resetMagHeading() if realignYawGPS() fails 2022-07-21 09:24:28 -04:00
Daniel Agar 05133aed27 ekf2: clear test ratios, flags, etc when stopping mag fusion 2022-07-21 09:24:28 -04:00
Daniel Agar 65a587e56a ekf2: mag fusion don't update all states if mag_fault or mag_field_disturbed 2022-07-21 09:24:28 -04:00
Daniel Agar a41a0e7e80 ekf2: resetMagHeading() split out simple init case 2022-07-21 09:24:28 -04:00
Daniel Agar 9efadad06a ekf2: move checkMagFieldStrength() to magFieldStrengthDisturbed() const method 2022-07-21 09:24:28 -04:00
Daniel Agar a7f573e150 ekf2: delete isStrongMagneticDisturbance() 2022-07-21 09:24:28 -04:00
Daniel Agar e6e27e694e ekf2: delete isYawResetAuthorized() 2022-07-21 09:24:28 -04:00
Daniel Agar 0f1f6daa1a ekf2: delete isMagBiasObservable() 2022-07-21 09:24:28 -04:00
Daniel Agar d160229f47 ekf2: delete isYawAngleObservable() 2022-07-21 09:24:28 -04:00
Daniel Agar b0c979f745 ekf2: add copyright header to EKFGSF_yaw and utils 2022-07-21 09:24:28 -04:00
Daniel Agar 4fee059696 ekf2: simplify mag yaw reset request when transitioning to mag enabled 2022-07-21 09:24:28 -04:00
Daniel Agar f254b55523 ekf2: add mag fusion timestamps 2022-07-21 09:24:28 -04:00
Jukka Laitinen e3e067d640 stub_keystore: Allow using also with other that SW_CRYPTO driver
Remove "depends on DRIVERS_SW_CRYPTO"

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-07-21 08:08:14 +02:00
Jukka Laitinen 026bd073b5 Don't error on CONFIG_CRYPTO_RANDOM_POOL not defined
px4_secure_random can be implemented also outside NuttX for some platform

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-07-21 08:08:14 +02:00
Thomas Stastny d6fb1114ff rtl: fix printout of rtl delay time 2022-07-20 14:15:12 +02:00
Thomas Stastny 1ec62c4063 rtl: let fixed-wing RTL all the way to the loiter/delay state
also fix home vs destination alt discrepancy on RTL
2022-07-20 14:15:12 +02:00
Daniel Agar 2f3cb97872 sensors/vehicle_magnetometer: don't advertise vehicle_magnetometer instance if mag has been disable
- if using multi-EKF across all magnetometers then an instance of
vehicle_magnetometer is advertised immediately for every sensor_mag
instance
 - this can become problematic if EKF2 multi-mag is enabled, but with
only 1 IMU (EKF2_MULTI_MAG) because you will be stuck with no magnetometer data
2022-07-20 01:18:19 -04:00
Daniel Agar e5be0e776e ekf2: if multi-mag disabled (EKF2_MULTI_MAG <= 1) properly re-enable sensors hub selection (SENS_MAG_MODE)
- this prevents potential misconfiguration if trying to disable ekf2 multi mag
2022-07-20 01:16:55 -04:00
Daniel Agar 8ccd8fbed1 px4io: minimal backup scheduling regardless of dynamic mixing
- even if there's no configured output we still need to run to grab RC
data
2022-07-20 01:15:36 -04:00
Daniel Agar 8f8615e6c2 delete CBRK_RATE_CTRL 2022-07-20 01:14:53 -04:00
Beat Küng 67107f4978 .clang-tidy: exclude some warnings
Some are too verbose, others don't apply to the code base
2022-07-20 01:14:04 -04:00
Beat Küng 84b0a889a4 cmake: add clion support 2022-07-20 01:14:04 -04:00