The acceleration setpoint gets implicitly inherited from the altitude
flight task since #14212. This feed-forward adds an unwanted
acceleration when the right stick is deflected. Instead I'm using it
to command the expected centripetal acceleration when flying
in a circle for better orbit tracking.
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.
* FW attitude control scaling fixes and cleanup
This commit aligns the scaling better with the derivations in
https://dev.px4.io/master/en/flight_stack/controller_diagrams.html#airspeed-scaling
Integrator terms now scale with IAS^2 (all three axes)
To match the roll and pitch controllers:
- Yaw integrator scale is now applied during accumulation, not to
integral value (so now FW_YR_IMAX is respected more intuitively)
- Yaw FF term now scale with IAS instead of IAS^2
Also made a number of small changes to make the three files
(roll, pitch, yaw) 3-way diffable to be clearer about what the
differences among them are.
* Remove unused yaw coordination method
- "Coordination method" open vs. closed code removed, since closed
is never used and not actually implemented.
- No change to behavior
* Remove PX4_WARN messages
Co-authored-by: george <george@campsix.com>
This Commit includes a update of the mavlink submodule
since the CELLULAR_STATUS message was updated, the necessary changes were done together
Add enums
This removes the check for the current position of the VTOL swtich, as arming is already prevented if in transition mode,
plus also if VTOL and in fixed-wing mode (unless CBRK_VTOL_ARMING is set).
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
- schedule on interval multiple of sensor_gyro publications without increasing the configured integration rate
- IMU_INTEG_RATE add enums to guide appropriate selection
- add average calculation bounds to prevent incorrect calculation and force monitoring again if there are consecutive gaps in data
- the latch would actually cause more problems if the backup schedule hit
- this reduces the number of cycles where the FIFO is actually empty at max rate (when there's only 1 sample in the FIFO expected)
- cleanup failover related messaging
- store previous failover count to prevent unecessary checks
- check for parameter update initially to minimize work after fetching
fresh sensor data
- Introduced COM_LKDOWN_TKO parameter
- Introduced auto disarm for lockdown state
- Do not trigger flight termiantion if system is in lockdown
Signed-off-by: Claudio Micheli <claudio@auterion.com>
- matrix in PX4/Firmware (a1043f6ce068cc4d039d6808ef98fd8c3f379582): f529358e9a
- matrix current upstream: 9a30828a0a
- Changes: f529358e9a...9a30828a0a9a30828 2020-06-30 Julian Kent - Add explicit matrix + scalar test
f3cf615 2020-06-30 Julian Kent - Do += -= and scalar *= /= in place
Within ekf2, optical flow messages (amongst others) are fused to the state estimates. It might occur that optical flow sensors report unreliable and unrealistic spikes. In that case, the state estimator went crazy so far and just ignored optical flow values from that moment on.
The common thread for all these spikes seems to be a too high integration time span. Therefore, this fix adds a simple logic that ignores unrealistically high integration time spans. As a threshold, 1 second was chosen.
Reported-by: Dominik Natter <dominik.natter@gmail.com>
If some bits are set but no topic was added, _subscriptions was null but
later accessed.
During normal use this only happens when switching between different
firmware versions with different SDLOG_PROFILE definition (with custom
config).
This fixes the corner case where a NAV_DELAY command changes the
validity of the next WP but not the rest of the triplet. The logic in
FlightTask was ignoring this change because the check was only based on
WP position change.
- ecl in PX4/Firmware (fff83fdee69789ec9da259b564bbfe67585a4b5f): a8bb8ea99f
- ecl current upstream: e4b44f704b
- Changes: a8bb8ea99f...e4b44f704be4b44f7 2020-06-23 PX4 BuildBot - Update geo_lookup WMM to latest Tue Jun 23 14:15:04 UTC 2020
4b746a3 2020-06-23 bresch - GPS Yaw: add consts and remove fusion starting message
2bafe9d 2020-06-22 bresch - GPS Yaw: wait to fuse at yaw at least once before declaring it faulty
51cd63d 2020-06-22 bresch - GPS Yaw: fall back to other yaw aiding source in case of bad data
fe2a9d3 2020-06-22 bresch - GPS Yaw: move isfinite checks in control.cpp
3c6790f 2020-06-22 bresch - GPS Yaw: Always reset Yaw when GPS Yaw fusion is starting
ff8b5ec 2020-06-21 kamilritz - Extract general functions into utils
fda30d8 2020-06-15 Daniel Agar - geo_lookup: expand latitude to +-80 degrees
109eca5 2020-06-15 Daniel Agar - geo_lookup: create simple python script to update tables
41b9e4f 2020-06-15 Daniel Agar - geo_lookup: move tables to separate file
- avoids the need for ekf2_timestamp publications by q and lpe
- adds logger to the lockstep cycle and makes it poll on ekf2_timestamps
or vehicle_attitude. This avoids dropped samples (required for replay).