Commit Graph

42461 Commits

Author SHA1 Message Date
Silvan Fuhrer 2a48c1cb18 boards: disable gyro fft module for v4 to safe flash
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-06-19 16:22:42 -04:00
Beat Küng 65ad6afb08 Micro-XRCE-DDS-Client: update submodule
Go get https://github.com/eProsima/Micro-XRCE-DDS-Client/pull/359.
2023-06-19 16:05:36 -04:00
Silvan Fuhrer 4632fbd600 FWRateController: use param find for VT_DIFTHR_EN as pure FW build doesn't have VTOL module built
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-06-19 10:59:20 +02:00
Matthias Grob 69aebe650b FixedwingRateControl: rework VTOL differential thrust saturation
Co-authored-by: Silvan Fuhrer <silvan@auterion.com>
2023-06-19 10:59:20 +02:00
Matthias Grob 53b9e66c66 RateControl: allow setting individual saturation flags
This helps for more complicated cases where certain axes are controlled
through and get feedback from a different allocator.
2023-06-19 10:59:20 +02:00
Beniamino Pozzan 957a06a780 Fix enum for COM_RC_IN_MODE in failsafe
add enum RcInMode

Signed-off-by: Beniamino Pozzan <beniamino.pozzan@phd.unipd.it>
2023-06-19 08:04:43 +02:00
Niklas Hauser 8fe65c6722 Driver: Refactor MCP23009 GPIO expander into uORB driver 2023-06-19 07:58:21 +02:00
Konrad 3303323971 mavlink stream: Heartbeat system status should neglect the actuator_armed.lockdown flag in HIL, since this is always enabled for HIL. 2023-06-16 14:21:32 +02:00
Matthias Grob 053d3020b0 esc_calibration: handle timeout wraps better
Co-authored-by: Beat Küng <beat-kueng@gmx.net>
2023-06-16 12:05:47 +02:00
Matthias Grob cfb24869e9 esc_calibration: allow to calibrate ESCs without battery detection
Before this the ESC calibration aborts if battery detection doesn't work.
The problem is if the user still connects the battery as he gets instructed
and the calibration aborts then the ESCs are in calibration mode and
after abortion calibrate to the wrong value.

Also I realized there's no additional safety by aborting the calibration
if the battery cannot be detected during the timeout because a pixhawk
board without power module will report a battery status from the
ADC driverand in it that no battery is connected which is the best
it can do. In this situation the motors will still spin if the
ESCs are powered.
2023-06-16 12:05:47 +02:00
Matthias Grob 4396b6e9f6 esc_calibration: adjust timing to work with all tested ESCs
Some ESCs e.g. Gaui enter the menu relatively quickly if the
signal is high for too long. To solve that it's kept high shorter.
Also all tested ESCs detect the low signal within a shorter time
so no need to wait longer.
2023-06-16 12:05:47 +02:00
Matthias Grob 6929493134 esc_calibration: Improve readability and robustness
- Change timings for a more reliable calibration.
- Make sure there's an error message when battery measurement is not
available also when it gets disabled after system boot in the power
just above the calibration button.
- Safety check if measured electrical current goes up after issuing the
high calibration value for the case the user did not unplug power
and the detection either fails or is not enforced.
2023-06-16 12:05:47 +02:00
Matthias Grob a28ad8e845 mixer_module: consistent PWM/oneshot calibration range 2023-06-16 12:05:47 +02:00
Matthias Grob 1ceca8f2cf actuator_test: condition order refactoring 2023-06-16 12:05:47 +02:00
Matthias Grob ffe0ec27e6 Unify MixingOutput constructor calls
to make them easy to search for and check the arguments.
2023-06-16 12:05:47 +02:00
Silvan Fuhrer fc357921fd navigator: send commands to anyone listening
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-06-12 09:41:28 +02:00
Junwoo Hwang 9b95330efc Github Issue: Replace Bug report to YAML 2023-06-09 21:18:28 -04:00
Junwoo Hwang 6b1f805b15 Issue Template: Move Feature request to YAML 2023-06-09 21:18:28 -04:00
Junwoo Hwang 89e8ba0b53 Issue Template: Switch to YAML for direct links 2023-06-09 21:18:28 -04:00
PX4 BuildBot bbc6ed43bd Update submodule sitl_gazebo-classic to latest Sat Jun 10 00:39:02 UTC 2023
- sitl_gazebo-classic in PX4/Firmware (f9510557a6): 2e3ed9bfb0
    - sitl_gazebo-classic current upstream: 0d53638452
    - Changes: 2e3ed9bfb0...0d53638452

    0d53638 2023-05-23 JaeyoungLim - Fix force visualization feature (#985)
9bfecb6 2023-05-22 JaeyoungLim - Fix readme displayed in github (#984)
2023-06-09 21:17:46 -04:00
alexklimaj 51a4eafe0c ARKV6X sync with FMUV6X 2023-06-09 21:17:12 -04:00
Matthias Grob 94d2140a4f mixer_module: remove unnecessary init state
That state only delayed the first arming by 50 miliseconds.
Was presumably a workaround for some issue very very early on.
See cc452834c0
2023-06-09 21:15:08 -04:00
Matthias Grob 0f256718d3 mixer_module: correct pwm ramp
Before:
When the mixed throttle for the motor was exactly zero the ramp went
from the disarmed PWM value to the minimum PWM value.

When the throttle was even just slightly different from zero the ramp
made a jump up to the commanded throttle scaled between
disarmed PWM and maximum PWM, then ramped between
disarmed PWM and minimum PWM and at the end jumped up again to
the commanded throttle scaled between minimum PWM and maximum PWM.

After:
The ramp goes from disarmed PWM value to the the
commanded throttle scaled between minimum PWM and maximum PWM.
If the commanded throttle changes during the ramp then the scale and
hence also end value of the ramp changes.
2023-06-09 21:15:08 -04:00
Mathieu Bresciani 24de623989
EKF2: Zero gyro update (#21691)
When at rest, directly fuse the gyro data as an observation of its bias.
This allows to strongly observe the gyro biases without having to fuse a
constant heading that makes the ekf too confident about its heading.
2023-06-09 21:13:18 -04:00
Beat Küng c95539e8ce boards: increase init stack size by 150B
External airframes need a bit more stack due to nested configs.
2023-06-09 21:11:11 -04:00
Beat Küng 7230a6dd8e commander: add option to exclude mag to param SYS_FAC_CAL_MODE 2023-06-09 21:05:40 -04:00
bresch 8b67fa91a1 factory cal: exclude _PRIO params 2023-06-09 21:05:40 -04:00
alessandro f9510557a6 always trigger all cameras 2023-06-09 13:17:45 +02:00
Morten Fyhn Amundsen 135f02679a ekf2: Fix description of EKF2_HDG_GATE 2023-06-09 11:52:55 +02:00
alexklimaj c3db4f57df Subscribe to all intances of gps_inject_data and mirror uavcan rtcm pub mirror gps driver 2023-06-09 14:51:28 +12:00
alexklimaj 5b8ae69f47 uavcan rtcm set max num injections 2023-06-09 14:51:28 +12:00
alexklimaj acd19a0520 Ublox add UBX-RXM-RTCM for RTCM input status 2023-06-09 14:51:28 +12:00
Beat Küng f119cca3b3 logger: restart on file write error
This can also happen if the maximum file size is reached.
2023-06-08 09:52:49 +02:00
Hamish Willee ea61d74c17
ADS1115: update docs (#21638) 2023-06-08 08:55:31 +02:00
mcsauder 1707805ed2 Remove the simulator SIH module from fmu-v5x test build and the fixedwing autotune module from the fmu-v5 test build to meet flash constraints. 2023-06-07 12:07:29 -04:00
mcsauder af44da25f0 Use accel of the same instance or primary baro for gyro instances that do not have valid temperature readings in temperature calibration data, use primary baro for magnetometers without valid temperature. 2023-06-07 12:07:29 -04:00
mcsauder b8ad9bdbe5 Add magnetometer thermal compensation. 2023-06-07 12:07:29 -04:00
oneWayOut 6ee2d796ea delete unused ECL_LIB_GIT_VERSION
Since 'ecl' is nomore a git submodule, code lines related to
'ECL_LIB_GIT_VERSION' could be deleted
2023-06-06 11:24:49 -04:00
Matthias Grob f4de43a10b PULL_REQUEST_TEMPLATE: fix typo 2023-06-06 17:22:33 +02:00
Matthias Grob b625e43566 rc_update: throttle trim centering fix for reverse channel
The entire logic did not work for the case when the throttle channel is
reversed because then QGC sets trim = max for that channel and
the result is only half the throttle range.
2023-06-06 17:22:33 +02:00
Julian Oes cd485b3a13 lights: Add LP5562 RGBLED driver
This adds support for the TI LP5562 RGB LED driver.

Things to note:
- The driver is initialized in simple PWM mode using its internal clock,
  for R,G,B, but not for W(hite).
- The chip doesn't have a WHO_AM_I or DEVICE_ID register to check.
  Instead we read the W_CURRENT register that we're generally not using
  and therefore doesn't get changed.
- The current is left at the default 17.5 mA but could be changed using
  the command line argument.

Datasheet:
https://www.ti.com/lit/ds/symlink/lp5562.pdf

Signed-off-by: Julian Oes <julian@oes.ch>
2023-06-06 13:12:44 +12:00
Eric Katzfey c468266b27
boards: Update modalai fcv2 board support (#21653)
* Removed obsolete voxl2-io directory
* Updated support for ModalAI FC v2 board
* Added UAVCAN back in and removed local position estimator and attitude estimator Q that are no longer supported.
* Removed unneeded IMU drivers
2023-06-05 12:42:46 -04:00
bresch 5233b33242 update change indicator 2023-06-05 11:58:42 -04:00
bresch 403a6310c4 gnss yaw: compare auto-generated Jacobian against autodiff 2023-06-05 11:58:42 -04:00
bresch c6b259d5f6 yaw_fusion: compare auto-generated Jacobian against autodiff 2023-06-05 11:58:42 -04:00
bresch d4528dc53a sideslip: compare auto-generated Jacobian against autodiff 2023-06-05 11:58:42 -04:00
bresch e7c4a22be8 mag_3d: compare auto-generated Jacobian against autodiff 2023-06-05 11:58:42 -04:00
bresch c6f1a63659 opt_flow: compare auto-generated Jacobian against autodiff 2023-06-05 11:58:42 -04:00
bresch d03f242c04 DCM: use simplified conversion from unit quaternion
This is exactly equivalent for a unit quaternion (and only unit
quaternions should be used to encode a rotation)
2023-06-05 11:58:42 -04:00
bresch 9d7abf2552 ekf2: symforce - use builtin Rot3 and Quaternion operations 2023-06-05 11:58:42 -04:00