Commit Graph

41256 Commits

Author SHA1 Message Date
Daniel Agar 1c72f86761 Update src/drivers/imu/analog_devices/adis16470/ADIS16470.cpp
Co-authored-by: Kabir Mohammed  <kabir@corvus-robotics.com>
2022-08-16 08:40:43 -04:00
Daniel Agar 49d87f1907 adis16470: fix accel and gyro scaling 2022-08-16 08:40:43 -04:00
bresch 616b5689ba Python: move symforce to optional requirements
symforce requires python 3.8 which isn't available by default on ubuntu
18.04.
2022-08-15 21:14:07 -04:00
Silvan Fuhrer a7a8daaf4d ROMFS: tiltrotor sitl config: some small tuning improvements in hover
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-08-16 02:48:44 +02:00
Silvan Fuhrer 771dbf9395 ROMFS: tiltrotor sitl config: adapt CA params to new output indexes
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-08-16 02:48:44 +02:00
Silvan Fuhrer 09f83016c9 update sitl_gazebo (tiltrotor index fixes)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-08-16 02:48:44 +02:00
Junwoo Hwang d7a962b426 mavlink: fix PX4_DEBUG message formats 2022-08-12 09:43:12 +02:00
Junwoo Hwang 0c218e6628 atl/mantis-edu: enable mavlink ftp 2022-08-12 09:43:12 +02:00
Silvan Fuhrer ffb8fb4383 Allocation: add SteeringWheel type control surface
Directly use yaw controls for it, and don't add it to the allocation matrix,
as that would have an effect on rudder scaling if the wheel also would have
a yaw effectiveness.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-08-12 09:43:12 +02:00
Silvan Fuhrer 9e18b351bc Allocation: add Single Channel Aileron to CS types
This is the control surface type for airframes that have only a
single aileron servo or have the ailerons on a single output channel.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-08-12 09:43:12 +02:00
Silvan Fuhrer c6d1b1f50f Allocation: add A-tail servo type
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-08-12 09:43:12 +02:00
Beat Küng f454dcef6b ROMFS: set control allocation parameters for airframes
Removes some airframes:
- 1000_rc_fw_easystar.hil
- 10015_tbs_discovery
- 10016_3dr_iris
- 10018_tbs_endurance
- 13001_caipirinha_vtol
- 13002_firefly6
- 13003_quad_tailsitter
- 13004_quad+_tailsitter
- 13005_vtol_AAERT_quad
- 13006_vtol_standard_delta
- 13007_vtol_AAVVT_quad
- 13008_QuadRanger
- 13009_vtol_spt_ranger
- 13012_convergence
- 13050_generic_vtol_octo
- 14001_tri_y_yaw+
- 14002_tri_y_yaw-
- 15001_coax_heli
- 2105_maja
- 2200_mini_talon
- 3031_phantom
- 3032_skywalker_x5
- 3033_wingwing
- 3036_pigeon
- 3100_tbs_caipirinha
- 4003_qavr5
- 4009_qav250
- 4019_x500_v2
- 4030_3dr_solo
- 4031_3dr_quad
- 4051_s250aq
- 4072_draco
- 4080_zmr250
- 4090_nanomind
- 4100_tiltquadrotor
- 50003_aion_robotics_r1_rover
2022-08-12 09:43:12 +02:00
Beat Küng 4d60fadc05 ROMFS: set control allocation parameters for sitl airframes
Removes some airframes:
- if750a
- solo
- iris_ctrlalloc
- typhoon_h480_ctrlalloc
2022-08-12 09:43:12 +02:00
Beat Küng f2db7b8deb control_allocator: hide motor positions for fixed-wings
should not be set for now
2022-08-12 09:43:12 +02:00
Beat Küng 923a90d78b control_allocator: set default control surface type to (not set)
Before it was set to left aileron, but the torque values were all 0.
2022-08-12 09:43:12 +02:00
Beat Küng 720cf5a485 config: enable dynamic control allocation by default (SYS_CTRL_ALLOC=1) 2022-08-12 09:43:12 +02:00
Oleg 6ea3c6a7d2 mavlink_ftp: fix to correctly trim reply messages
Clear any not used payload data to correctly trim mavlink ftp message reply to avoid sending long ACK and NACK messages.
2022-08-12 08:53:33 +02:00
David Sidrane cd971948da NuttX Backport critical F7 Ethernet issues 2022-08-12 08:22:55 +02:00
Matthias Grob 1f81101994 mc_att_control_main: do not jump throttle scaling when taking off
2fbb70d9ca made the lowest possible
throttle value commanded by stick in Stabilized mode before taking off 0.
The real world problem with this is that when takeoff is detected then
the entire throttle scaling range jumps from
[0, MPC_MANTHR_MIN]
to [MPC_MANTHR_MIN, MPC_MANTHR_MIN].
As a result whenever MPC_MANTHR_MIN is not zero there is a thrust jump
on every takeoff just at the moment takeoff is detected even when the
stick is moved continuously.

Because of this I suggest to revert to having a higher throttle value
from the beginning on because it's less complicated and there's
no obvious value in starting out with zero thrust if anyways not
possible to go back to zero for safety once takeoff is detected.
2022-08-11 14:18:54 +02:00
Matthias Grob 5b1b6f6080 mc_att_control_main: use gradual() for throttle curve rescale without hover thrust 2022-08-11 14:18:54 +02:00
Matthias Grob 7cb6a47714 TIME_ESTIMATE_TO_TARGET: fill unsupported fields with value representing unavailability 2022-08-11 07:27:04 +02:00
bresch 7996a1a70f ekf2: reset ekf preflight checks on takeoff correctly
Using the control status flags isn't robust as this part of the code
runs at the EKF update rate while the in_air transition is don at the
prediction rate. It was then likely to miss the transition
2022-08-10 16:52:28 +02:00
marcirsch a8b342722e mavlink_main: Add TIME_ESTIMATE_TO_TARGET stream to config, onboard, and onboard_low_bandwidth modes
Signed-off-by: marcirsch <marcell@auterion.com>
2022-08-10 09:13:58 +02:00
marcirsch 4bf6ebf4c3 TIME_ESTIMATE_TO_TARGET: Populate TIME_ESTIMATE_TO_TARGET MAVLink message with the estimated time to RTL
mavlink_messages: Added newly created MAVLink stream
mavlink_main: Enabled stream

Signed-off-by: marcirsch <marcell@auterion.com>
2022-08-10 09:13:58 +02:00
Daniel Agar 7f2fea1cca mpu9250: try all I2C addresses if not manually specified 2022-08-09 13:06:40 -04:00
Jaeyoung Lim d4b77a6172 Update sitl gazebo submodule 2022-08-09 16:35:27 +02:00
Jaeyoung Lim ea5b1be2d4 Disable rear motors tilt for tiltrotor SITL airframe
This commit disables the rear motor tilt on the tiltrotor SITL airframe
2022-08-09 16:35:27 +02:00
Jukka Laitinen c7aaf52fd4 Double the allocated stack size of 64-bit NuttX built-in modules
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-08-09 08:08:54 +02:00
Daniel Agar 7c809f034d replay: ReplayEkf2 disable parameter auto save
- not needed and silences a startup error
2022-08-08 21:27:47 -04:00
Daniel Agar 34dee09b74 ekf2: replay fixes, don't use HRT for timeout checks
- this interferes with current ekf2 replay where the latest IMU sample
is effectively the current timestamp
2022-08-08 21:27:47 -04:00
Daniel Agar 1c49a4349f ekf2: force skip multi-EKF config if replay is enabled 2022-08-08 21:27:47 -04:00
Daniel Agar 66b55d9d0a ekf2: fix yaw estimator velocity accuracy
- additionally require GPS speed accuracy is within EKF2_REQ_SACC
2022-08-08 21:27:01 -04:00
bresch d9d127a237 lightware dist sensor: set min range based on datasheet 2022-08-08 19:32:44 -04:00
Daniel Agar 0bce1ef573 drivers/imu: new TDK IIM-42652 IMU support 2022-08-08 13:51:39 -04:00
Thomas Stastny 0ea347a5c9 fw pos ctrl: fix the touchdown offset on flare, and nudge the wheel directly 2022-08-08 09:32:44 +02:00
Thomas Stastny 02d7a46025 fw pos ctrl: increase landing nudge rate 2022-08-08 09:32:44 +02:00
Beat Küng 3e68870547 gtest: update to version 1.12.1
Fixes the error
googletest-src/googletest/src/gtest-death-test.cc:1283:24: error: ‘dummy’ may be used uninitialized [-Werror=maybe-uninitialized]
with GCC 11
2022-08-08 07:43:42 +02:00
Daniel Agar bce4237963 move ekf2 Matrix helper utilities to mathlib 2022-08-05 09:58:07 -04:00
Silvan Fuhrer 6ebc88fed7 ROMFS: vtol_defaults: reduce aggressiveness around roll and yaw axis
For most VTOLs the param defaults for the agressiveness of the MC attitude controller
are too high, as VTOLs usually have high intertia and lot af drag due to wings and
can thus not rotate as fast as MCs.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-08-05 14:11:59 +02:00
Silvan Fuhrer a064164c14 FW pos C params: add param group FW Auto Landing
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-08-05 14:11:59 +02:00
Silvan Fuhrer b039ae1614 FW pos c params: change grouping of some clearly longitudinal params to TECS
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-08-05 14:11:59 +02:00
Silvan Fuhrer 45073f000a FW Position control: reduce defaults for max pitch
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-08-05 14:11:59 +02:00
Silvan Fuhrer d04f21aa16 FW attitude controller: reduce FW_MAN_P_MAX from 45 to 30
45° is a very large pitch angle, and for me 30° is much more reasonable for
a default value.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-08-05 14:11:59 +02:00
Silvan Fuhrer 828992adf7 increase default of MPC_Z_VEL_MAX_DN and MPC_Z_V_AUTO_DN from 1 to 1.5
I think most vehicle can safely decend with at least 1.5m/s, and having this
value too low makes Descents/Landings/RTLs unnecessary long.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-08-05 14:11:59 +02:00
Silvan Fuhrer c42667ac64 ROMFS: vtol_defaults: remvoe custom NAV_ACC_RAD, leave at param default (10)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-08-05 14:11:59 +02:00
Silvan Fuhrer 4614c1a0b4 ROMFS: vtol_defaults: increase default hover speeds
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-08-05 14:11:59 +02:00
Silvan Fuhrer 0d10491b89 ROMFS: vtol_defaults: remove MPC_TKO_SPEED from VTOL defaults
The VTOL default was set to 1, while the param default is 1.5.
I don't see why it shuold be a different default for VTOLs and thus remove it.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-08-05 14:11:59 +02:00
Matthias Grob 87cbda1992
FlightTaskOrbit: parameterize hardcoded maximum radius (#20012) 2022-08-05 09:19:32 +02:00
Daniel Agar dfdfbbfa9c
msg/vehicle_odometry.msg: simplify covariance handling and update all usage (#19966)
- replace float32[21] URT covariances with smaller dedicated position/velocity/orientation variances (the crossterms are unused, awkward, and relatively costly)
 - these are easier to casually inspect and more representative of what's actually being used currently and reduces the size of vehicle_odometry_s quite a bit
 - ekf2: add new helper to get roll/pitch/yaw covariances
 - mavlink: receiver ODOMETRY handle more frame types for both pose (MAV_FRAME_LOCAL_NED, MAV_FRAME_LOCAL_ENU, MAV_FRAME_LOCAL_FRD, MAV_FRAME_LOCAL_FLU) and velocity (MAV_FRAME_LOCAL_NED, MAV_FRAME_LOCAL_ENU, MAV_FRAME_LOCAL_FRD, MAV_FRAME_LOCAL_FLU, MAV_FRAME_BODY_FRD)
 - mavlink: delete unused ATT_POS_MOCAP stream (this is just a passthrough)

Co-authored-by: Mathieu Bresciani <brescianimathieu@gmail.com>
2022-08-04 12:55:21 -04:00
bresch 61f390b0dd ekf2_test: fix height offset compensation after origin reset 2022-08-04 16:50:31 +02:00