Commit Graph

40622 Commits

Author SHA1 Message Date
Daniel Agar c46fa01195 sensors: add kconfig mechanism to optionally exclude sensor types 2022-06-17 19:31:45 -04:00
Alex Klimaj 60450e63c0
uavcannode: Fix dronecan baro units 2022-06-17 14:22:15 -04:00
Beat Küng b9475d6ebe mavlink_shell: set target system and component id
These got added in https://github.com/mavlink/mavlink/pull/1725 and need
to be set for correct routing.
2022-06-17 09:29:43 -04:00
Daniel Agar dea404a9a3 boards: disable modules to save flash
- px4_fmu-v5x_rtps disable common barometers to save flash
 - px4_fmu-v6x_default disable telemetry drivers to save flash
2022-06-16 16:14:57 -04:00
Junwoo Hwang 8bae4e5c0e FollowMe : Replace First order target position filter with Second order position and velocity filter
Follow me : tidied second order filter implementation

Added velocity filtered info to uORB follow target status message, and rebase to potaito/new-follow-me-task

FollowMe : Rebasing and missing definition fixes on target position second order filter

Follow Me : Remove Alpha filter delay compensation code, since second order filter is used for pose filtering now

Followme : Remove unused target pose estimation update function

Follow Target : Added Target orientation estimation logic

Follow Target : Replaced offset vector based setpoint to rate controlled orbital angle control

Follow Target : Bug fixes and first working version of rate based control logic, still buggy

Follow Target : Added target orientation, follow angle, orbit angle value into follow_target_status uORB message for debugging

Follow Target : Fix orbit angle step calculation typo bug

Follow Target : Few more fixes

Follow Target : Few fixes and follow angle value logging bug fix

Follow Target : Added lowpass alpha filter for yaw setpoint filtering

Follow Target : Remove unused filter delay compensation param

Follow Target : Add Yaw setpoint filter initialization logic and bufix for when unwrap had an input of NAN angle value

Follow Target : Add Yaw setpoint filtering enabler parameter

Follow Target : Change Target Velocity Deadzone to 1.0 m/s, to accomodate walking speed of 1.5 m/s

Follow Target : Add Orbit Tangential Velocity calculation for velocity setpoint and logging uORB topics

Follow target : Fix indentation in yaw setpoint filtering logic

Follow Target : Fix Follow Target Estimator timeout logic bug that was making the 2nd order pose filter reset to raw value every loop

Follow Target : Remove debug printf statement for target pose filter reset check

Follow Target : Add pose filter natural frequency parameter for filter testing

Follow Target : Make target following side param selectable and add target pose filter natural frequency param description

Follow Target : Add Terrain following altitude mode and make 2D altitude mode keep altitude relative to the home position, instead of raw local position origin

Follow Target : Log follow target estimator & status at full rate for filter characteristics test

Follow Target : Implementing RC control user input for Follow Target control

Follow Target : edit to conform to updated unwrap_pi function

Follow Target : Make follow angle, distance and height RC command input configurable

Follow Target : Make Follow Target not interruptable by moving joystick in Commander

Follow Target : reconfigure yaw, pitch and roll for better user experience in RC adjusting configurations, and add angular rate limit taking target distance into account

Follow Target : Change RC channels used for adjustments and re-order header file for clarity

Follow Target : Fix Parameters custom parent macro, since using DEFINE_PARAMETERS alone misses the parameter updates of the parent class, FlightTask

Follow Target : Fix Orbit Tangential speed actually being angular rate bug, which was causing a phenomenon of drnoe getting 'dragged' towards the target velocity direction

Follow Target : Final tidying and refactoring for master merge - step 1

Add more comments on header file

Follow Target : tidy, remove unnecessary debug uORB elements from follow_target_status message

Follow Target : Turn off Yaw filtering by default

Follow Target : Tidy maximum orbital velocity calculation

Follow Target : add yaw setpoint filter time constant parameter for testing and fix NAV_FT_HT title

Follow Target : Add RC adjustment window logic to prevent drone not catching up the change of follow target parameters

Follow Target : fixes

Follow Target: PR tidy few edits remove, and update comments

Follow Target : apply comments and reviews

Follow Target : Edit according to review comments part 2

Follow Target : Split RC adjustment code and other refactors

- Splitted the RC adjustment into follow angle, height and distance
- Added Parameter change detection to reset the follow properties
- Added comments and removed yaw setpoint filter enabler logic

Follow Target : Modify orbit angle error bufferzone bug that was causing excessive velocity setpoints when setpoint catched up with raw orbit setpoint

Follow Target : Remove buffer zone velocity ramp down logic and add acceleration and rate limited Trajectory generation library for orbit angle and velocity setpoint

Follow Target : Remove internally tracked data from local scope function's parameters to simplify code

Follow Target : Fix to track unwrapped orbit angle, with no wrapping

Follow Target : Apply user adjustment deadzone to reduce sensitivity

Follow Target : Apply suggestions from PR review round 2 by @potaito

Revert submodule update changes, fall back to potaito/new-followme-task

Follow Target : [Debug] Expose max vel and acceleration settings as parameters, instead of using Multicopter Position Controller
's settings

Follow Target : Use matrix::isEqualF() function to compare floats

Follow Target : Add Acceleration feedback enabler parameter and Velocity ramp in initial commit for overshoot phenomenon improvement

Follow Target : Implement Velocity feed forward limit and debug logging values

Follow Target : Apply Velocity Ramp-in for Acceleration as well & Apply it to total velocity setpoint and not just orbit tangential velocity component

Follow Target : Don't set Acceleration setpoint if not commanded

Follow Target : Use Jerk limited orbit angle control. Add orbit angle tracking related uORB values"

Follow Target : Add Orbit Angle Setpoint Rate Tracking filter, to take into consideration for calculating velocity setpoint for trajectory generator for orbit angle

Revert "Follow Target : Add Orbit Angle Setpoint Rate Tracking filter, to take into consideration for calculating velocity setpoint for trajectory generator for orbit angle"

This reverts commit a3f48ac7652adb70baf3a2fed3ea34d77cbd6a70.

Follow Target : Take Unfiltered target velocity into acount for target course calculation to fix overshoot orbit angle 180 deg flip problem

Follow Target : Remove Yaw Filter since it doesn't make a big difference in yaw jitterness

Follow Target : Remove velocity ramp in control & remove debug values from follow_target_status.msg

Follow Target : Tidy Follow Target Status message logging code

Follow Target : Remove jerk and acceleration settings from Follow Target orbit trajectory generation

Follow Target : Change PublicationMulti into Publication, since topics published are single instances

Follow Target : Edit comments to reflect changes in the final revision of Follow Target

Follow Target : Apply incorrectly merged conflicts during rebase & update Sticks function usage for getThrottled()

Follow Target : Apply final review comments before merge into Alessandro's PR

Apply further changes from the PR review, like units

Use RC Sticks' Expo() function for user adjustments to decrease sensitivity around the center (0 value)

Update Function styles to lowerCamelCase

And make functions const & return the params, rather than modifying them
internally via pointer / reference

Specify kFollowPerspective enum as uint8_t, so that it can't be set to negative value when converted from the parameter 'FLW_TGT_FP'

Fix bug in updateParams() to reset internally tracked params if they actually changed.

Remove unnecessary comments

Fix format of the Follow Target code

Fix Follow Perspective Param metadata

follow-me: use new trajectory_setpoint msg

Convert FollowPerspective enum into a Follow Angle float value

1. Increases flexibility in user's side, to set any arbitrary follow
angle [deg]
2. Removes the need to have a dedicated Enum, which can be a hassle to
make it match MAVSDK's side
3. A step in the direction of adding a proper Follow Mode (Perspective)
mode support, where we can support kite mode (drone behaves as if it is
hovering & getting dragged by the target with a leash) or a constant
orbit angle mode (Drone always on the East / North / etc. side, for
cinematic shots)

Continue fixing Follow Target MAVSDK code to match MAVSDK changes

- Support Follow Angle configuration instead of Follow Direction
- Change follow position tolerance logic to use the follow angle
*Still work in progress!

Update Follow Me MAVSDK Test Code to match MAVSDK v2 spec

- Add RC Adjustment Test case
- Change follow direction logic to follow angle based logic completely
- Cleanup on variable names and comment on code

follow-me: disable SITL test

Need to update MAVSDK with the following PR:
https://github.com/mavlink/MAVSDK/pull/1770

SITL is failing now because the follow-me
perspectives are no longer defined the
same way in MAVSDK and in the flight task.

update copyright year

follow-me: mark uORB topics optional

Apply review comments

more copyright years

follow-me sitl test: simpler "state machine"

flight_mode_manager: exclude AutoFollowTarget and Orbit on flash contrained boards

Remove unnecessary follow_target_status message properties

- As it eats up FLASH and consumes uLog bandwidth
2022-06-16 16:14:57 -04:00
Alessandro Simovic de1fa11e96 New follow-me flight task
rename follow_me_status to follow_target_status

enable follow_target_estimator on skynode

implement the responsiveness parameter:
The responsiveness parameter should behave similarly to the previous
follow-me implementation in navigator. The difference here is that
there are now two separate gains for position and velocity fusion.
The previous implemenation in navigator had no velocity fusion.

Allow follow-me to be flown without RC

SITL tests for follow-me flight task

This includes:
- Testing the setting for the follow-me angle
- Testing that streaming position only or position
  and velocity measurements both work
- Testing that RC override works

Most of these tests are done with a simulated model
of a point object that moves on a straight line. So
nothing too spectacular. But it makes the test checks
much easier.

Since the estimator for the target actually checks new
measurements and compares them to old ones, I also added
random gausian noise to the measurements with a fixed seed
for deterministic randomness. So repeated runs produce
exactly the same results over and over.

Half of the angles are still missing in MAVSDK. Need to create
an upstream PR to add center left/right and rear left/right options.
These and the corresponding SITL tests need to be implemented
later.

sitl: Increase position tolerance during follow-me

Astro seems to barely exceed the current tolerance (4.3 !< 4.0)
causing CI to fail. The point of the CI test is not to check
the accuracy of the flight behaviour, but only the fact that the
drone is doing the expected thing. So the exact value of this
tolerance is not really important.

follow-me: gimbal control in follow-me

follow-me: create sub-routines in flight task class

follow-me: use ground-dist for emergency ascent

dist_bottom is only defined when a ground facing distance sensor exist.
It's therefore better to use dist_ground instead, which has the distance
to the home altitude if no distance sensor is available.

As a consequence it will only be possible to use follow-me in a valley
when the drone has a distance sensor.

follow-me: point gimbal to the ground in 2D mode

follow-me: another fuzzy msg handling for the estimator

follow-me: bugfix in acceleration saturation limit

follow-me: parameter for filter delay compensation

mantis: dont use flow for terrain estimation

follow-me: default responsiveness 0.5 -> 0.1

0.5 is way too jerky in real and simulated tests.

flight_task: clarify comments for bottom distance

follow-me: minor comment improvement

follow-me: [debug] log emergency_ascent

follow-me: [debug] log gimbal pitch

follow-me: [debug] status values for follow-me estimator

follow-me: setting for gimbal tracking mode

follow-me: release gimbal control at destruction

mavsdk: cosmetics 💄
2022-06-16 16:14:57 -04:00
Chris Seto 285556e463 Re-set param limits for fw tuning values to align with fw tuning guide 2022-06-16 14:22:51 -04:00
Daniel Agar c1c2858341
Update submodule GPSDrivers to latest Thu Jun 16 12:38:52 UTC 2022
- GPSDrivers in PX4/Firmware (1069570a2a90fdc7f0e081b6c2c4b418446d65d7): 016c37cd1f
    - GPSDrivers current upstream: 8c09c5426d
    - Changes: 016c37cd1f...8c09c5426d

    8c09c54 2022-06-15 Daniel Agar - sbf trivial whitespace fix

Co-authored-by: PX4 BuildBot <bot@px4.io>
2022-06-16 12:21:06 -04:00
Matthias Grob 92b6862485 Commander: replace arm requirements 2022-06-16 10:25:32 -04:00
Matthias Grob 3b3d8b9942 Commander: execute pre arm check with preflight checks 2022-06-16 10:25:32 -04:00
Matthias Grob aa575d6af0 Commander: move first preflight check run to constructor 2022-06-16 10:25:32 -04:00
Matthias Grob 0f41a5e385 ArmStateMachine: simplify how preflight checks are called 2022-06-16 10:25:32 -04:00
Igor Mišić 5dc3fecac0 boards/bitcraze: add PWM_SERVO_STOP define 2022-06-16 08:09:00 +02:00
Igor Mišić 7c1da8d608 driver/px4io: set default failsafe values 2022-06-16 08:09:00 +02:00
Igor Mišić 04c2d0fe97 drivers/pwm_out: set default failsafe values 2022-06-16 08:09:00 +02:00
Daniel Agar 1980b5c5e8
ekf2: setEkfGlobalOrigin() reset baro and hgt sensor offsets if necessary
- handle uninitalized _gps_alt_ref
 - add basic lat/lon/alt sanity checks
2022-06-16 00:59:54 -04:00
achim fc3d88bb67
boards/diatone/mamba-f405-mk2: symmetric buffers for wifi telemetry (#19808)
Symmetric buffers allow a much more reliable QGC Wifi telemetry connection especially when (virtual) joysticks are used.  (this board does not provide RX DMA on UART 4 as its timer does DSHOT).
2022-06-15 14:30:28 -04:00
Matthias Grob c59809b14a Commander: remove system_sensors_initialized
and system_hotplug_timeout. They're not in use for over 2 years.
Instead control LED with preflight checks.
2022-06-15 14:02:00 -04:00
Igor Mišić 0922f003f5 uavcan: don't print an error if there is no UAVCAN device on the CAN bus 2022-06-15 03:29:13 -04:00
bresch 680191cc75 WindEstimator: make wind process noise tuning same as EKF2 2022-06-14 18:44:30 +10:00
bresch b6f1a7aed9 migrate wind process noise parameters 2022-06-14 18:39:10 +10:00
bresch 0d256b8ff6 ekf2 wind: use noise spectral density for process noise tuning
The noise spectral density, NSD, (square root of power spectral density) is a
continuous-time parameter that makes the tuning independent from the EKF
prediction rate.
NSD corresponds to the rate at which the state uncertainty increases
when no measurements are fused into the filter.
Given that the current prediction rate of EKF2 is 100Hz, the
same tuning is obtained by dividing the std_dev legacy parameter by 10:
nsd = sqrt(std_dev^2 / 100Hz)
2022-06-14 18:39:10 +10:00
bresch e105869986 wind_estimator: use noise spectral density for process noise tuning
The noise spectral density, NSD, (square root of power spectral density) is a
continuous-time parameter that makes the tuning independent from the EKF
prediction rate.
NSD corresponds to the rate at which the state uncertainty increases
when no measurements are fused into the filter.
Given that the current prediction rate of the wind estimator is 1Hz, the
same tuning is obtained with the same values as before.
2022-06-14 18:39:10 +10:00
Junwoo Hwang 377338109c uLog message definition comment improvements
- Added more comments
- Converted to DOxygen comment format for the comments on struct members
2022-06-13 10:31:07 +02:00
Junwoo Hwang 1ddd1573be Improve uLog message struct definitions
1. Rename *_header_s structs to *_s, since the _header postfix is not
helpful
2. Rename the "key" string variables in the message structs to
"key_value_str" as the string actually contains not just the key but the
key and value pair information
3. Add comments on other uLog messages to clarify use (need more
improvement / can be even more simplified)
2022-06-13 10:31:07 +02:00
achim e6f90bcb81 disable uart´s dma
Still no way to get GPS and auto flash of the IO without disabling their uart´s dma
2022-06-11 13:39:01 -04:00
fury1895 283aad01fd Airspeed params: change default for ASPD_SCALE_APPLY to 2 2022-06-10 14:02:41 +02:00
David Sidrane f15eb91814 px4_fmu-v6x:HB Mini add Ver 3, Ver 4 init 2022-06-10 04:20:26 -07:00
PX4 BuildBot e33199c182 Update submodule mavlink to latest Fri Jun 10 00:38:25 UTC 2022
- mavlink in PX4/Firmware (59630bcc7e7e983db2d9138c8254144c77855adc): 0909631552
    - mavlink current upstream: 05864e218e
    - Changes: 0909631552...05864e218e

    05864e21 2022-06-09 Peter Barker - common.xml: add ignition_voltage to EFI_STATUS (#1854)
adc9c3f5 2022-06-01 olliw42 - update storm32.xml (nfc) (#1851)
49dbdb66 2022-06-01 Randy Mackay - ardupilotmega: add nav_attitude_time command (#1852)
2022-06-10 01:01:20 -04:00
Thomas Debrunner 46c9d1e288
SIH in SITL with lockstep (#19028)
* 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>
2022-06-09 09:52:34 +02:00
Thomas Stastny a7e11464c1 fw pos ctrl: update method documentation 2022-06-09 09:23:02 +02:00
Thomas Stastny 594a6d6e80 fw pos ctrl: some incremental clean up of the class
- 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
2022-06-09 09:23:02 +02:00
Silvan Fuhrer 9863c24b40 navigator_main: DO_REPOSITION: only trigger reposition setpoint update if vehicle is armed
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-06-08 21:47:06 +02:00
Thomas Stastny cbf0fe8803 fw pos ctrl: centralize parameter and state resets 2022-06-08 08:44:30 -05:00
Thomas Stastny ccfbbb553a fw pos ctrl: only manipulate heading hold yaw in manual position control mode 2022-06-08 08:44:30 -05:00
Thomas Stastny 67d8dd359d fw pos ctrl: calculate control interval once
- Use the same time interval for all position control logic (including TECS)
- Sync naming in control methods
- Remove some unused input arguments
2022-06-08 08:44:30 -05:00
Matthias Grob f5e7b1e6a8 Commander: switch battery bitflied to dedicated datatype 2022-06-08 11:32:26 +02:00
Matthias Grob 9b2166de72 manual_control_params: configure arm gesture doesn't require reboot
I added wrong documentation here.
2022-06-08 05:12:05 -04:00
Matthias Grob bd50a52c9c Commander: fix startup sound interrupted by safety button initialization
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.
2022-06-08 05:12:05 -04:00
Matthias Grob 71103e6114 Safety: keep initialized constant flags when safety disabled 2022-06-08 05:12:05 -04:00
Matthias Grob 44c4b8fa85 Style refactoring related to safety button 2022-06-08 05:12:05 -04:00
Daniel Agar ce70b6f4ac sensors/vehicle_angular_velocity: add IMU_GYRO_RATEMAX constraints 2022-06-07 15:45:47 -04:00
Daniel Agar 01f0992f49 sensors/vehicle_imu: don't bother checking IMU_GYRO_RATEMAX 2022-06-07 15:45:47 -04:00
Matthias Grob 5df266cedc MulticopterRateControl: use constructor to copy thrust setpoint array 2022-06-07 11:45:59 -04:00
bresch 4f1091792f ekf2 preflight: only check innovation of active height sources 2022-06-07 11:44:56 -04:00
Daniel Agar cb2738e187
Update submodule GPSDrivers to latest Sat Jun 4 12:38:49 UTC 2022 (#19766)
- GPSDrivers in PX4/Firmware (6e77a084cd43830c8b13018b7fd5470da9bc4ff5): 181fae1a4b
    - GPSDrivers current upstream: 016c37cd1f
    - Changes: 181fae1a4b...016c37cd1f

    016c37c 2022-06-01 Julian Oes - sbf: fix overrun on invalid length
2022-06-04 15:58:56 -04:00
PX4BuildBot a247b42907 [AUTO COMMIT] update change indication 2022-06-04 15:57:11 -04:00
PX4 BuildBot e86a74321e Update world_magnetic_model to latest Sat Jun 4 11:14:10 UTC 2022 2022-06-04 15:57:11 -04:00
Beat Küng da55256f2f test_multicopter_failure_injection: remove 'Reject before arming' test
Not sure why injection should fail before arming.
2022-06-04 07:40:29 +02:00
Beat Küng d1142008f6 FailureDetector: check if ESCs have current
And increase the timeout to 300ms, as some ESCs only update with 10Hz.
2022-06-04 07:40:29 +02:00