because we need to have SITL simulation as realistic as possible
compared to a real flight with default settings such that we
either fix the problems or adjust the defaults already in SITL testing.
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