Peter Barker
e26ee85cf6
AP_RangeFinder: move enabling of specific rangefinders into linux hwdef
2025-02-19 15:42:52 +11:00
Peter Barker
0feb2d2f53
AP_HAL_Linux: move enabling of specific rangefinders into linux hwdef
2025-02-19 15:42:52 +11:00
Peter Barker
052914c38f
AP_HAL_Linux: move analogue battmonitor configs into linux hwdef
2025-02-19 15:42:52 +11:00
Peter Barker
98570f6456
AP_HAL: move analogue battmonitor configs into linux hwdef
2025-02-19 15:42:52 +11:00
Peter Barker
d22346c3f6
AP_BattMonitor: move analogue battmonitor configs into linux hwdef
2025-02-19 15:42:52 +11:00
Peter Barker
5341690431
AP_Notify: use linux hwdefs to define AP_Notify information
2025-02-19 15:42:52 +11:00
Peter Barker
e6d5efe456
AP_HAL_Linux: use linux hwdefs to define AP_Notify information
2025-02-19 15:42:52 +11:00
Peter Barker
5a60fc1faf
AP_HAL: use linux hwdefs to define AP_Notify information
2025-02-19 15:42:52 +11:00
Peter Barker
dddb4583a6
AP_InertialSensor: start tidying Linux GPIO
2025-02-19 15:42:52 +11:00
Peter Barker
a8374a28f3
AP_HAL_Linux: start tidying Linux GPIO
2025-02-19 15:42:52 +11:00
Peter Barker
6d1cea44dd
AP_HAL: start tidying Linux GPIO
2025-02-19 15:42:52 +11:00
Peter Barker
eaf0feef44
AP_HAL_Linux: specify Linux SPI devices in hwdefs
2025-02-19 15:42:52 +11:00
Peter Barker
d60a7e5f93
AP_HAL_Linux: factor functionality in hwdef.py classes
2025-02-19 15:42:52 +11:00
Peter Barker
0c0278a70d
AP_HAL: factor functionality in hwdef.py classes
2025-02-19 15:42:52 +11:00
Peter Barker
51729e62a5
AP_HAL_ChibiOS: factor functionality in hwdef.py classes
2025-02-19 15:42:52 +11:00
Peter Barker
d0510b0a26
AP_HAL_ChibiOS: chibios_hwdef.py: inherit from hwdef.py
2025-02-19 15:42:52 +11:00
Peter Barker
6004ed44c7
AP_HAL_Linux: add and use linux_hwdef.py
...
like chibios_hwdef.py - but for Linux
2025-02-19 15:42:52 +11:00
Peter Barker
7ce9ec2c61
AP_HAL: add and use linux_hwdef.py
...
like chibios_hwdef.py - but for Linux
2025-02-19 15:42:52 +11:00
Peter Barker
d31889854c
chibios_hwdef.py: prune out unused hal.i2c_mgr parsing code
...
we have GET_I2C_DEVICE now-adays
2025-02-19 15:42:52 +11:00
Henry Wurzburg
984409ca82
RC_Channel: add AUTOLAND AUX Function
2025-02-19 10:51:25 +11:00
Randy Mackay
ebbf3998b6
AP_Proximity: add Hexsoon radar support
2025-02-18 16:38:12 +09:00
Randy Mackay
7fbad0bea3
AP_Arming: integrate NanoRadar to RadarCAN rename
2025-02-18 16:38:12 +09:00
Randy Mackay
0abb0a70f0
AP_RangeFinder: integrate RadarCAN rename
2025-02-18 16:38:12 +09:00
Randy Mackay
4f3981ce27
AP_CANManager: rename NanoRadar to RadarCAN
2025-02-18 16:38:12 +09:00
Iampete1
9da6be2ef8
RC_Channel: Document EKF lane switch and yaw reset aux functions.
2025-02-18 14:19:51 +09:00
Thomas Watson
7a6861e28d
AP_Filesystem: FATFS: drop tty check logic
...
In Standard C, the first three file descriptors are usually standard in,
out, and error. However, ArduPilot doesn't have a concept of this and
other backends (such as LittleFS) don't bother to reject them.
Remove this logic to simplify implementation and allow use of more open
files.
2025-02-18 12:33:37 +11:00
Peter Barker
5fcac2b304
SITL: add instructions for testing MaxSonarI2CXL in SITL
2025-02-18 11:34:10 +11:00
Peter Barker
fd1ade76ca
SITL: clamp rangefinder distance to 0m
...
our starting positions are often underground
2025-02-18 11:34:10 +11:00
Peter Barker
e348c6e7a3
AP_Rangefinder: avoid OwnPtr for MaxSonarI2CXL I2CDevice
2025-02-18 11:34:10 +11:00
abaghiyan
9893017f3c
AP_TECS: Corrected formula for _TASmin according to fix in formula for the load factor
...
To connect loadFactor to airspeed we can use formula of balancing between lift force and gravity force:
liftForce = loadFactor * gravityForce; on the other hand lift force can be expressed as
liftForce = 0.5 * lifCoefficient * airDensity * sq(airspeed) * referenceArea; minimum airseepd is at loadFactor = 1
and lift force only balances the gravit force, so gravity force (which is same as lift force at minimum airspeed) with minimum airspeed can be expressed as
gravityForce = 0.5 * lifCoefficient * airDensity * sq(airspeed_min) * referenceArea; substituting gravit force in previous formula gives us
0.5 * lifCoefficient * airDensity * sq(airspeed) * referenceArea = loadFactor * 0.5 * lifCoefficient * airDensity * sq(airspeed_min) * referenceArea;
from where we get:
loadFactor = sq(airspeed / airspeed_min); and_TASmin should be
_TASmin *= safe_sqrt(_load_factor);
2025-02-18 10:53:06 +11:00
SULILG
59e0f5cc84
AP_HAL_ChibiOS : add SULILGH7 board
2025-02-17 19:50:16 +11:00
Iampete1
494af643b5
GCS_MAVLink: move from MAV_MODE
enum to uint8_t
2025-02-17 17:20:24 +11:00
Iampete1
a74f0b35c7
RC_Channel: add docs for copter inflight trim
2025-02-17 17:15:10 +11:00
Thomas Watson
ec7ece3a4d
AP_Filesystem: littlefs: drop singleton
2025-02-17 16:33:51 +11:00
Thomas Watson
ca3c2c7c72
AP_Logger: File: take advantage of new optimal fsync API
...
Now FATFS will always sync on 4K boundaries even if it gets misaligned
due to a short or forced write.
LittleFS behavior is verified identical.
2025-02-17 16:33:51 +11:00
Thomas Watson
ed2c42ede2
AP_Filesystem: new API for performing optimal fsyncs
2025-02-17 16:33:51 +11:00
Thomas Watson
182646a7e4
AP_Filesystem: littlefs: debug warn of misaligned fsyncs
2025-02-17 16:33:51 +11:00
Randy Mackay
a6c2c1527b
AP_Mount: CADDX RC rate control fix
2025-02-17 13:39:44 +09:00
Shiv Tyagi
3d96c7e419
AP_HAL_ChibiOS: create and use AP_PERIPH_NETWORKING_ENABLED
2025-02-17 09:55:51 +11:00
Shiv Tyagi
15376a4908
AP_HAL_ChibiOS: replace AP_PERIPH_AIRSPEED_ENABLED with HAL_PERIPH_ENABLE_AIRSPEED
2025-02-16 10:11:10 +11:00
Thomas Watson
fb8f3488d5
AP_Filesystem: littlefs: fix lseek
...
lseek must return the current file position. Previously, the littlefs
version always returned 0, which broke terrain I/O as it checks that the
position returned is the one it seeked to. Fix to return the current
position, which is correctly returned from littlefs.
This problem was originally and incorrectly diagnosed as an issue with
littlefs seeking past the end of the file, but this functionality works
fine and fixing the incorrect return completely fixes terrain.
Terrain functionality was verified using `TERRAIN_DEBUG` on
KakuteH7Mini-Nand running sim on HW. Terrain data is correctly
downloaded from the GCS and loaded from the filesystem after reboot.
2025-02-14 13:29:12 +01:00
Andrew Tridgell
f1a7abb31b
AP_BLHeli: fixed documentation for SERVO_BLH_3DMASK and SERVO_BLH_RVMASK
...
they can be combined on both BLHeli32 and AM32
2025-02-13 11:22:50 +01:00
Shiv Tyagi
8655d013c6
AP_RPM: use AP_PERIPH_RPM_ENABLED and AP_PERIPH_RPM_STREAM_ENABLED
2025-02-13 20:29:06 +11:00
Shiv Tyagi
c7a4489b58
AP_HAL_ChibiOS: create and use AP_PERIPH_RPM_ENABLED and AP_PERIPH_RPM_STREAM_ENABLED
2025-02-13 20:29:06 +11:00
Peter Barker
354c861753
GCS_MAVLink: correct AP_Periph compilation when GCS enabled and mag not
...
../../libraries/GCS_MAVLink/GCS_Common.cpp: In member function 'void GCS_MAVLINK::send_highres_imu()':
../../libraries/GCS_MAVLink/GCS_Common.cpp:2184:27: error: unused variable 'HIGHRES_IMU_UPDATED_XMAG' [-Werror=unused-variable]
2184 | static const uint16_t HIGHRES_IMU_UPDATED_XMAG = 0x40;
| ^~~~~~~~~~~~~~~~~~~~~~~~
compilation terminated due to -Wfatal-errors.
cc1plus: all warnings being treated as errors
2025-02-13 10:18:13 +01:00
Andy Piper
8ea00032ee
AP_HAL_ChibiOS: reset DMA after exiting soft serial
...
only configure DMA on groups that are actually being used for soft serial
2025-02-13 17:12:09 +11:00
Andy Piper
9f31795dda
AP_BLHeli: properly deal with interface test when disconnected
...
don't cache connection result and return appropriate error if connection fails.
don't wait 1s to send first serial passthrough message
retry failed cmd_DeviceInitFlash as per betaflight
ensure the bootinfo structure is large enough
2025-02-13 17:12:09 +11:00
Randy Mackay
4d424a8314
Filter: SlewCalculator2D typo fix
2025-02-12 20:38:13 +09:00
Peter Barker
14cbc1995c
AP_IRLock: tidy up inclusions to match standards
...
including adding an _config.h
2025-02-12 16:15:40 +09:00
Peter Barker
549c1fafb5
AP_IRLock: rename IRLock class to AP_IRLock
2025-02-12 16:15:40 +09:00
Peter Barker
3e5f1ae9ec
AP_IRLock: adjust for file rename
2025-02-12 16:15:40 +09:00
Peter Barker
93b2b3c924
AP_IRLock: rename IRLock files to AP_IRLock
2025-02-12 16:15:40 +09:00
Peter Barker
200b51370f
AP_IRLock: remove old AP_IRLock header
2025-02-12 16:15:40 +09:00
Shiv Tyagi
3ab1aa1c56
AP_HAL_ChibiOS: replace HAL_PERIPH_ENABLE_RCIN with AP_PERIPH_RCIN_ENABLED
2025-02-11 19:31:19 +11:00
Le Minh Duc
1a10241639
AP_Airspeed: Correct airspeed calibration issue for gliders with sensors positioned behind the propeller
2025-02-11 15:31:45 +11:00
Henry Wurzburg
6a02fdb5df
TECS:correct metadata
2025-02-11 15:14:03 +11:00
Peter Barker
42c1ad30c9
AP_Scripting: remove use of OwnPtr
2025-02-11 11:54:52 +11:00
Peter Barker
11932d6d50
AP_RangeFinder: correct buffer size problems in LightWareI2C
...
../../libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp:158:105: warning: argument 'reply' of type 'char[15]' with mismatched bound [-Warray-parameter]
158 | void AP_RangeFinder_LightWareI2C::sf20_get_version(const char* send_msg, const char *reply_prefix, char reply[15])
| ^
../../libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h:47:80: note: previously declared as 'char[5]' here
47 | void sf20_get_version(const char* send_msg, const char *reply_prefix, char reply[5]);
| ^
2025-02-11 11:54:52 +11:00
Peter Barker
2e46dcf582
AP_HAL_SITL: remove unused variables from RCInput
...
In file included from ../../libraries/AP_HAL_SITL/RCInput.cpp:6:
../../libraries/AP_HAL_SITL/RCInput.h:22:17: warning: private field '_sitlState' is not used [-Wunused-private-field]
22 | SITL_State *_sitlState;
| ^
../../libraries/AP_HAL_SITL/RCInput.h:23:10: warning: private field 'using_rc_protocol' is not used [-Wunused-private-field]
23 | bool using_rc_protocol;
| ^
2025-02-11 11:54:52 +11:00
Peter Barker
4c2c20c018
AP_Airspeed: remove unused variable
...
../../libraries/AP_Airspeed/AP_Airspeed_AUAV.h:68:11: warning: private field 'pressure_abs_L' is not used [-Wunused-private-field]
68 | float pressure_abs_L;
2025-02-11 11:54:52 +11:00
mattp256
0fd3448e31
AR_Motors: fix brushed motor support for omni vehicles
...
Fixes an issue where omni motors (BrushedWithRelay/BrushedBiplor)
are not configured correctly due to initialization order. setup_omni()
must execute first so that _motors_num is set correctly when
setup_pwm_type() uses it to determine which motors are in use.
2025-02-11 09:21:16 +09:00
Thomas Watson
de2ebe22b6
AP_HAL_ESP32: I2CDevice: take into account driver timeout
...
Necessary for proper INA3221 operation apparently.
2025-02-11 10:54:03 +11:00
Thomas Watson
34a0e827fd
AP_HAL_ESP32: SPIDevice: deassert all CSes on startup
...
Ensure initialization of each device doesn't conflict with other devices
on the bus.
2025-02-11 10:54:03 +11:00
Thomas Watson
76019ffe18
AP_HAL_ESP32: SPIDevice: fix automatic full duplex transfer
...
This condition must be exactly the same as the one in ChibiOS as whether
we use full duplex or not causes different bus traffic.
This probably needs refactoring, the semantics are confusing and subtle,
though the use of the same driver between I2C and SPI devices must be
accounted for.
2025-02-11 10:54:03 +11:00
Peter Barker
25f7eebce5
AP_RCProtocol: move navio2 RC input into AP_RCProtocol
2025-02-11 10:41:52 +11:00
Peter Barker
261a804f6b
AP_HAL_Linux: move navio2 RC input into AP_RCProtocol
2025-02-11 10:41:52 +11:00
Peter Barker
e92d540d64
AP_HAL: move navio2 RC input into AP_RCProtocol
2025-02-11 10:41:52 +11:00
Rishabh
5b3fe19916
AC_Loiter: Add method to change Loiter horizontal maximum speed
2025-02-11 08:35:34 +09:00
Thomas Watson
c7f32c2fb4
AP_Scripting: mavlink: clearer error messages
2025-02-11 10:26:59 +11:00
Thomas Watson
55a0cbbd9a
AP_Scripting: mavlink: remove redundant Lua buffer usage
2025-02-11 10:26:59 +11:00
Thomas Watson
2b995b2087
AP_Scripting: mavlink: fix RX init locking
...
If there is an error, the semaphore will never be released. Fix by only
calling functions which could cause errors after it's released.
2025-02-11 10:26:59 +11:00
Your Name
9160de1599
AP_HAL_ChibiOS: AP_HAL_ChibiOS: Add ZeroOne_Air board
2025-02-11 08:09:27 +11:00
Iampete1
a81c79a1b0
GCS_MAVLink: highres imu: remove all "bitmask" value
2025-02-10 22:17:16 +11:00
Shiv Tyagi
3a13e0d292
AP_HAL_ChibiOS: create and use AP_PERIPH_RTC_ENABLED
2025-02-10 09:37:48 +11:00
Shiv Tyagi
09c8ad81bb
AP_HAL_ChibiOS: set HAL_VISUALODOM_ENABLED to 0 directly
2025-02-09 07:40:47 +11:00
Thomas Watson
1ca1b5d26f
AP_Logger: clarify behavior of log_file_content
...
It hasn't kept the passed pointer for a while now.
2025-02-09 07:28:53 +11:00
Thomas Watson
962616a76f
AP_Scripting: update so mavlink init intent matches behavior
...
RX message ID buffer sizes have been shrunk to the amount actually used.
2025-02-08 13:52:21 -06:00
Iampete1
fe3f12dc87
AP_Scripting: Docs: correct argument order on mavlink:init
2025-02-08 11:38:06 -06:00
cuav-chen2
aee973f4de
AP_Baro: Fix BMP581 initialization error
2025-02-08 14:36:10 +11:00
Ep Pravitra
43cdf1a03d
AP_Mount: fix object tracking command for ViewPro
...
The command should also take negative values
Redo scaling to comply with mavlink documentation.
2025-02-08 08:48:52 +09:00
Stephen Dade
d5c1478324
AP_Scripting: Update rockblock and MAVLinkHL with additional commands and gcs timeout
2025-02-08 09:42:06 +11:00
Shiv Tyagi
f62e65f26e
AP_HAL_ChibiOS: use AP_PERIPH_IMU_ENABLED in place of HAL_PERIPH_ENABLE_IMU
2025-02-08 08:22:10 +11:00
Davide Iafrate
2257009eba
SITL: Added comment to clarify IMU acceleration value
2025-02-07 00:42:28 +00:00
Peter Barker
498dc11cef
RC_Channel: add RC channel option for trimming AHRS using RC
2025-02-06 16:03:52 +11:00
Ep Pravitra
0b659ac8a1
AP_Mount: zoom for Viewpro IR sensor
2025-02-06 10:50:14 +09:00
Peter Barker
4161c425d1
GCS_MAVLink: simplify MissionItemProtocol get_item interface
...
stop passing through _link and the original msg, move use to the base class instead.
starts fence and rally also using the "correct the GCS's count" code.
This also corrects the error code when correcting the GCS's count to INVALID_SEQUENCE rather than just ERROR
2025-02-06 10:20:23 +11:00
Peter Barker
26c61f527e
SIM_XPlane: remove use-after-free issue
...
c_str points to a member of .str(), so we have to make sure that object persists
../../libraries/SITL/SIM_XPlane.cpp:239:34: warning: object backing the pointer will be destroyed at the end of the full-expression [-Wdangling-gsl]
239 | const char *type_s = d.get("type").to_str().c_str();
2025-02-05 20:06:10 +11:00
Peter Barker
53701655a0
SIM_XPlane: avoid leaking memory upon json load failure
...
../../libraries/SITL/SIM_XPlane.cpp:209:16: warning: Potential leak of memory pointed to by 'fname' [unix.Malloc]
return false;
^~~~~
2025-02-05 20:06:10 +11:00
Bob Long
dd54f025d6
AP_ESC_Telem: fix timeout race
...
The timeout for non-RPM telemetry is vulnerable to a similar race as the
RPM. This change makes the timeout logic consistent between the two.
2025-02-05 18:54:29 +11:00
Iampete1
54a71cef9d
AP_Airspeed: Calibration: remove unused DT
2025-02-05 18:04:41 +11:00
Peter Barker
4959cee694
Rover: add option to require position for Rover before arming
2025-02-05 10:39:20 +11:00
Peter Barker
0fb5a2105c
AP_Arming: add option to require position for Rover before arming
2025-02-05 10:39:20 +11:00
bugobliterator
f8726ee646
AP_HAL_ChibiOS: disable mcast bridging in bootloader
2025-02-05 10:23:46 +11:00
bugobliterator
51471a0a7e
AP_Networking: make can multicast an endpoint by default
...
also add option to enable multicast with bridging to CAN bus in application
and disabled in bootloader
2025-02-05 10:23:46 +11:00
bugobliterator
f9a8d9b034
AP_CANManager: use updated frame callback types
...
also change to IsForwardedFrame from IsMAVCAN
2025-02-05 10:23:46 +11:00
bugobliterator
4bad4f856b
AP_HAL: change IsMavCAN to IsForwardedFrame
2025-02-05 10:23:46 +11:00
Davide Iafrate
131c0f8e2d
SITL: Clarification for timestamp in JSON interface
2025-02-05 10:03:52 +11:00
Tdogb
9c12476d39
AP_Airspeed: AUAV airspeed support
2025-02-04 16:17:28 +11:00
Peter Barker
eed3e147a0
AP_BattMonitor: remove use of ownptr
2025-02-04 11:57:58 +11:00
Peter Barker
6f40c80d65
AP_Notify: move enabling of AP_NOTIFY_TONEALARM_ENABLED out of AP_Notify_config.h
...
this is looking at chibios-specific defines, which is bad
2025-02-04 11:53:25 +11:00