Commit Graph

41862 Commits

Author SHA1 Message Date
Daniel Agar 1aa8ec4537
drivers: initial VectorNav (VN-100, VN-200, VN-300) support 2023-01-20 19:09:30 -05:00
Daniel Agar bd9d09663f
commander: avoid uint64 timestamp implicit float conversions
- 64 bit time in microseconds stored in a 32 bit float quickly becomes problematic
 - fixes https://github.com/PX4/PX4-Autopilot/issues/20944
2023-01-19 17:48:40 -05:00
Daniel Agar 3822ef1519 boards: update all in tree bootloaders 2023-01-19 17:25:39 -05:00
PX4 BuildBot c4127813b3 Update submodule sitl_gazebo-classic to latest Thu Jan 19 12:38:59 UTC 2023
- sitl_gazebo-classic in PX4/Firmware (f3cdf70732): 1a725dd858
    - sitl_gazebo-classic current upstream: 9343aaf4e2
    - Changes: 1a725dd858...9343aaf4e2

    9343aaf 2023-01-15 JaeyoungLim - Fix model prefix for user camera plugin (#948)
e5836d3 2023-01-13 Simone - Added robot namespace to the model (#941)
2023-01-19 12:33:53 -05:00
PX4 BuildBot d2240c0c48 Update submodule nuttx to latest Thu Jan 19 12:39:05 UTC 2023
- nuttx in PX4/Firmware (0e2eed62f9a9b44cefc9765fd21aac1a368e4314): d43edd7879
    - nuttx current upstream: f80785664f
    - Changes: d43edd7879...f80785664f

    f80785664f 2023-01-16 Julian Oes - [FIX] Add missing define condition
1751c2c7cb 2023-01-16 Julian Oes - [BACKPORT] stm32h7: add SMPS PWR option for STM32H7X7
2023-01-19 12:33:27 -05:00
PX4 BuildBot 8d6a336b2c boards: update all NuttX defconfigs 2023-01-19 12:32:57 -05:00
PX4 BuildBot 898dbb96b4 update all px4board kconfig 2023-01-19 12:32:09 -05:00
Silvan Fuhrer f3cdf70732 VTOL: Quad-chute: rework loss of altitude condition
Previously the condition was based on hard coded height rate estimate and
setpoint values and an altitude error threshold. That showed to be leading
to false positives when the vehicle doesn't tightly follow the altitdue
ramp given by TECS to achieve a new altitude setpoint, and has become
completely infeasibly with the latest TECS rework that leads to non-ramped
altitude setpoint changes in the tecs_status message.
The new check no longer checks the altitude error but only the height rate
instead. It begins to integrate the height rate error once it detects an
uncommanded descend condition (height rate negative while setpoint is
positive). Integral threshold can be tuned by user (VT_QC_HR_ERROR_I).

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-19 09:36:09 +01:00
Silvan Fuhrer 36dc75bedf VTOL: introduce new quad-chute check for altitude loss during front transition
By default the threshold is set to 10m.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-19 09:36:09 +01:00
Beat Küng 98705ced2f lightware_laser_i2c: fix unreliable startup detection
In rare occasions asking for the protocol values after setting it returned
[0, 0]. I did not see any documentation for having to wait, but adding a
short wait period fixes it.
2023-01-18 23:02:56 -05:00
modaltb 05d828642d
boards/modalai: FCv1 DMA optimiziation for 2Mbit UART (#20956)
- disable unused SPI3 DMA
- enable USART2 RX/TX, UART5/6 TX, UART4 RX
2023-01-18 23:01:57 -05:00
Daniel Agar 9d7c4b8273
boards: ark_can-flow_default disable sensors/vehicle_acceleration to save flash 2023-01-18 22:58:19 -05:00
Daniel Agar ffa9d61065
boards: px4_sitl_default include gz_bridge by default 2023-01-18 22:56:17 -05:00
Daniel Agar 2b5722786b cmake: fix and update packaging 2023-01-18 22:51:12 -05:00
alexklimaj 5eb13e4448 ARKV6X bootloader init all pwm outputs as input pulldown 2023-01-18 21:52:11 -05:00
alexklimaj 7c2da8d1ef Enable ARKV6X SPIX SYNC, enable icm426889 and iim42652 CLKIN 2023-01-18 21:52:11 -05:00
Daniel Agar 967c37ac17
boards: mro_pixracerpro_default disable examples/fake_gps to save flash 2023-01-18 21:44:09 -05:00
Daniel Agar 6a64e74ef3
icm42688p: fix register bank selection
* icm42688p: clear INT_CONFIG1 INT_ASYNC_RESET for proper INT1/INT2 pin operation
2023-01-18 11:08:03 -05:00
Daniel Agar 95300d5637
ekf2: refactor output predictor to class
- refactor all EKF backend output predictor pieces into new OutputPredictor class
 - output states are now calculated immediately with new high rate IMU rather than after EKF update
 - IMU delayed sample is passed as around as control data to avoid storing an extra copy and make the requirement clear
2023-01-18 10:59:34 -05:00
murata c054ca20cc logger: Add arm to shutdown 2023-01-18 07:47:36 +01:00
Julian Oes 35d6b734f5 perf: avoid leaks in dtor
From what address sanitizer tells me, we need to tell delete what type
it is deleting.

Signed-off-by: Julian Oes <julian@oes.ch>
2023-01-17 21:20:51 -05:00
modaltb 8123090571
boards: modalai FCv2 BSP updates (#20958)
- FCv2 MR1
 - configure TELEM2 for VOXL use case by default
 - use ICP201XX baro by default
2023-01-17 21:20:16 -05:00
Siddharth Bharat Purohit 1c63d5666b
boards: add support for CubeOrange+ (#20304)
Co-authored-by: Julian Oes <julian@oes.ch>
2023-01-17 20:55:57 -05:00
Daniel Agar 71d916dbcd ekf2: PreFlightChecker fix vel_ne_innov_lpf index 2023-01-17 13:03:38 -05:00
modaltb 6f718cd48d
drivers/actuators/modalai_esc: update to use mixer module and control allocator properly
- update motor mapping to use new UART_ESC_FUNC* auto generated params
 - add support for actuator_test msg to support Actuator Testing in QGC
 - modalai_fc-vX targets start driver if configured
 - keep track of ESC spin direction in own param
 - set ramp up param in MixerOutput to false
2023-01-16 21:46:37 -05:00
Beniamino Pozzan 2a64145dcd microdds_client: add _subs reset method to allow reconnections
Signed-off-by: Beniamino Pozzan <beniamino.pozzan@phd.unipd.it>
2023-01-16 21:43:49 -05:00
Alex Klimaj 00bfd5436a
ekf2: increase optical flow preflight check innovation limit (#20940) 2023-01-15 17:52:12 -05:00
Daniel Agar 6991ac014c
rename 'gazebo' simulation to 'gazebo-classic' (#20936)
- use `gazebo-classic` everywhere consistently referring to the original Gazebo (eg version 9,10,11)
   - additional `gazebo_*` helper targets added for compatibility, but warn about deprecation and tell you the new target naming
 - use `gz` everywhere when referring to Gazebo (aka Ignition Gazebo or new Gazebo)
2023-01-15 11:36:12 -05:00
Daniel Agar 6605378d0d
boards: px4_fmu-v6c_default disable systemcmds/serial_test to save flash 2023-01-14 19:24:47 -05:00
Daniel Agar 30a240a7a4
boards: modalai_fc-v2_default disable examples/fake_gps to save flash 2023-01-14 19:23:19 -05:00
Daniel Agar 52b9b9ba2f
simulation: restore 'gazebo' alias for 'gazebo_iris'
- only create helper targets if Gazebo 11 found on system
2023-01-14 17:03:18 -05:00
murata 82ecbccd85 distance_sensor: Add TF02 Pro I2C 2023-01-14 09:28:33 -05:00
Jukka Laitinen 2985b5b9c2 msg/ActuatorTest.msg: Use default queue size the same as MAX_NUM_MOTORS
For the esc_calibration code, the actuator test is published for each motor
in a row. If the orb queue size is too small, messages are lost and not
received in mixer_module.

Set the default orb queue size of ActuatorTest high enough to keep the commands
for all motors in the queue.

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2023-01-14 09:19:10 -05:00
Daniel Agar 45912066d2 fix copyright header year range 2023-01-14 09:16:16 -05:00
Daniel Agar 674a59e48f
ekf2: new gyro bias limit parameter EKF2_GYR_B_LIM
- default is now a more conservative 0.15 rad/s (~8.6 deg/s) instead of the previous hardcoded 20 deg/s
2023-01-14 09:15:46 -05:00
Andrew Wilkins 22f7d913bd
rover_pos_control: thrust normalization for joystick input (#20885) 2023-01-13 20:11:39 -05:00
Peter van der Perk 7d92d4893e VSCode C/C++ include path and config hints 2023-01-13 20:03:53 -05:00
Daniel Agar c97381c97f mavlink: streams SCALED_IMU fix gyro dt 2023-01-13 20:01:41 -05:00
Daniel Agar 5942194c66 iridiumsbd: advertise status topic immediately and log by default 2023-01-13 20:01:03 -05:00
Eric Katzfey ac80dcd7a8
Voxl2: add qurt i2c driver support and first i2c driver voxlpm 2023-01-13 19:59:41 -05:00
Julian Oes 1e93ae3148 jsbsim: take FG_BINARY env var into account
This is just to match the docs.

Signed-off-by: Julian Oes <julian@oes.ch>
2023-01-13 17:07:20 -05:00
Silvan Fuhrer 7c766692c4 FW Att and Rate Controller, Tailsitter: fix tailsitter frame transformations
Strictly follow the following convention for tailsitter:
FW Attitude and FW rate controller always operate in the FW frame, meaning that roll is
roll in FW, which for tailsitter means around the yaw axis in the body frame. The interfaces
between modules is though always in body frame.

That enables us to do the axis transformations for tailsitter, that are currently distributed
all over the controller (attitude, rate, vtol module), only at the input and output data of modules.

Side effect is that the FW rate control tuning gains meanings change: while before the roll gains
where meant for the body axis, they are now always applied for the FW roll axis (also in hover). So
the naming now is correct for FW, while before it was for Hover.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-13 18:18:11 +01:00
Silvan Fuhrer edb59a9000 VTOL: improve QC parameter meta data
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-13 19:02:21 +03:00
Silvan Fuhrer 544be72503 VTOL: improve messaging for quad-chute triggered error messages
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-13 19:02:21 +03:00
Silvan Fuhrer 623c1418bb Commander: improve messaging for vtol fixed-wing system failure arming check
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-13 19:02:21 +03:00
Silvan Fuhrer 303b879748 VTOL/Commander: rename transition_failsafe to vtol_fixed_wing_system_failure
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-13 19:02:21 +03:00
Silvan Fuhrer 2d4be68e00 VTOL: reset quad-chute failsafe flag when user triggeres a new transition to FW
This failsafe flag is currently used for not allowing to re-transition to FW, as well
as disabling pusher assist in hover. Till now it was only possible to reset it with
a commanded transition to MC, which many ground station interfaces didn't allow
as the system, after a quad-chute, already was in MC mode.
Hereby it is changed to reset when a new transition to FW is triggered (either via
RC switch or MAVLink command). It is the users responsibility to assess the situation
after a quad-chute happened to try to transition to FW again, manually proceed/land
the vehicle in MC, or let it finish the defined behavior after a quad-chute.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-13 19:02:21 +03:00
Silvan Fuhrer 8a680a3153 VTOL: fix quad-chute max altitude limit
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-13 19:02:21 +03:00
bresch 3d50a7ce44 CAL_MAG_SIDES: do not save with factory cal 2023-01-13 10:48:01 -05:00
bresch 3d73e273e6 MAG_SIDES: don't spam user to not change parameter
otherwise this will always show up on every boot if factory calibration
was done in an earlier release
2023-01-13 10:48:01 -05:00