bresch
5818974f0f
ekf: add range finder "faulty" status
...
When delclared faulty, the range finder cannot be used anymore
3 years ago
bresch
a3b2550f07
mc_auto: only check for offtrack, infront and behind in XY-plane
...
This fixes the issue when changing the altitude during a goto for
example, where the vehicle was going backwards and upwards to reach the
closest point to the line. Now the vehicle simply goes towards the
target waypoint.
3 years ago
alessandro
1febba315a
mantis: disable optical flow fusion in EKF2
...
Above grass fields I can frequently observe position
instabilities with the mantis due to the optical flow fusion.
Let's disable flow fusion for now.
3 years ago
Daniel Agar
0b9f60a037
drivers/rc_input: always provide RC_PORT_CONFIG parameter
...
- RC_PORT_CONFIG is disabled by default if the board doesn't have
CONFIG_BOARD_SERIAL_RC set
- allows user facing custom RC configuration that overrides board
defaults
3 years ago
Daniel Agar
97a75fc388
sensors: skip selection and failover checks during parameter update cycles
3 years ago
Beat Küng
b6607a7b78
battery_status: do not publish if no voltage channel is defined
...
This is the case for boards with digital readout, like v5x, but still
enable the battery_status module for external analog driver options.
An alternative would be to not run battery_status depending on config.
3 years ago
Nico van Duijn
10ad553f1d
v5x: add battery_status module to enable analog bat sensing
3 years ago
Beat Küng
28c27f1b9a
px4/fmu-v5x: add ADC_ADS1115_EN param to use external ADC
3 years ago
David Sidrane
fd1aa3cfb9
matek_gnss-m9n-f4:Use CONFIG_BOARD_SERIAL_GPSn for serial_passthru
3 years ago
David Sidrane
0c936e4fd2
serial_passthru:Move CONFIG_xxx to serial_passthru
3 years ago
Silvan Fuhrer
81b08a0168
FW Pos C: set position_sp type to position during VTOL backtransition
...
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
3 years ago
Silvan Fuhrer
1d6396b418
Navigator: VTOL: track virtual WP 1m ahead of vehicle during backtransition in Land mode
...
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
3 years ago
Jukka Laitinen
dcde0d0559
src/drivers/sw_crypto: Late initialize tomcypt
...
This saves a lot of flash space, in case functions from libtomcrypt
are not used (currently only RSA related).
When RSA is not used, the linker can now drop all libtomcrypt related things.
This is especially relevant for bootloaders using the SW crypto.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
3 years ago
Daniel Agar
a95da715d5
Jenkins: HIL remove airframe 4018 test
3 years ago
Beat Küng
86860808e3
ROMFS: set CA_* geometry params for some of the generic airframes
...
Not enabled, makes it easier to switch.
3 years ago
Beat Küng
a2ba613254
ROMFS: remove 4018 + 6003 ctrlalloc airframes
3 years ago
PX4 BuildBot
33ce1b9b64
Update submodule mavlink to latest Wed Feb 9 00:39:13 UTC 2022
...
- mavlink in PX4/Firmware (ed8c1dca2e792e95d9ab1ba72a22bc9658f10b79): 51abf3c82b
- mavlink current upstream: 311eee010b
- Changes: 51abf3c82b...311eee010b
311eee01 2022-02-04 Peter Barker - common.xml: deprecate SET_HOME_POSITION message (#1791 )
63d62522 2022-02-02 Julian Oes - minimal: add MAV_TYPE_WINCH (#1789 )
3 years ago
PX4 BuildBot
421ca2fc48
Update submodule sitl_gazebo to latest Wed Feb 9 00:39:03 UTC 2022
...
- sitl_gazebo in PX4/Firmware (a088277fe866860272f1ef21773f5be1b6832b11): 2750fe233c
- sitl_gazebo current upstream: 25138e803e
- Changes: 2750fe233c...25138e803e
25138e8 2021-07-16 Julian Oes - gimbal_controller: fix attitude status
3 years ago
Daniel Agar
b24aa071b6
Jenkins: hardware always dump pyserial debug (silently)
3 years ago
Daniel Agar
6686736cff
drv_pwm_output.h fix dshot cmd typo
3 years ago
Daniel Agar
86f81680fb
sensors: check uORB::SubscriptionData validity before use
3 years ago
Oleg Kalachev
21b78f9d05
Enable mpu9250’s magnetometer on fmu-v4
3 years ago
Steve Nogar
dce067df83
add configurable rtps rate parameter
3 years ago
Daniel Agar
133fe0cfb1
local_position_estimator: move to INS0 work queue (for significantly more stack)
3 years ago
Daniel Agar
be3da5089c
uORB: uORBDeviceNode use px4_cache_aligned_alloc
3 years ago
Viktor Vladic
f4d02a2937
MatekH743 board_id, usb vid/pid changes, and MPU6000 delay before transfer - not after ( #18733 )
...
* Make board_id compatible with ardupilot
* Initialize outputs for CAM1/CAM2 and Vsw pad
* Correct board type 1013 in bootloader to match AP
* Change usb vendor string to "Matek"
* Change cdcacm pid to 1013
* Comment out FLASH_BASED_PARAMS because of #15331
3 years ago
Julian Oes
490a0c473b
Rename vmount to gimbal
3 years ago
Julian Oes
853047c643
Mantis: use gimbal auto input
...
This allows RC and mavlink gimbal v2 input.
3 years ago
Julian Oes
39f0e97245
vmount: refactor for v2 auto input, test command
...
This is a bigger refactor of vmount to clean it up and plug some holes
in functionality.
The changes include:
- Fixing/simplifying the test command.
- Changing the dependencies of the input and output classes to just the
parameter list.
- Adding a separate topic to publish gimbal v1 commands to avoid
polluting the vehicle_command topic.
- Removing outdated comments and author lists.
- Extracting the gimbal v2 "in control" notion outside into control_data
rather than only the v2 input.
3 years ago
Julian Oes
f2216dff55
mavlink: don't send gimbal_device_attitude_status
...
If we receive gimbal_device_attitude_status by mavlink we should not
re-send it as we are already supposed to be forwarding mavlink traffic
from the gimbal to the ground station.
3 years ago
Julian Oes
7e7a99b542
mavlink: handle for GIMBAL_DEVICE_ATTITUDE_STATUS
...
That way we can log it later.
3 years ago
Daniel Agar
5b07398b3e
Tools/HIL/test_airframes.sh: only attempt setting first 3 MAV_x_CONFIG
...
- MAV_3_CONFIG doesn't exist
3 years ago
Daniel Agar
f9d87fd97a
sensors/vehicle_angular_velocity: improve error handling (especially during initial selection)
3 years ago
Daniel Agar
3a37fd92e6
Jenkins: HIL temporarily tolerate ERRORs during 'uorb top' (long running command)
...
- on older boards if the sensor auto cal completes while this is
running it causes a brief sensor timeout
3 years ago
Daniel Agar
052adfbfd9
borads: holybro_kakutef7 disable modules/events to save flash
3 years ago
Daniel Agar
3a741cb9c9
boards: bitcrazy_crazyflie disable gyro_fft to save flash
3 years ago
Thomas Debrunner
b4087ebd2b
mc_pos_control: increase the default crawl speed for three-stage-landing approach for a more robust landing detection
3 years ago
Matthias Grob
4ef8cead3d
mc_pos_control_params: correct crawl speed reference
3 years ago
Matthias Grob
1df9d6fca6
MulticopterLandDetector: fix crawl speed parameter fetching
3 years ago
Thomas Debrunner
fb8b9b647a
land-detector: switch to crawl speed for intent detection
3 years ago
Thomas Debrunner
2a6d9bc1dd
fligh-mode-manager: First implementation of a three-stage-landing for multirotos, in case LIDAR is available
3 years ago
Daniel Agar
893cdf8f38
ekf2: test external vision adjustments after lowering fake position fusion variance
3 years ago
Daniel Agar
6b1750d8be
ekf2: lower fake position observation variance when at rest
3 years ago
Daniel Agar
c028b964e2
bmm150: minor changes to match reference driver
3 years ago
Beat Küng
8b2016b4ed
fix protocol_splitter: increment i properly in scan_for_packets
...
This also guarantees that i is increased in every loop iteration.
Before it was possible to enter a busy loop.
3 years ago
Daniel Agar
cf3db0d313
mavlink: don't send_mission_current if mission invalid
3 years ago
Silvan Fuhrer
26dba1407b
Commander: VTOL quadchuate also triggers a RTL in Loiter and VTOL_Takeoff modes, not just in Mission ( #19123 )
...
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
3 years ago
JaeyoungLim
f82c722653
Publish correct orbit status with goto ( #19102 )
...
For fixedwings, the orbit status was publishing zero radius when a goto waypoint was being passed.
This commit corrects this by passing the default loiter radius as the guidance logic was using
3 years ago
bresch
917910f3e2
ekf: pass a float by copy instead of a constant ref
3 years ago
bresch
3077f27821
ekf: use float instead of Vector2f for innov gate in pos/vel fusion
...
We always use the same innovation gate for X and Y anyway
3 years ago