Ryan Friedman
01cd42d1e7
AP_GPS: Allow multiple external AHRS GPS instances
...
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
2023-08-24 12:01:32 +10:00
Nick Exton
fad1f35d93
GCS_MAVLink: Remove unreachable return in handle_command_mount()
2023-08-24 11:57:55 +10:00
Pierre Kancir
d78fe1ad99
AP_HAL_SITL: fix possible divide by 0 on synth.hpp
2023-08-24 07:46:20 +10:00
Ryan Friedman
d31896a545
AP_DDS: Stub out external odom
...
* Implement frame ID checking and test it
* Implement the visual odom function that does narrowing to floats
* Normalize quaternions from ROS
* Supply 0 error to EKF
* Handle external odomo only if HAL_VISUALODOM_ENABLED is defined
* Implement odom timestamping and improve docs
* Add unit tests
* Add a CONFIG file for DDS
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
2023-08-24 07:46:06 +10:00
Tom Pittenger
732cd31f27
GCS_MAVLink: MSG_HOME_POSITION to use NaN for invalid
2023-08-23 08:53:29 -07:00
Andy Piper
f7c86cc06a
AP_NavEKF: fallback to no baro on boards that have no baro
2023-08-23 18:25:26 +10:00
Paul Riseborough
5aa7bd0b7a
AP_NavEKF3: Allow operation with EK3_SRCx_POSZ = 0 (NONE)
2023-08-23 18:25:26 +10:00
Paul Riseborough
2572c9be48
AP_NavEKF: Allow EK3_SRCx_POSZ to be set to 0 (NONE)
2023-08-23 18:25:26 +10:00
Andy Piper
c57efa1b20
AP_NavEKF3: allow high values of EK3_ALT_M_NSE for boards without baros
2023-08-23 18:25:26 +10:00
Randy Mackay
9d09739044
AP_Mount: Viewpro supports get rangefinder distance
2023-08-23 18:09:56 +10:00
Andy Piper
8f644f473c
AP_Vehicle: add autotune options
2023-08-23 18:06:22 +10:00
Andy Piper
ee883b6ad0
APM_Control: allow autotune FLTD and FLTT updates to be disabled
2023-08-23 18:06:22 +10:00
Peter Barker
81326a17db
hwdef: qiotek: correct HAL_BATT_MONITOR_DEFAULT define name
2023-08-23 17:20:20 +10:00
Tom Pittenger
ed43f095ce
AP_HAL_ChibiOS: add AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED to defaults_periph
2023-08-22 16:14:36 -07:00
Tom Pittenger
21ead4e8e3
AP_Battery: add param _ESC_ID to write to ESC_Telem
2023-08-22 16:14:36 -07:00
Tom Pittenger
dbe0aac73f
AP_ESC_Telem: update_telem_data to be public
2023-08-22 16:14:36 -07:00
Tom Pittenger
5ddb649ed1
Update libraries/AP_Networking/AP_Networking.cpp
...
Co-authored-by: Peter Barker <pb-gh@barker.dropbear.id.au>
2023-08-22 09:25:42 -07:00
muramura
4bad05c49c
AP_Logger:AP_Networking: If initialization fails, the process is terminated
2023-08-22 09:25:42 -07:00
muramura
75a279a11d
AP_Networking: Delete entity class pointer
2023-08-22 09:25:42 -07:00
Andrew Tridgell
847c7980c7
AP_DDS: use AP_ExternalControl for velocity control
...
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
Co-authored-by: Andrew Tridgell <tridge60@gmail.com>
2023-08-22 18:21:23 +10:00
Andrew Tridgell
0f624089f8
AP_ExternalControl: external control library for MAVLink,lua and DDS
...
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
Co-authored-by: Andrew Tridgell <tridge60@gmail.com>
2023-08-22 18:21:23 +10:00
Andy Piper
37a3f85a9a
AP_HAL_ChibiOS: add 8 bi-directional dshot channels to KakuteH7-Wing
2023-08-22 11:08:14 +10:00
Andrew Tridgell
4f0ba39b64
AP_Param: fixed parameter defaults array length handling
...
we need to add up the total for all comma separated parameter files
2023-08-22 11:07:30 +10:00
Willian Galvani
158b99c20a
AP_MotorsUGV: add asymmetry factor for skid-steering
...
Co-authored-by: Iampete1 <iampete@hotmail.co.uk>
2023-08-22 09:14:42 +09:00
Peter Barker
b141cca3d5
GCS_MAVLink: pass mavlink_message_t to handle_command_*_packet
...
the "special case" blocks are getting longer and longer. Merge the switch statements for the command type to be handled by passing around the message.
2023-08-22 10:11:33 +10:00
Andrew Tridgell
aaec99ae31
hwdef: removed baro from HolybroG4_GPS
...
not included in production versions, and baro is not generally a good
idea on a GPS due to impact of airflow
also disable unused IMU, SPI bus and 2nd I2C and re-enable 2nd CAN as
helical units have dual CAN
2023-08-22 09:37:20 +10:00
Peter Barker
1dd5778956
GCS_MAVLink: correct placement of AP_MAVLINK_MISSION_SET_CURRENT_ENABLED
2023-08-22 09:09:54 +10:00
Peter Barker
b4a9c0ec1e
AP_RPM: include backend header
...
in the case you're inlcuding the RPM library but no backends we don't know the shape of the backend class, so we can't call the update-esc-telem method.
2023-08-22 09:09:54 +10:00
Peter Barker
84b3c9e267
SITL: reset balancebot to vertical in a kinmetically consistent manner
...
The hard-reset of all state variables means we feed the EKF inconsistent gyro data. Attempt to upright the vehicle with a simple p-gain when it is disarmed, as if someone is pushing the thing back upright
2023-08-21 22:09:04 +10:00
Michelle Rossouw
26bbd6536a
SITL: Improve Blimp dynamics and fin motion to be more realistic, allow SITL loop rate to be changed and add more logging
2023-08-21 21:01:47 +10:00
Peter Barker
efa680f1e0
AP_HAL_ChibiOS: add hwdef for bootloader for MatekL431-RC
2023-08-20 17:37:44 +10:00
Fred Kummer
7c6551af9b
AP_DroneCAN: allow sending negative RawCommands to ESCs
2023-08-19 20:27:58 +10:00
Andrew Tridgell
24139d661a
AP_RCProtocol: allow for fport without FRSky telem
2023-08-19 20:27:24 +10:00
Peter Barker
ca549e1887
hwdef: add MatekL431-RC for RC input
2023-08-19 20:27:24 +10:00
Peter Barker
103caac92c
AP_HAL_ChibiOS: add support for DroneCAN RCInput packets
2023-08-19 20:27:24 +10:00
Peter Barker
b8a80817e4
AP_RCProtocol: add support for DroneCAN RCInput packets
2023-08-19 20:27:24 +10:00
Peter Barker
1e8d256bc2
AP_DroneCAN: add support for DroneCAN RCInput packets
2023-08-19 20:27:24 +10:00
Peter Barker
48b9172f5b
RC_Channel: add note about copying parameter to AP_Periph
2023-08-19 20:27:24 +10:00
Ryan Friedman
e14afa6f2b
AP_DDS: Add AP_DDS_config.h for feature defines
...
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
2023-08-18 08:35:24 +10:00
Tom Pittenger
27f9a54a54
AP_HAL_ChibiOS: fix CubeRed default MAC Address
2023-08-17 13:51:54 +10:00
Tom Pittenger
7e62904d5e
AP_Networking:fix default MAC address UID
2023-08-17 13:51:54 +10:00
Peter Barker
5a0f0915ed
AP_RPM: tidy constructors and use of config.h
2023-08-17 09:22:41 +10:00
Peter Barker
8df2d4998b
AP_Math: improve gating of use of AP_InternalError library
...
- gate calls into library directly on the define
- INTERNAL_ERROR becomes empty if library not compiled in
2023-08-17 09:16:46 +10:00
Peter Barker
94e61a263d
AP_InternalError: improve gating of use of AP_InternalError library
...
- gate calls into library directly on the define
- INTERNAL_ERROR becomes empty if library not compiled in
2023-08-17 09:16:46 +10:00
Peter Barker
bb6f0ae527
AP_HAL_ChibiOS: improve gating of use of AP_InternalError library
...
- gate calls into library directly on the define
- INTERNAL_ERROR becomes empty if library not compiled in
2023-08-17 09:16:46 +10:00
Peter Barker
c2f4fb5def
hwdef: use APJ_BOARD_ID mapping for ACNS-CM4Pilot
2023-08-17 09:13:54 +10:00
Peter Barker
19bd97a893
chibios_hwdef.py: permit board ID to be specified as a string
2023-08-17 09:13:54 +10:00
Peter Barker
b8978ad73a
hwdef: explicitly state no-bootloader-embedding on some boards
2023-08-17 08:37:31 +10:00
Peter Barker
a11df25490
chibios_hwdef.py: enforce presence of bootloader if embedding desired
2023-08-17 08:37:31 +10:00
yunjiuav
f92073fa4d
HAL_ChibiOS: modify APJ_BOARD_ID of YJUAV_A6SE
2023-08-17 08:35:18 +10:00
Michael du Breuil
a0efcc7bdc
AP_ESC_Telem: Correct a regression with calclulating active_esc_mask
...
Credit to @casrya on github for spotting this (#24665 ), and
investigating. The intent here was to bail out only if no data was
within the timeout, which I had messed up in a bad refactor.
2023-08-17 08:34:29 +10:00
Paul Riseborough
e3c0175bb4
AP_NavEKF3: Update EK3_GLITCH_RADIUS metadata
2023-08-16 17:56:43 +10:00
Paul Riseborough
842882355f
AP_NavEKF3: increase innovation variance instead of clipping innovations
2023-08-16 17:56:43 +10:00
Paul Riseborough
573bd7c7f3
AP_NavEKF3: Provide option to clip velocity and position innovations
2023-08-16 17:56:43 +10:00
Andy Piper
7896b04365
AP_HAL_ChibiOS: betafpv F450 AIO hwdef
2023-08-16 17:51:23 +10:00
Henry Wurzburg
b1fc5bd69f
AP_HAL_ChibiOS: add missing bootloader binaries
2023-08-16 17:49:00 +10:00
Peter Barker
2ce61cce58
AP_Generator: rename generator define to fix feature extraction
...
pattern-matching requires a regular pattern. Renaming the class would be bad, so just rename the define
2023-08-16 17:35:59 +10:00
Peter Barker
7273c8416a
AP_HAL_ChibiOS: prevent Periph bricking problem when paniccing early
...
if Periph panics before we mark the scheduler as initialised then we don't watchdog, which we really need to do on periph nodes so they can be re-flashed conveniently.
2023-08-16 17:21:30 +10:00
Peter Barker
4d3e7bd3da
AC_Fence: remove old polygon fence conversion code
2023-08-16 17:13:31 +10:00
Peter Barker
83cecdd229
AP_RPM: correct compilation when AP_RPM_ESC_TELEM_ENABLED is disabled
2023-08-15 18:06:58 -07:00
Tom Pittenger
d8e9379289
AP_RPM: add writing to outbound ESC_Telem
2023-08-16 06:35:05 +10:00
Tom Pittenger
15b8700a2c
Revert "AP_RPM: enable AP_RPM to set ESC Telemetry"
...
This reverts commit 1e633df3de
.
2023-08-16 06:35:05 +10:00
Andrew Tridgell
3e3c086ab7
SITL: build the whole simulator as double precision
2023-08-15 22:39:23 +10:00
Andrew Tridgell
ba7d94d5ad
HAL_SITL: mark all as double precision
2023-08-15 22:39:23 +10:00
Ryan Friedman
2c5f90adca
AP_DDS: Enable the DDS parameter by default
...
* DDS is still disabled by default in all builds for the library level compile flag
* This parameter was blocking running ROS 2 automated testing in CI
* This can be changed once ENABLE_DDS compiler flag is enabled in SITL or for the 4.5 release
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
2023-08-15 18:32:39 +10:00
Shiv Tyagi
0d87479314
AP_Scripting: make follow bindings dependant on AP_FOLLOW_ENABLED
2023-08-15 09:57:35 +10:00
Shiv Tyagi
6251b3e3f3
AP_Follow: add and use AP_FOLLOW_ENABLED
2023-08-15 09:57:35 +10:00
Tom Pittenger
932ed9ff28
AP_Mission: show tag or jump index on WP change
2023-08-14 16:55:04 -07:00
muramura
62aee72820
GCS_MAVLink: Change a number to a defined name
2023-08-15 08:36:59 +09:00
Peter Barker
f2066d8e58
GCS_MAVLink: remove ap_message<->mavlinkid mappings for unused ids
2023-08-15 09:14:27 +10:00
Peter Barker
9d74b3d2d9
AP_NMEA_Output: remove from 1MB boards
2023-08-15 08:45:30 +10:00
Peter Barker
7764d1d904
GCS_MAVLink: add build_options.py option to remove rallypoint protocol
2023-08-15 08:37:17 +10:00
Peter Barker
941e9785d4
AP_GPS_NOVA: avoid infinite reading of bytes
...
if we have a very fast stream of garbage coming in available() may never return 0
2023-08-15 08:36:13 +10:00
yjuav
ac993753eb
Modify the LED light pins and adjust the direction of the IMU and COMPASS sensors.
2023-08-15 08:35:26 +10:00
yunjiuav
5671e502d3
HAL_ChibiOS: added YJUAV_A6SE support
2023-08-15 08:35:26 +10:00
Peter Barker
0dae9b46ee
SRV_Channel: correct description of SERVO_RC_FS_MSK
2023-08-15 08:16:16 +10:00
Peter Barker
b8c1367aac
SRV_Channel: avoid using bad RC data in passthrough code
...
we may not have valid input but not be at the stage of declaring an RC failsafe.
2023-08-15 08:16:16 +10:00
Peter Barker
808fcbda0e
GCS_MAVLink: fix airspeed cal / format commands via non-USB telemetry
2023-08-15 08:13:32 +10:00
Andy Piper
75c1ad6efa
AP_HAL_ChibiOS: explicitly set dshot rate when using iomcu
2023-08-15 06:53:48 +10:00
Andy Piper
c4cfc5dbe4
AP_IOMCU: fix eventing mask and some minor cleanups
2023-08-15 06:53:48 +10:00
Andy Piper
2af3d53eac
AP_IOMCU: use a command queue for dshot commands and telemetry requests to avoid losing data
2023-08-15 06:53:48 +10:00
Andy Piper
c6c78a9c32
AP_HAL_ChibiOS: ensure reverse and reversible masks are applied to iomcu
2023-08-15 06:53:48 +10:00
Andy Piper
d9f42236ad
AP_IOMCU: support dshot600 on f103
2023-08-15 06:53:48 +10:00
Andy Piper
52dbac1de7
AP_HAL_ChibiOS: run STM32F103 core clock at 72Mhz on 24Mhz oscillators
2023-08-15 06:53:48 +10:00
Andy Piper
33c40eaba3
AP_HAL_ChibiOS: add iomcu dshot for Pixhawk1, Pixhawk5X and fmuv5
2023-08-15 06:53:48 +10:00
Andy Piper
876f4f7a8f
AP_HAL_ChibiOS: dshot iofirmware for Durandal, Pixhawk6C, CubePurple and CubeYellow
2023-08-15 06:53:48 +10:00
Andy Piper
af256f4b1b
AP_IOMCU: output mcuid on f103 if able to
2023-08-15 06:53:48 +10:00
Andy Piper
9ac683a350
GCS_Common: report ARM CPUID on startup
2023-08-15 06:53:48 +10:00
Andy Piper
9db5d0bf9b
AP_IOMCU: reduce latency for oneshot
...
correctly update outmode modes when requested
get ARM CPUID and display in startup banner
ensure correct rc input timing on 1Khz iofirmware
2023-08-15 06:53:48 +10:00
Andy Piper
cf9a3ada28
GCS_MAVLink: print out IOMCU mcuid on startup
2023-08-15 06:53:48 +10:00
Andy Piper
1c646d2986
AP_HAL_ChibiOS: use f103 iofirmware for Pixhawk6X
2023-08-15 06:53:48 +10:00
Andy Piper
c057cc5485
AP_HAL_ChibiOS: add get_output_mode() and use it to print correct banner for iomcu
...
add support for undef of STM32 lines and DMA_NOMAP
add support for F103 running at 24Mhz
add f103 variants of iofirmware
reduce memory usage in iomcu for new model
correct pwm output reporting
split iofirmware into config + mcu to allow f103 definition
don't enable non-existant timers on F103
2023-08-15 06:53:48 +10:00
Andy Piper
7b96f66413
AP_IOMCU: add support for getting output mode and mcuid
...
give an appropriate MCUID on F103
2023-08-15 06:53:48 +10:00
Andy Piper
2dd4f3f581
AP_BoardConfig: control dshot availability with HAL_WITH_IO_MCU_DSHOT
...
correct parameter id for BRD_IO_DSHOT
2023-08-15 06:53:48 +10:00
Andy Piper
c631b79dde
AP_HAL: add get_output_mode() and HAL_WITH_IO_MCU_DSHOT
2023-08-15 06:53:48 +10:00
Andy Piper
83fddd0d61
AP_HAL_ChibiOS: enable iomcu-dshot on CubeBlack
2023-08-15 06:53:48 +10:00
Andy Piper
bb730e8e24
AP_IOMCU: inverted locking model 2
2023-08-15 06:53:48 +10:00
Andy Piper
ec1edea1da
AP_IOMCU: add support for shared DMA to iomcu-dshot
...
new event-based update() loop for iomcu to allow for DMA channel sharing
spin event loop at 2Khz to give dshot thread ample access to DMA channels
correct transmission complete callbacks
ensure peripheral is re-enabled on DMA resumption
ensure DMA transactions do not get clobbered by locking
restructure callbacks for shared and non-shared DMA cases
ensure RC updates happen at 1Khz
increase expected delay at startup
2023-08-15 06:53:48 +10:00
Andy Piper
10a612566a
AP_HAL_ChibiOS: ensure shared DMA works in IOMCU
...
enable TIM4 in shared mode on IOMCU for dshot
stop the PWM peripheral in rcout DMA swapping on IOMCU to prevent UART corruption
provide debugging options on iomcu dshot
support unshared DMA with iomcu dshot
optimize rcout on iomcu
tune iomcu stack for 8 channels
2023-08-15 06:53:48 +10:00
Andy Piper
3c42f1b7d9
AP_HAL_ChibiOS: disable stack checking on iomcu
2023-08-15 06:53:48 +10:00
Andy Piper
9611baf148
AP_Vehicle: soft reboot iomcu on soft reboot
2023-08-15 06:53:48 +10:00
Andy Piper
837c81af5e
AP_HAL_ChibiOS: fix sending of dshot commands to all channels
2023-08-15 06:53:48 +10:00
Andy Piper
e6e0543b8a
AP_IOMCU: propagate dshot rates through to IOMCU
...
implement dshot ESC telemetry
add support for channel enablement/disablement
add stack checks and reporting for MSP stack
wait correct timeout in tickless mode
ensure that dshot sees all pwm updates as the occur in order to maintain periodicity
ensure dshot options are propagated on reset
implement dshot commands
ensure oneshot/125 and mode are setup correctly
add instrumentation for process stack
prevent illegal recursive locks
ignore requests for dshot 600
add support for soft reboot of iomcu
2023-08-15 06:53:48 +10:00
bugobliterator
9a21297cd1
AP_HAL_ChibiOS: add support for DShot on IOMCU
...
set timer counter size to be a byte wide
use HAL_DSHOT_ENABLED instead of DISABLE_DSHOT
build iomcu-dshot from existing iomcu
correct defines for DMAR size on iomcu
allow iomcu dshot rate to be configured from FMU
correct DMA allocation for dshot on iomcu
allow debug builds on iofirmware
ensure dshot is enabled on iomcu dshot
support proper iomcu dshot output thread triggered by FMU
allow selective disablement of serial LEDs and passthrough
disable serial LEDs and passthrough on iomcu-dshot
propagate ESC telemetry to iomcu
dshot_send_groups() for iomcu
remove use of ICU on iomcu for dshot. only allocate possible DMA channels
rename serial passthrough and dshot defines
update dshot docs
resize dshot iomcu main stack to minimum
correct dshot prescaler usage and bit_width_mul calculation
use ChibiOS in tickless mode on iomcu-dshot so that virtual timers can be used
propagate dshot commands to iomcu
passthrough oneshot125 to iomcu
2023-08-15 06:53:48 +10:00
Andy Piper
f233a65580
AP_HAL_ChibiOS: add global interrupt handlers for TIM15 and TIM17 on F1
2023-08-15 06:53:48 +10:00
Andy Piper
9642343e8e
AP_BLHeli: normalize motor index correctly for iomcu running dshot
2023-08-15 06:53:48 +10:00
Andy Piper
0b4838475d
AP_SerialLED: configure serial LED feature based on hal availability
2023-08-15 06:53:48 +10:00
Andy Piper
4c8b346512
AP_BoardConfig: check IOMCU is enabled when checking dshot
2023-08-15 06:53:48 +10:00
Andy Piper
1b210f8ea9
AP_HAL: support accessors for dshot_period_us
...
add support for selectively disabling serial LEDs and passthrough
provide mutator to allow iomcu to set dshot rate
support HAL_SERIAL_ESC_COMM_ENABLED and DISABLE_SERIAL_ESC_COMM
update dshot docs
make default serial led enablement dependent on dshot
2023-08-15 06:53:48 +10:00
Andy Piper
eacc29e81e
AP_Math: do not use internal_error() on iofirmware
2023-08-15 06:53:48 +10:00
bugobliterator
4ce32c74de
AP_HAL: add default DISABLE_DSHOT as false
...
use HAL_ENABLE_DSHOT instead of DISABLE_DSHOT
2023-08-15 06:53:48 +10:00
bugobliterator
b8af6da623
AP_BoardConfig: add ability to change dshot firmware
2023-08-15 06:53:48 +10:00
bugobliterator
ad428ac060
AP_IOMCU: add support for sending DShot function command
...
add support for dshot on iomcu
add support for updating to dshot iofirmware
2023-08-15 06:53:48 +10:00
Peter Barker
771f8855b7
AP_Logger: correct use of nullptr in SITL structure sanity checks
...
A developer might be able to craft a fault such that s could be nullptr here. They would need to work at it, but we can do better.
2023-08-14 22:25:50 +10:00
Andrew Tridgell
0d97b308b2
GCS_MAVLink: fixed corruption of FTP reply component ID
...
this led to not being able to do FTP transfers with
support.ardupilot.org unless MissionPlanner used the same component ID
as the support engineer GCS
2023-08-14 22:25:23 +10:00
alexklimaj
738a4c638a
hwdef: arkv6x default to no IO MCU
2023-08-14 12:06:25 +10:00
Peter Barker
90929205e9
SRV_Channel: correct RC channel failsafe mask
...
this is a 32-bit parameter.
2023-08-14 11:21:06 +10:00
Andrew Tridgell
484312df93
AP_NavEKF3: fixed race condition in updateFilterStatus()
...
filter status was initially set to zero then updated. This interacts
with the IMU filtering code which checks filter status from a
different thread to determine active_EKF_type(). When the race
condition is hit then the IMU we are running notch filters on changes
for a single sample, causing a notch filter glitch
2023-08-12 17:47:56 +10:00
Andy Piper
205e6bebc7
AP_HAL_ChibiOS: fix incorrect removal of HAL_I2C_INTERNAL_MASK undef in SkystarsH743HD
2023-08-12 14:00:11 +10:00
Michelle Rossouw
e4d44c1006
SITL: Make SIM_Aircraft use double precision to stop SITL's short-range teleporting
2023-08-12 10:49:02 +10:00
Tom Pittenger
2b30fbcfb2
AP_HAL_ChibiOS: disable RPM by default on Periph
2023-08-11 13:31:45 -07:00
Tom Pittenger
0de754bff3
AP_RPM: prepare for AP_Periph
2023-08-11 13:31:45 -07:00
Tom Pittenger
41024b7f02
AP_TemperatureSensor: add Source Pitot_tube
2023-08-11 13:20:51 -07:00
olliw42
2f58d082f0
GCS_Common: brackets missing in switch case
2023-08-11 12:11:43 -07:00
arshPratap
47efaf9c62
AP_DDS: Added ROS 2 service support
2023-08-11 13:35:49 +10:00
arshPratap
5f17e33b39
AP_Arming: Added DDS Method for Arming/Disarming
2023-08-11 13:35:49 +10:00
Peter Barker
7f8df080f8
SITL: correct compilation for CubeOrange-SimOnHardware
...
../../libraries/SITL/SIM_GPS.cpp: In member function 'void SITL::GPS::send_gsof(const uint8_t*, uint16_t)':
../../libraries/SITL/SIM_GPS.cpp:1292:24: error: 'AP_InternalError' has not been declared
1292 | INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
2023-08-11 12:40:59 +10:00
Ryan Friedman
5b21834827
AP_GPS: Switch to sparse endian to make it portable
...
* Instead of custom algorithm to reduce flash and code maintenance
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
2023-08-11 11:21:41 +10:00
Peter Barker
e638925ee0
AP_HAL_ChibiOS: chibios_hwdef.py: fix minor bugs
...
also mark as flake8-clean
2023-08-11 10:41:02 +10:00
Peter Barker
536f3ac922
chibios_hwdef.py: minor flake8 fixes
...
whitespace, long lines, ambiguous variables etc
2023-08-11 10:41:02 +10:00
Peter Barker
65cc16c51d
SITL: add descriptions for simulated IMU scale factors
2023-08-11 10:34:02 +10:00
Andrew Tridgell
44c5754e36
AP_Airspeed: increased timeout on DroneCAN airspeed data
...
the data is sent at 20Hz, which means a single lost packet with 10Hz
reading resulted in an unhealthy sensor
2023-08-11 10:33:36 +10:00
Andrew Tridgell
faa4d28851
AP_Airspeed: fixed handling of unhealthy airspeed
...
this fixes a bug introduced in
https://github.com/ArduPilot/ardupilot/pull/22416 which results in
using bad airspeed data on timeout. The prev_health variable is
updated by the get_pressure call
2023-08-11 10:33:36 +10:00
Peter Barker
cbd2b199eb
SITL: factor simulated GPS
2023-08-11 10:01:56 +10:00
olliw42
e2599252a1
AP_Mount: use backend instead of _backends[instance]
2023-08-11 07:55:05 +09:00
Andrew Tridgell
8ff37bc79c
AP_Networking: fixed duplicate parameters in wiki
...
defining two parameter tables in one file causes duplicates
2023-08-10 13:34:14 -07:00
Andy Piper
f787e940b3
AP_HAL_ChibiOS: change incorrect I2C internal mask from SkystarsH7HD bdshot
2023-08-10 16:16:16 +10:00
davidsastresas
767710340a
AP_Mount: Viewpro sends gimbal_device_id in camera_information
2023-08-10 14:37:30 +09:00
davidsastresas
25e8bd1f42
AP_Mount: Xacti sends gimbal_device_id in camera_information
2023-08-10 14:37:30 +09:00
davidsastresas
d242a968f3
AP_Mount: Siyi sends gimbal_device_id in camera_information
2023-08-10 14:37:30 +09:00
davidsastresas
55aa1b5a32
AP_Mount: Backend sends gimbal_device_id in device_attitude_status_send
2023-08-10 14:37:30 +09:00
davidsastresas
073e93dfec
AP_Camera: MAVLinkCamV2 sends gimbal_device_id in camera_information
2023-08-10 14:37:30 +09:00
davidsastresas
9bca2740b2
AP_Camera: backend sends gimbal_device_id in camera_information
2023-08-10 14:37:30 +09:00
davidsastresas
6a9b457be3
GCS_Common: autopilot_state_for_gimbal_device sends angular_velocity_z
2023-08-10 14:37:30 +09:00
Ryan Friedman
578ba20df0
GCS_MAVLink: Use renamed visual odom function
...
* Now called pose instead of position
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
2023-08-10 13:58:00 +09:00
Ryan Friedman
1615038e57
AP_VisualOdom: Change name from position to pose
...
* The function takes position (linear) + orientation (angular), therefore it's a pose, not a position
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
2023-08-10 13:58:00 +09:00
Andrew Tridgell
c8b2622f45
AP_BattMonitor: fixed reset_remaining() for INAxxx and LTC2946
...
these can use the generic reset_remaining() call in the backend
2023-08-10 07:43:25 +10:00
Andrew Tridgell
5722cb584d
AP_Scripting: added BattEstimate lua script
...
this estimates state of charge from resting voltage while disarmed
2023-08-10 07:43:25 +10:00
Peter Barker
6097f1aa61
GCS_MAVLink: allow removal of preflight commands to fail the autopilot
2023-08-10 07:11:22 +10:00
Tom Pittenger
aefc2a8492
AP_RPM: enable AP_RPM to set ESC Telemetry
2023-08-09 12:02:31 -07:00
Randy Mackay
ee07d6bec8
AP_DroneCAN: get/set param timeout after 0.1 sec
2023-08-09 18:10:35 +10:00
Randy Mackay
6fe31396d9
AP_DroneCAN: improve get/set param comments
2023-08-09 18:10:35 +10:00
Peter Barker
77b8c96eae
GCS_MAVLink: add build_options.py option to remove fencepoint protocol
...
also gate more code on defines
Saves ~2kB
2023-08-09 17:53:54 +10:00
Peter Barker
e54baf41f6
AP_Frsky_Telem: add build_options.py option to remove fencepoint protocol
...
also gate more code on defines
Saves ~2kB
2023-08-09 17:53:54 +10:00
Peter Barker
c300beae69
AC_Fence: add build_options.py option to remove fencepoint protocol
...
also gate more code on defines
Saves ~2kB
2023-08-09 17:53:54 +10:00
Andy Piper
9212a24248
AP_HAL_ChibiOS: properly support CRSF on HEEWING-F405
...
update HeeWing F405 README to reflect VTX pinout
2023-08-09 17:44:14 +10:00
Peter Barker
aa5466c6e2
AP_Torqeedo: remove use of HAL_BUILD_AP_PERIPH
...
turn torqeedo off in chibios_hwdef.py instead for Periph
2023-08-09 17:39:49 +10:00
Peter Barker
ceab0180ec
AP_HAL_ChibiOS: remove use of HAL_BUILD_AP_PERIPH
...
turn torqeedo off in chibios_hwdef.py instead for Periph
2023-08-09 17:39:49 +10:00
Peter Barker
a8bb397eb7
AP_MSP: remove references to HAL_BUILD_AP_PERIPH
...
HAL_MSP_ENABLED is already explicitly off in chibios_hwdef.py for Periph
2023-08-09 17:39:49 +10:00
Peter Barker
fb0ebf75ca
AP_RangeFinder: move rangefinder rotation default down into AP_Periph
2023-08-09 17:39:49 +10:00
Peter Barker
68e3b1e79b
AP_HAL_ChibiOS: move rangefinder rotation default down into AP_Periph
2023-08-09 17:39:49 +10:00
Henry Wurzburg
af34b1e43b
AP_Vehicle: add failsafe protections to Mode Takeoff
2023-08-09 17:33:58 +10:00
Andrew Tridgell
2832f8ca76
AP_Arming: fixed auto-enable of fence with forced arm
...
when a user forced armed and had FENCE_AUTOENABLE=3 for enable on
arming then the fence did not enable
2023-08-09 16:08:42 +10:00
Tom Pittenger
0d0ba0f656
AP_TemperatureSensor: add support for MCP9601
2023-08-09 15:49:30 +10:00
Ryan Friedman
6a2a852450
SITL: Implement GSOF SIM
...
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
2023-08-09 12:26:10 +10:00
Asif Khan
f26528edba
AP_Mount: fix GIMBAL_MANAGER_SET_PITCHYAW not working correctly when using multiple gimbals
2023-08-09 10:03:34 +09:00
Asif Khan
47977b1635
AP_Camera: add parameter CAMx_MNT_INST for associating camera with corresponding mount
2023-08-09 10:03:34 +09:00
Asif Khan
ea9f4a79f5
AP_Mount: fix sending camera information and settings for each backend
2023-08-09 10:03:34 +09:00
Asif Khan
09e949173d
AP_Camera: fix sending camera information and settings for each backend
2023-08-09 10:03:34 +09:00
Peter Barker
13c83ee9f8
GCS_MAVLink: enable sending of RELAY_STATUS message
2023-08-09 07:44:07 +10:00
Peter Barker
1e18ca595f
AP_Relay: enable sending of RELAY_STATUS message
2023-08-09 07:44:07 +10:00
Peter Barker
67988320a7
hwdef: disable sending of RELAY_STATUS on mimimized boards
2023-08-09 07:44:07 +10:00
Ryan Friedman
be5d846af0
AP_DDS: Switch topic to cmd_vel
...
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
2023-08-08 15:35:43 +10:00
Ryan Friedman
9b0f485fee
AP_DDS: Add velocity control DDS subscriber
...
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
2023-08-08 15:35:43 +10:00
bnsgeyer
53100c8e96
SITL: fix vertical axis dynamics for autorotation
2023-08-07 22:10:09 -04:00
Andy Piper
fe56a6aedd
AP_HAL_ChibiOS: allow 8 bdshot channels on mRoControlZeroH7
2023-08-08 11:50:56 +10:00
Peter Barker
53d5d1b9a9
AP_HAL_ChibiOS: break out include files for firmware defaults
2023-08-08 11:45:50 +10:00
Peter Barker
5670b8a062
AP_RangeFinder: compile mavlink rangefinder in only if HAL_GCS_ENABLED
2023-08-08 11:39:45 +10:00
Peter Barker
e6ac368972
AP_GPS: make AP_GPS_MAV dependent on HAL_GCS_ENABLED
2023-08-08 11:33:54 +10:00
Peter Barker
6ee9f01ffb
AP_GPS: avoid use of mavlink constructs when GCS not compiled in
2023-08-08 11:33:54 +10:00
Peter Barker
bf005731a9
AP_GPS: tidy is_healthy calculations
...
this removes some duplicate code and simplifies the flow of control
2023-08-08 11:31:18 +10:00
Peter Barker
009172685e
AP_HAL_ChibiOS: avoid use of MINIMIZE_FEATURES define in Copter directory
2023-08-08 10:35:19 +10:00
Peter Barker
3fea8d16f1
AP_HAL: remove MINIMIZE_FEATURES define
2023-08-08 10:35:19 +10:00
Peter Barker
646704c5dc
AP_HAL_ChibiOS: remove MINIMIZE_FEATURES define
2023-08-08 10:35:19 +10:00
Peter Barker
d6979e62f0
GCS_MAVLink: handle mag cal as both COMMAND_LONG and COMMAND_INT
2023-08-08 10:06:13 +10:00
Peter Barker
d50c429355
AP_Compass: handle mag cal as both COMMAND_LONG and COMMAND_INT
2023-08-08 10:06:13 +10:00
Tom Pittenger
1e83e61b25
AP_Networking: fix build for periph
2023-08-07 17:04:27 -07:00
Iampete1
5c09a16a80
AP_BattMonitor: add health logging
2023-08-08 10:04:12 +10:00
Michael du Breuil
935fad54ad
AP_ESC_Telem: Fix some time wrap issues that can lead to using stale data if a ESC stops responding
2023-08-08 09:53:48 +10:00
Michael du Breuil
c1e6f130dd
AP_HAL_ChibiOS: CubeOrange map EXTERN_DRDY and !EXTERN_CS to ADC
2023-08-08 09:16:56 +10:00
Ryan Friedman
843a14ee57
SITL: Add heading and speed_2d utils
...
* These are also needed by the upcoming GSOF PR
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
2023-08-07 08:40:58 -07:00
Henry Wurzburg
8d86503ed5
AP_Motors: correct metadata for H_DDFP_SPIN_MIN param
2023-08-07 07:36:47 -04:00
Ryan Friedman
e0b23ddf8f
AP_HAL_SITL: Rename LORD to MicroStrain
...
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
2023-08-07 19:16:03 +10:00
Ryan Friedman
109c894929
AP_HAL: Rename LORD to MicroStrain
...
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
2023-08-07 19:16:03 +10:00
Ryan Friedman
7c2baa75d9
SITL: Rename LORD to MicroStrain
...
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
2023-08-07 19:16:03 +10:00
Ryan Friedman
cb480d2855
AP_ExternalAHRS: Rename LORD to MicroStrain
...
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
2023-08-07 19:16:03 +10:00
Peter Barker
5d52d7f78b
SITL: add description for SIM_BATT_VOLTAGE
2023-08-07 15:32:31 +10:00
Iampete1
63666ea83a
AP_Scripting: generator: fix dependancy start and end miss-match
2023-08-07 12:33:01 +10:00
muramura
9374b374de
AP_Networking: Change message level from DEBUG to INFO
2023-08-06 17:37:17 -07:00
Peter Barker
37de51f1d4
hwdef: remove un-needed lines in KakuteH7 config
...
these are the default values, and KakuteH7 isn't minimized
2023-08-06 17:36:25 -07:00
Andrew Tridgell
0333e92cbc
hwdef: update SIYI_N7 hwdef
...
the N7 isn't the same as the Durandal. It has 1 CAN bus, and 2 less
UARTs, and an extra compass. This fixes the hwdef.dat to match the
schematic
2023-08-06 09:23:45 +10:00
Andrew Tridgell
e1fad5ee38
AP_Compass: allow override of IST8310 orientation
...
this allows for vendor GPS modules and internal compass which use a
different orientation
2023-08-06 09:23:45 +10:00
Andrew Tridgell
5af7fdf330
AP_Networking: use host byte order addresses internally
...
this should make the lua API easier to handle, as it can manipulate
uint32_t easily
2023-08-06 09:20:08 +10:00
Andrew Tridgell
8ddaf17184
AP_Vehicle: update networking at 10Hz
2023-08-06 09:20:08 +10:00
Andrew Tridgell
fd70f5c7d7
AP_Networking: split ChibiOS code into its own backend
2023-08-06 09:20:08 +10:00
Andrew Tridgell
5705c68954
AP_Networking: cleanup parameter handling and fixed lwip config
2023-08-06 09:20:08 +10:00
Tom Pittenger
8bddd4168b
AP_HAL_ChibiOS: update hwdefs for eth
2023-08-06 09:20:08 +10:00
Tom Pittenger
d59c3d7de0
AP_HAL_ChibiOS: remove common_eth.ld
2023-08-06 09:20:08 +10:00
Tom Pittenger
772465fef3
AP_HAL_ChibiOS: fix whitespace
2023-08-06 09:20:08 +10:00
Tom Pittenger
1e9d00fecb
AP_Networking: cleanup
2023-08-06 09:20:08 +10:00
bugobliterator
f84572a545
AP_HAL_ChibiOS: remove legacy define WATCHDOG_DISABLED
2023-08-06 09:20:08 +10:00
bugobliterator
724b0908e0
AP_Networking: panic if bad memory alignment
2023-08-06 09:20:08 +10:00
bugobliterator
cf6fd6717b
AP_HAL_ChibiOS: fix alignment for Ethernet safe memory
2023-08-06 09:20:08 +10:00
Tom Pittenger
9698291920
AP_HAL_ChibiOS: fix unused var compile error
2023-08-06 09:20:08 +10:00
Tom Pittenger
6d3c5e7a61
AP_Networking: cleanup defines
2023-08-06 09:20:08 +10:00
bugobliterator
13acf60c7e
AP_Networking: fix allocation of mac trx buffers
2023-08-06 09:20:08 +10:00
bugobliterator
5c657cad9a
AP_HAL_ChibiOS: disable AP_Periph_Heavy for CubePilot-CANMod
2023-08-06 09:20:08 +10:00
bugobliterator
7bdee92d77
AP_HAL_ChibiOS: disable CAN2 on CubePilot-CANMod
2023-08-06 09:20:08 +10:00
bugobliterator
4e39318920
AP_HAL_ChibiOS: disable watchdog on CubePilot-CANMod
2023-08-06 09:20:08 +10:00
bugobliterator
50ae1ca7e8
AP_HAL_ChibiOS: update CubePilot-CANMod to support Networking
2023-08-06 09:20:08 +10:00
Tom Pittenger
a4984cb595
AP_Networking: bugfixes for dynamic battery malloc
2023-08-06 09:20:08 +10:00
bugobliterator
558f0272d6
AP_Networking: dynamically allocate memory for MAC Peripheral
2023-08-06 09:20:08 +10:00
bugobliterator
e6b51df7cd
AP_HAL_ChibiOS: dynamically allocate memory for MAC Peripheral
2023-08-06 09:20:08 +10:00
Tom Pittenger
1aff011e52
AP_Networking: astyle changes
2023-08-06 09:20:08 +10:00
Tom Pittenger
90dc58be29
AP_Networking: Enable DHCP as default, add example to default netmasks
2023-08-06 09:20:08 +10:00
Tom Pittenger
ec65b5175b
AP_HAL_ChibiOS: update Networking hwdef's param defaults
2023-08-06 09:20:08 +10:00
Tom Pittenger
f5a1525fd8
AP_Networking: new library
2023-08-06 09:20:08 +10:00
Tom Pittenger
291226eb5d
AP_HAL_ChibiOS: hwdef add support for Networking
2023-08-06 09:20:08 +10:00
Tom Pittenger
f66327d97d
AP_HAL_ChibiOS: Ethernet related memory allocations
2023-08-06 09:20:08 +10:00
Tom Pittenger
3b79ff0ad3
AP_HAL_ChibiOS: add hooks to compile Networking
2023-08-06 09:20:08 +10:00
Tom Pittenger
d841d250d8
AP_HAL_ChibiOS: allow HW without HW_RNG to SW-based create psuedo-random
2023-08-06 09:20:08 +10:00
Tom Pittenger
169a7b1c73
AP_Vehicle: add support for Networking
2023-08-06 09:20:08 +10:00
Henry Wurzburg
86afb1d66b
AP_RangeFinder:correct nooploop max dist
2023-08-05 20:04:41 +10:00
Asif Khan
2141f06967
AP_Camera: add time based triggering support
2023-08-05 18:52:57 +10:00
Andrew Tridgell
3534417a12
AP_Terrain: fixed assumption that HOME is on the ground
...
this fixes height_above_terrain() to give a correct value when HOME is
not on the ground after the user has done a DO_SET_HOME with a
home position that is not at ground level
2023-08-05 08:31:02 +10:00
Karol Pieniący
abc78d1169
libraries: fix delay after subsequent Robotis servo detections
...
This fix probably reflects the original intention of the code author, because without it delays set in detect_servos() are ignored.
Without this fix Dynamixel XC330-T288-T does not start and enters something like a "soft bricked" state (no errors reported, but not responding to any commands). This adds a delay after ping messages so that servos have time to respond to the pings and are ready to be configured further.
2023-08-04 08:55:55 +10:00
Peter Barker
8d30f84e73
GCS_MAVLink: move definition of HAL_HIGH_LATENCY2_ENABLED into config
2023-08-03 13:09:23 +10:00
Andrew Tridgell
ce33149c9d
AP_AHRS: fixed relative home functions to calculate without origin
...
this allows for FENCE_AUTOENABLE on planes with no compass
2023-08-03 13:08:21 +10:00
Andrew Tridgell
b38fde2cf6
AP_AHRS: fixed comments on position functions
2023-08-03 13:08:21 +10:00
Lokesh Ramina
b7a0f47853
AP_BATTMonitor: Reserve ID 28 for AD7091R5 I2C ADC
...
Reserving an ID for a Battmonitor type which reads the analog value from an I2C ADC IC.
2023-08-03 13:03:51 +10:00
rishabsingh3003
0969a28381
AP_Scripting: Add docs for proximity backend
2023-08-03 08:02:49 +09:00
rishabsingh3003
153ff58bd9
AP_Scripting: Add drivers for NoopLoop TOFSense-M CAN and Serial sensors
2023-08-03 08:02:49 +09:00
rishabsingh3003
b6a54bbef9
AP_Scripting: Add scripting proximity driver bindings
2023-08-03 08:02:49 +09:00
rishabsingh3003
601b01ed8b
AP_Proximity: Add backend for scripted Lua Driver
2023-08-03 08:02:49 +09:00
Andy Piper
7238c603c1
AP_HAL_SITL: compile system as double so that time advances
2023-08-02 16:22:59 +01:00
Andy Piper
f726ca1809
Filter: fix notch filter test.
2023-08-02 16:22:59 +01:00
Andrew Tridgell
e97f5d8012
AP_Math: mark test_math_double.cpp as double precision source
...
fixed test_math_double
the wrap check needs to be wrap_PI() as otherwise rounding of 2*PI if
just over 6.28 will give a large error
ensure double tests are double
test_vector2
2023-08-02 16:22:59 +01:00
Andy Piper
d94e36fccc
AP_Common: ensure that constants are float not double if not otherwise declared
...
use correct DOUBLE_PRECISION_SOURCES definition
portably define qsort argument in tests
fix test_location
add test_location to double sources
2023-08-02 16:22:59 +01:00
Peter Barker
31281b5d11
AP_HAL_ChibiOS: eliminate use of MINIMIZE_FEATURES for Plane features
2023-08-02 17:48:25 +10:00
Peter Barker
00bc4a9e8b
AP_GPS: add and use AP_GPS_DRONECAN_ENABLED
2023-08-02 17:46:30 +10:00