Andrew Tridgell
511b0f69f2
AP_Mission: skip aux function in determining if a takeoff
...
and reset landing sequenece flag on a takeoff command
2022-07-12 10:34:26 +10:00
Iampete1
ecc3ae2d05
AP_Logger: Log Structure: remove comma on included AIS structure
2022-07-12 09:39:54 +10:00
Iampete1
8f7cad39cd
AP_AIS: only include log structures if enabled
2022-07-12 09:39:54 +10:00
Iampete1
60408fd16e
hwdef: skyviper: update AP_AIS_ENABLED to AP_AIS_ENABLED
2022-07-12 09:39:54 +10:00
Iampete1
faa414fbdb
AP_AIS: add dummy methods
2022-07-12 09:39:54 +10:00
Iampete1
e8607c09f1
GCS_MAVLink: send ais message
2022-07-12 09:39:54 +10:00
Iampete1
30fffb491c
AP_Vehicle: add AIS
2022-07-12 09:39:54 +10:00
Iampete1
b94e1c5027
AP_AIS: add singleton
2022-07-12 09:39:54 +10:00
Andrew Tridgell
a92161cd18
GCS_MAVLink: improved start battery cell monitoring
...
this fixes two issues:
1) we are not reporting the sag corrected voltage to GCS when we are
sending individual cells
2) we don't cope with having more than AP_BATT_MONITOR_CELLS_MAX
cells (or 12 for low flash boards, 14 for 2M boards)
it fixes this by distributing the extra voltage over the calls.
This change is particularly important for high cell count DroneCAN
smart batteries, where we currently would not handle more than 14
cells and the GCS would display the wrong voltage
the PR also cleans up the use of volts vs mVolts for the local
variables
2022-07-11 14:21:41 +10:00
Shiv Tyagi
489a27ca19
SITL: fix sim_precland orientation bug
2022-07-11 10:10:55 +10:00
RuffaloLavoisier
0e0c23a8e3
AP_Logger : correct spelling on comment
2022-07-11 08:51:27 +09:00
chobitsfan
a723abf986
AP_Motors: reuse spool_step for code refactoring
2022-07-11 08:39:34 +09:00
Andrew Tridgell
0103776d83
Filter: fixed test_notchfilter for the change in allocate_filters()
...
changed for triple notch
2022-07-10 06:57:29 +10:00
Andrew Tridgell
32e1767647
AP_ICEngine: added option to force low throttle on engine off
...
this fixes an issue with EFI engines that use low throttle demand to
stop the engine, instead of using an ignition channel. This option
needs to be set on these aircraft to prevent the idle governor or the
fwd throttle integrator in quadplanes from keeping the engine on when
the pilot asks for it to be off.
2022-07-10 06:56:58 +10:00
Yuri
565f757f35
AP_Scripting: rover-MinFixType example param caching fix
2022-07-07 19:34:10 +09:00
Yuri
6a74be104f
AP_Scripting: add set_desired_speed binding
2022-07-07 19:34:10 +09:00
Yuri
bc8bdc18c9
AP_Vehicle: add set_desired_speed for use in scripting
2022-07-07 19:34:10 +09:00
Andrew Tridgell
39fd4f01cd
AP_Scripting: fixed SimOnHardware build
...
HAL_MOUNT_ENABLED depends on !HAL_MINIMIZE_FEATURES
2022-07-07 12:33:01 +10:00
Iampete1
56c6233be9
AC_AttitudeControl: remove PosControl_Sub
2022-07-05 16:00:03 -03:00
xiao
084bae21ef
HAL_ChibiOS: hwdef: MFE-PixSurveyA1 rename PixSurveyA1
2022-07-05 17:44:03 +10:00
xiao
39abb13692
HAL_ChibiOS: hwdef: add new hardware MFE-PixSurveyA1
2022-07-05 17:44:03 +10:00
Andrew Tridgell
af5eb44629
hwdef: added telem3 on Pixhawk6X
2022-07-05 10:34:36 +10:00
Iampete1
ea4f050aa8
AP_Scripting: Generator: fix docs generator aliasing
2022-07-05 10:31:51 +10:00
Peter Barker
a647cd9b8f
hwdef: remove redundant 'define HAL_MINIMIZE_FEATURES 0'
2022-07-05 10:20:38 +10:00
Peter Barker
80e70b2fb4
AP_InertialSensor: remove voiding of parameter
...
Clearly this is used - we pass it down
2022-07-05 09:54:53 +10:00
Andrew Tridgell
c29b390e7b
AP_InertialSensor: implemented harmonics in SITL vibration
2022-07-03 18:47:33 +10:00
Andrew Tridgell
6b55073508
SITL: added SIM_VIB_MOT_HMNC parameter
2022-07-03 18:47:33 +10:00
Andy Piper
193375a7e5
AP_InertialSensor: implement triple notches
2022-07-03 18:21:41 +10:00
Andy Piper
dfba938e63
Filter: add triple harmonic notches
2022-07-03 18:21:41 +10:00
Andy Piper
9d851a0c1a
AP_InertialSensor: allow concurrent logging of both pre- and post-filter IMU data for FFT
...
remove batch logging bitfields
2022-07-03 18:19:55 +10:00
Andrew Tridgell
2318c0e505
AP_Arming: added Scripting2 CAN protocol to switch
2022-07-03 08:21:55 +10:00
Andrew Tridgell
d8b98789e6
AP_Scripting: add support for scripting2 protocol
2022-07-03 08:21:55 +10:00
Andrew Tridgell
1b25babd8a
AP_CANManager: added scripting2 protocol
...
allows for lua scripts to distinguish two CAN interfaces
2022-07-03 08:21:55 +10:00
Randy Mackay
a7aa77ff86
AP_Scripting: add lua docs for mount methods
2022-07-02 09:21:53 +09:00
Randy Mackay
b8560345f7
AP_Scripting: add mount-test example script
2022-07-02 09:21:53 +09:00
Randy Mackay
47e10eaefa
AP_Scripting: add bindings to control mount
2022-07-02 09:21:53 +09:00
murata
531e92db8f
AP_TECS: Unify coding style for if statements
2022-07-01 11:54:46 -07:00
Peter Barker
db59117b83
SITL: add tests for ICE Planes
2022-07-01 19:33:51 +10:00
Peter Barker
61e65ca5f2
AP_ICEngine: add tests for ICE Planes
2022-07-01 19:33:51 +10:00
François Carouge
84b0f6478c
SITL/SIM_RF_MAVLink: fix incomplete initializer clauses
2022-07-01 18:24:43 +09:00
Yuri
f155c1b027
AP_Scripting: add rover-MinFixType and rover-SaveTurns examples
2022-07-01 18:23:31 +09:00
Andrew Tridgell
eefc41fe30
Filter: added a way to plot attenuation and phase lag for complex filters
2022-06-30 20:58:37 +10:00
Andrew Tridgell
50740124fe
AP_Vehicle: implement INS_HNTCH_FM_RAT
...
this allows for a throttle based harmonic notch min frequency ratio,
allowing for the notch to go below the configured frequency at low
throttle
This is important for quadplanes, but will also benefit multirotors
flying at lower throttle due to lower payload or when descending
This also disables the throttle based harmonic notch when motors are
in SHUT_DOWN state
2022-06-30 20:58:37 +10:00
Andrew Tridgell
366aa7154c
Filter: added FM_RAT for throttle notch frequency ratio
...
allow for configurable min frequency ratio for throttle based notches
2022-06-30 20:58:37 +10:00
Andrew Tridgell
9ac3472b47
AP_InertialSensor: add set_inactive() on notch filters
2022-06-30 20:58:37 +10:00
Peter Barker
c085b713ac
AP_Common: correct comments on get_alt_cm and change_alt_frame
2022-06-30 20:08:24 +10:00
Ryan Beall
77f922a1ae
AP_TECS.cpp: remove line copy error
...
This was a copy paste error that is duplicated in the correct spot (in line 530)
2022-06-30 20:06:33 +10:00
Randy Mackay
f03ac3648d
AP_Mount: fixup handle do-gimbal-manager-pitchyaw flags
2022-06-29 10:56:48 +09:00
Randy Mackay
3b0869d098
AP_Mount: SToRM32_serial restructure and support for ef/bf angle and rate
2022-06-29 10:56:48 +09:00
Randy Mackay
f14f524ff5
AP_Mount: SToRM32 restructure and support for ef/bf angle and rate
2022-06-29 10:56:48 +09:00
Randy Mackay
18fe1d44b7
AP_Mount: Solo restructure and support for ef/bf angle and rate
2022-06-29 10:56:48 +09:00
Randy Mackay
d59e87ea59
AP_Mount: Servo restructure and support for ef/bf angle and rate
2022-06-29 10:56:48 +09:00
Randy Mackay
80b70dcd66
AP_Mount: Gremsy fixup for support of ef/bf angle and rate
2022-06-29 10:56:48 +09:00
Randy Mackay
d17e1b6fab
AP_Mount: Alexmos restructure and support for ef/bf angle and rate
2022-06-29 10:56:48 +09:00
Randy Mackay
0d60e47c68
AP_Mount: backend restructure and support for ef/bf angle and rate
2022-06-29 10:56:48 +09:00
Randy Mackay
f0f95fb812
AP_Mount: frontend adds support for both ef/bf angle and rate
2022-06-29 10:56:48 +09:00
Randy Mackay
c22d8b379f
AP_Mission: do_gimbal_manager_pitchyaw supports bf/ef angles and rates
...
also minor bug fix so verify DO_GIMBAL_MANAGER_PITCHYAW returns true
2022-06-29 10:56:48 +09:00
Randy Mackay
33a4efa936
AP_Mount: move mode, yaw_lock, roi_target and sysid target to backend
2022-06-29 10:56:48 +09:00
Randy Mackay
ec07c15e1e
AP_Mount: set_roi_target and set_target_sysid lose struct and const before args
2022-06-29 10:56:48 +09:00
Randy Mackay
898bdb864c
AP_Mount: fix handle_command_do_mount_configure instance handling
2022-06-29 10:56:48 +09:00
Randy Mackay
e58d72931e
AP_Mount: Solo in sysid target sets lockedToBody
...
Also re-order calls in home-location mode to be consistent with other modes
2022-06-29 10:56:48 +09:00
Randy Mackay
e8ab4eb8b7
AP_Mount: SToRM32_serial provides calc_angle_to_xxx relative_pan argument
2022-06-29 10:56:48 +09:00
Randy Mackay
5958bced0c
AP_Mount: SToRM32 provides calc_angle_to_xxx relative_pan argument
2022-06-29 10:56:48 +09:00
Randy Mackay
57a508b037
AP_Mount: Solo provides calc_angle_to_xxx relative_pan argument
2022-06-29 10:56:48 +09:00
Randy Mackay
3c501bb408
AP_Mount: alexmos provides calc_angle_to_xxx relative_pan argument
2022-06-29 10:56:48 +09:00
Randy Mackay
b0a473ee53
AP_Mount: alexmos minor spell fix
2022-06-29 10:56:48 +09:00
Randy Mackay
f426711177
AP_Mount: backend calc_angle_to_xxx requires relative_pan argument
2022-06-29 10:56:48 +09:00
Randy Mackay
3711c362ce
AP_Mount: update_rate_and_angle_from_rc fix arg name to match units
2022-06-29 10:56:48 +09:00
Randy Mackay
23209ddafd
AP_Mount: gremsy neutral mode leaves ef targets untouched
2022-06-29 10:56:48 +09:00
Peter Barker
5f095304cf
GCS_MAVLink: add AP_LTM_TELEM_ENABLED
2022-06-28 20:19:41 +10:00
Peter Barker
75862b3e27
AP_LTM_Telem: add AP_LTM_TELEM_ENABLED
2022-06-28 20:19:41 +10:00
李孟晓
8a83e02e59
HAL_ChibiOS: hwdef: add support for ICP101XX to CUAV_GPS
2022-06-28 11:59:04 +10:00
李孟晓
522f1fa6de
AP_Baro: add support for ICP101XX
2022-06-28 11:59:04 +10:00
Peter Barker
336a6b0359
AP_BoardConfig: remove reference to CONFIG_ARCH_BOARD_*
...
These are vestiges from when we ran both on ChibiOS and NuttX
2022-06-28 11:21:30 +10:00
François Carouge
e52e64b11c
AP_Math: class template parameters not compliant in constructor declaration
2022-06-28 11:05:53 +10:00
François Carouge
772c80a038
AP_Common: class template parameters not compliant in constructor declaration
2022-06-28 11:05:53 +10:00
Peter Barker
2228f1407d
hwdef: remove unused NO_DATAFLASH hwdef directive
2022-06-28 11:03:53 +10:00
Andy Piper
feaad96963
AP_HAL_ChibiOS: hwdef for Foxeer Reaper F745v2.
...
README for Reaper F745v2
2022-06-28 11:03:26 +10:00
Peter Barker
c2091fdef5
AP_GPS: fix clang++ warnings on static inits
...
these are static variables so don't need zeroing anyway...
2022-06-28 10:20:30 +10:00
Peter Barker
16ea4f03b6
AP_Compass: fix clang++ warnings on static inits
...
these are static variables so don't need zeroing anyway...
2022-06-28 10:20:30 +10:00
Peter Barker
b11cd3b69d
AP_Baro: fix clang++ warnings on static inits
...
these are static variables so don't need zeroing anyway...
2022-06-28 10:20:30 +10:00
Peter Barker
1185da02a6
AP_Airspeed: fix clang++ warnings on static inits
...
these are static variables so don't need zeroing anyway...
2022-06-28 10:20:30 +10:00
Bill Geyer
2377d7a2c3
AC_AttitudeControl: move input_shaping_rate into input_shaping_ang_vel
2022-06-28 07:56:12 +09:00
Bill Geyer
be65358cc1
AC_AttitudeControl: incorporate suggested changes
2022-06-28 07:56:12 +09:00
Bill Geyer
355524206b
AC_AttitudeControl: modify constructor to allow defaults
2022-06-28 07:56:12 +09:00
Bill Geyer
fd24b3912f
AC_AttitudeControl: add comments
2022-06-28 07:56:12 +09:00
Bill Geyer
1cd537895e
AC_AttitudeControl: add command model class for parameters
2022-06-28 07:56:12 +09:00
Bill Geyer
a547916ebf
AC_AttitudeControl: only use rate shaping tc if tc is nonzero
2022-06-28 07:56:12 +09:00
bnsgeyer
7594f7a558
AC_AttitudeControl: incorporate sqrt controller in rate shaping
2022-06-28 07:56:12 +09:00
Andrew Tridgell
864353aa4d
AP_Scripting: example script for lidar control
...
enable lidar for only landing in quadplanes by changing RNGFND_LANDING
2022-06-26 08:46:44 +10:00
Andrew Tridgell
a941e4cd41
AP_NavEKF: re-implemented EKF ring buffer
...
this fixes a bug where elemnts being pushed into the buffer more
slowly than we recall can be lost
for example, if you push a single element in then try a recall it will
fail
2022-06-24 20:25:39 +10:00
Andrew Tridgell
19da623077
AP_NavEKF: added test suite for EKF ring buffer
2022-06-24 20:25:39 +10:00
Andrew Tridgell
ba10c0ae42
AP_BattMonitor: make healthy() check all configured monitors
...
GCS reporting for SYS_STATUS should check all healthy, not just first
backend
2022-06-24 11:13:16 +10:00
Andrew Tridgell
93ee9a4ac1
AP_BattMonitor: allow INA2xx battery monitors to be powered after boot
...
the device doesn't show up till main battery is connected, so we need
this change to allow for separate avionics battery and main battery
with avionics battery powered on first
2022-06-24 11:13:16 +10:00
Andrew Tridgell
9a6fb19208
AP_BattMonitor: report arming unhealthy if backend unhealthy
...
important for i2c based battery backends
2022-06-24 11:13:16 +10:00
Peter Barker
1f4ebb49b5
AP_Mount: document point-at-home default mode option
2022-06-23 16:37:54 +10:00
Andrew Tridgell
5f8ea596a5
hwdef: changed Pixhawk6C board type to 56
...
production bootloader uses 56
2022-06-23 13:43:38 +10:00
Peter Barker
2d3092407f
AP_HAL_Empty: move implementations of functions to header
...
Makes it much clearer what's implemented and what's dangling
2022-06-23 12:38:41 +10:00
Andrew Tridgell
881d9764d4
hwdef: added Pixhawk6C support
2022-06-23 12:37:24 +10:00
Andrew Tridgell
4d031a0c9e
AP_Compass: HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE for Pixhawk6C
2022-06-23 12:37:24 +10:00
Andrew Tridgell
e48f405c08
AP_Compass: removed "AK09916 Wrong id" message
...
we don't need this on every board that doesn't have an I2C AK09916
2022-06-23 12:37:24 +10:00
Andrew Tridgell
b1e3b9414b
hwdef: fixed Pixhawk6X ALT_RAM_MAP check
2022-06-23 12:37:24 +10:00
Peter Barker
f4df4298a0
AP_RangeFinder: make LeddarOne calculations more efficient
2022-06-22 21:15:18 +10:00
Peter Barker
90362a4849
AP_RangeFinder: tighten scope of stack variable definition
2022-06-22 21:15:18 +10:00
Peter Barker
6923f20ce6
AP_RangeFinder: stop persisting detections in LeddarOne driver
...
We don't use these readings except immediately after where we store them - so don't store them persistently.
2022-06-22 21:15:18 +10:00
Andy Piper
1287fc4fff
AC_AttitudeControl: reset throttle mix to used mix when scaling mix down
2022-06-22 16:17:26 +09:00
Dr.-Ing. Amilcar do Carmo Lucas
f7d21b63a7
AP_FETTecOneWire: Fix the recent change of NUM_SERVO_CHANNELS > 24
2022-06-22 11:51:23 +10:00
Randy Mackay
45cd158b1c
AP_Mount: gremsy searches for gimbal while disarmed
2022-06-21 13:37:11 +09:00
Randy Mackay
a47ac7430b
AP_Arming: add mount pre-arm check
2022-06-21 13:37:11 +09:00
Randy Mackay
8ba8c67452
AP_Mount: gremsy implements healthy
2022-06-21 13:37:11 +09:00
Randy Mackay
822ee75e20
AP_Mount: add healthy and pre_arm_checks
...
Co-authored-by: olliw42 <waldmanns@gmx.de>
2022-06-21 13:37:11 +09:00
Randy Mackay
10da8a42bd
AP_Mount: replace JSTICK_SPD with RC_RATE
2022-06-21 13:37:11 +09:00
Isaac A
94064175af
AP_HAL_ChibiOS: Allow KakuteF7 initialization without baro
2022-06-21 10:03:08 +10:00
Iampete1
dc0491a8ff
AP_AHRS_view: add rotate method to move from AHRS to AHRS view referance frames
2022-06-21 10:01:30 +10:00
TunaLobster
0027660f3f
AP_RCMapper: Increase parameter metadata range to match NUM_RC_CHANNELS
2022-06-21 09:57:44 +10:00
Peter Barker
deba0b712b
AP_RangeFinder: correct creation/use of TFMINI_ADDR_DEFAULT
...
Named incorrectly and defined in wrong file...
2022-06-21 09:15:20 +10:00
Peter Barker
05131853d8
AP_UAVCAN: allow rangefinder backends to be individually compiled in
2022-06-21 09:15:20 +10:00
Peter Barker
3a347d32ca
AP_RangeFinder: allow rangefinder backends to be individually compiled in
2022-06-21 09:15:20 +10:00
Peter Barker
ce1bb906b7
AP_HAL_ChibiOS: allow rangefinder backends to be individually compiled in
2022-06-21 09:15:20 +10:00
Peter Barker
4e438464d7
AP_Baro: tidy probing of external i2c baros
2022-06-21 09:09:55 +10:00
Bill Geyer
4bb3b08a4a
AC_AutoTune: fix tradheli bug with load gain set
2022-06-20 13:00:53 +09:00
TunaLobster
afaca4b5f6
AP_RCMapper: Remove APM 2.x reference in parameter description
2022-06-18 08:26:40 +09:00
Andrew Tridgell
2e1af59057
AP_Rangefinder: fixed scaling on PWM driver and enable SCALING parameter
...
this fixes a bug introduced here:
https://github.com/ArduPilot/ardupilot/pull/18829
and allows the scaling of PWM rangefinders to be adjusted
2022-06-17 08:21:44 +10:00
Andrew Tridgell
7e4fb803a2
AC_AttitudeControl: reduced default quadplane VTOL pos XY gains
2022-06-16 21:26:49 +10:00
Shiv Tyagi
c339b1d374
SIM_Precland: add option to set orientation of precland device in sitl
2022-06-16 12:43:55 +10:00
Randy Mackay
1400eba400
AP_Mount: minor include and definition re-order and fixup
2022-06-15 18:08:58 +10:00
Randy Mackay
d24d3c0af8
AP_Mount: add HAL_MOUNT_STORMSERIAL_ENABLED build option
2022-06-15 18:08:58 +10:00
Randy Mackay
59916d0327
AP_Mount: add HAL_MOUNT_STORM32MAVLINK_ENABLED build option
2022-06-15 18:08:58 +10:00
Randy Mackay
4f0ee1276b
AP_Mount: add HAL_MOUNT_SERVO_ENABLED build option
2022-06-15 18:08:58 +10:00
Randy Mackay
e2106e63bf
AP_Mount: add HAL_MOUNT_ALEXMOS_ENABLED build option
2022-06-15 18:08:58 +10:00
Randy Mackay
8f51e28242
AP_RobotisServo: disable with minmimize features and 1mb flash
2022-06-15 18:05:44 +10:00
Randy Mackay
91d33c885e
AP_Volz: disable with minmimize features
2022-06-15 18:05:44 +10:00
Andrew Tridgell
06a9a1521c
AP_GPS: added GPS_DRV_OPTIONS bit for ellipsoid height
2022-06-15 17:30:28 +10:00
Andrew Tridgell
509f03f946
AP_GPS: cleanup driver option access
...
use option_set() to make code clearer
2022-06-15 17:30:28 +10:00
Andrew Tridgell
8f3405d308
hwdef: added Pixhawk6X support
...
a new H753 based board similar to the Pixhawk5X
2022-06-15 17:28:40 +10:00
Andrew Tridgell
9efcad3adf
HAL_ChibiOS: added support for ALT_RAM_MAP on H7
...
for compatibility with the px4 H7 bootloader
2022-06-15 17:28:40 +10:00
Andrew Tridgell
308717d5eb
HAL_ChibiOS: enable ITCM and DTCM on H7 at startup
...
these may have been disabled by the px4 H7 bootloader
2022-06-15 17:28:40 +10:00
Andy Piper
25785e12d9
AP_RCTelemetry: don't spam mode changes on CRSF startup
...
rewrite device ping bootstrap to avoid ping flood
enable device pings on CRSF in the event of TX loss.
only send pings if not negotiating the version
2022-06-15 17:20:36 +10:00
Andy Piper
9b8ea8475d
AP_RCProtocol: reset UART on RX failure for CRSF
...
update CRSF timestamps to use microseconds
implement RX liveness protocol and implement for CRSF
2022-06-15 17:20:36 +10:00
Andy Piper
ed6f7fb9e9
AP_HAL_ChibiOS: add support for MambaF405 2022 MK4
...
mark DMA on MambaF405US-I2C UARTs
correct RSSI pin on MambaF405US-I2C
2022-06-15 17:05:41 +10:00
Randy Mackay
34f327404a
AP_Mount: Gremsy only enabled on >1MB boards
2022-06-15 09:07:14 +09:00
Randy Mackay
1fca72a831
GCS_MAVLink: add comment re sending locations to mounts
2022-06-15 09:07:14 +09:00
Randy Mackay
e595da41e6
AP_Mount: gremsy uses gimb-dev-att-send to retract gimbal
...
this replaces the MAV_CMD_USER_1 method
2022-06-15 09:07:14 +09:00
Randy Mackay
14c81099db
AP_Mount: add Gremsy driver
...
Co-authored-by: bugobliterator <siddharthbharatpurohit@gmail.com>
this drivers special features include
sends ATTITUDE and AUTOPILOT_STATE_FOR_GIMBAL
support of RC rate targets
captures and re-forwards gimbal_device_attitude_status
2022-06-15 09:07:14 +09:00
Randy Mackay
6723a0fc55
AP_Mount: handle gimbal_device_attitude_status
2022-06-15 09:07:14 +09:00
Randy Mackay
247697ccc4
AP_Mount: add support for DO_GIMBAL_MANAGER_PITCHYAW mavlink command
2022-06-15 09:07:14 +09:00
Randy Mackay
8092697c1a
AP_Mount: backend record RC rate targets
2022-06-15 09:07:14 +09:00
Randy Mackay
f157e5a073
AP_Mount: add set_yaw_lock
2022-06-15 09:07:14 +09:00
Randy Mackay
589102b7d7
AP_Mission: add DO_GIMBAL_MANAGER_PITCHYAW support
2022-06-15 09:07:14 +09:00
Randy Mackay
640a4b1a5f
RC_Channel: add mount lock aux function
2022-06-15 09:07:14 +09:00
Randy Mackay
f83b4cdb40
GCS_MAVLink: support sending AUTOPILOT_STATE_FOR_GIMBAL_DEVICE
2022-06-15 09:07:14 +09:00
bugobliterator
4dd66fed4b
GCS_MAVLink: forward gimbal-device-information to AP_Mount
...
Co-authored-by: Randy Mackay <rmackay9@yahoo.com>
also forward gimbal_device_attitude_status
2022-06-15 09:07:14 +09:00
Randy Mackay
c19d5391d9
AP_Vehicle: add get_rate_bf_targets method
2022-06-15 09:07:14 +09:00
Randy Mackay
0975da6068
AP_Mount: remove virtual distructor from backend
2022-06-15 09:07:14 +09:00
Randy Mackay
b6d7601a55
AP_Mount: SToRM32 minor comment fix
...
also move definitions to cpp file
2022-06-15 09:07:14 +09:00
Tom Pittenger
c28db6d91c
AP_HAL_ChibiOS: Durandal hwdef to enable Sagetech MXS driver by default for CI to test against
2022-06-14 07:10:17 -07:00
Tom Pittenger
7b681d55a8
AP_ADSB: fix sagetech MXS SDK linking error
2022-06-14 07:10:17 -07:00
Chuck Faber
c0b2b679a1
AP_ADSB: Added Sagtetech MXS Driver and it's SDK
2022-06-14 07:10:17 -07:00
Tom Pittenger
0645aee865
AP_ADSB: Driver cleanup and refactor
2022-06-14 07:10:17 -07:00
Tom Pittenger
07be987073
AP_HAL_ChibiOS: enable SagetechMXS driver by default only for CUAV-X7 and CubeOrange
2022-06-14 07:10:17 -07:00
mateksys
71b9e80c04
hwdef: added more PWM options in MatekL431-Dshot
2022-06-14 18:59:52 +10:00
Andy Piper
4068337971
AP_HAL_ChibiOS: correct UART RX stats
2022-06-14 10:25:17 +10:00
Andrew Tridgell
064b6c8a9d
AP_ESC_Telem: use send_struct mavlink function
...
saves some flash, cpu and stack, but means we need a cast
2022-06-14 10:11:03 +10:00
Andy Piper
619fa021e7
AP_GyroFFT: make sure the parameters are updated at least once on startup
2022-06-14 10:09:18 +10:00
Andy Piper
24e47ea08d
AP_Arming: make sure FFT gets initialized when arming checks are off
2022-06-14 10:09:18 +10:00
James Harton
b963be7ee8
AP_HAL_ChibiOS: Add on-board baro support to iFlight BeastH7 V2 target.
...
iFlight's own website says that there is no barometer on this device,
however on my one there is a DPS310 connected on I2C. This PR adds
support for the on-board baro but leaves it as optional.
2022-06-14 09:46:46 +10:00
Peter Barker
5a1d4f3bf5
AP_AHRS: update rotation based on board_orient parameter
2022-06-12 17:32:11 +10:00
Andrew Tridgell
7928fa6e69
Filter: added a NotchFilter test suite
2022-06-12 15:39:44 +10:00
Andrew Tridgell
7c782dda88
Filter: fixed ordering of samples in notch reset
2022-06-12 15:39:44 +10:00
Andrew Tridgell
d653499efc
AP_InertialSensor: count filters to match notch options
...
this allows for much more complex filter setups as long as not
filtering on all IMUs
2022-06-12 15:39:44 +10:00
Andrew Tridgell
d07761cfd9
Filter: fixed reset of notch filters
...
when we reset a notch we need to init the stored values to the current
value, rather than assuming that zero is the right value
this matters when switching IMUs in flight when we are only running
notch filters on the active gyro
2022-06-12 15:39:44 +10:00
Andrew Tridgell
a37f268dc6
Ap_Inertialsensor: by default only run harmonic notch on the active gyro
...
this should save quite a lot of CPU. Only the active gyro impacts
vehicle flight
2022-06-12 15:39:44 +10:00
Andrew Tridgell
9e3a29bf86
Filter: added EnableOnAllIMUs option to harmonic notch filter
2022-06-12 15:39:44 +10:00
Peter Barker
39b7f63140
AP_Beacon: stop passing serialmanager into beacon constructor
2022-06-11 16:02:37 +10:00
Dr.-Ing. Amilcar do Carmo Lucas
d3eae308da
Filter: NFC spell corrections in comments
2022-06-11 08:43:03 +09:00
Andrew Tridgell
c01e21dcb3
AP_FETtecOneWire: cleanup mask handling
...
use unsigned masks
2022-06-10 13:46:43 +10:00
Andrew Tridgell
3a1fc0f338
AP_ESC_Telem: disable ESC telem with zero channels
...
this prevents a build error and saves flash
2022-06-10 13:46:43 +10:00
Andrew Tridgell
cd8ff2b37a
AP_ESC_Telem: added ESC_TLM_MAV_OFS parameter
...
this allows for the ESC telemetry to be remapped to a lower range for
GCS displays. Users often want their quadplane ESCs to show up as ESCs
1 to 8 instead of the high numbers used internally
2022-06-10 13:46:43 +10:00
Andrew Tridgell
42624bdbeb
AP_Vehicle: added parameter table for ESC telemetry
2022-06-10 13:46:43 +10:00
Andrew Tridgell
aedf465049
AP_ESC_Telem: support ESC telem for ESCs 13 to 32
...
also fix a mavlink buffer starvation issue
2022-06-10 13:46:43 +10:00
Randy Mackay
a358357951
AP_Scripting: remove ToshibaCAN support
2022-06-10 12:08:05 +09:00
Randy Mackay
2a264b0331
SRV_Channel: remove ToshibaCAN support
2022-06-10 12:08:05 +09:00
Randy Mackay
85b9e6e57c
GCS_MAVLink: remove ToshibaCAN support
2022-06-10 12:08:05 +09:00
Randy Mackay
533a16287e
AP_CANManager: remove ToshibaCAN support
2022-06-10 12:08:05 +09:00
Randy Mackay
d503246be2
AP_Arming: remove ToshibaCAN support
2022-06-10 12:08:05 +09:00
Randy Mackay
02faacf448
AP_ToshibaCAN: remove support
2022-06-10 12:08:05 +09:00
Andrew Tridgell
d85fe81537
AP_EFI: fixed bug in Lutan driver
...
we need to send an initial request pkt if no data from Lutan
2022-06-09 21:10:37 +10:00
Andrew Tridgell
9ddd1afb34
AP_EFI: added DroneCAN EFI driver
2022-06-09 21:10:37 +10:00
Andrew Tridgell
465dbd89f4
AP_UAVCAN: support DroneCAN EFI
2022-06-09 21:10:37 +10:00
Andrew Tridgell
085413865a
hwdef: added MatekL431-EFI
2022-06-09 21:10:37 +10:00
Andrew Tridgell
0fad35112f
AP_EFI: allow EFI to be used in AP_Periph
2022-06-09 21:10:37 +10:00
Andrew Tridgell
998072f600
AP_Scripting: setup axis filters when starting an axis
2022-06-09 13:15:13 +10:00
Andrew Tridgell
4bc697dfa2
AP_Scripting: added QUIK_AUTO_SAVE option
...
allows tuning with 2 position switch
2022-06-09 13:15:13 +10:00
Andy Piper
fafa4158dd
AP_HAL_ChibiOS: hwdef for MambaH743v4
...
support BMI270 on MambaH743v4 and increase flash SPI clock
add bi-directional dshot to MambaH743
add README and pinout for MambaH743
2022-06-08 21:44:21 +10:00
Andy Piper
11f5d1974a
AP_InertialSensor: don't print error when probing non-existant BMI270
...
fix device locking at startup on BMI270
2022-06-08 21:44:21 +10:00
Andy Piper
f666ed8ec7
AP_Logger: support W25N01GV flash chips
...
add separate driver for W25N01GV triggered via HAL_LOGGING_DATAFLASH_DRIVER
move flash_test() into AP_Logger_Block.
cleanup use of 4k sector commands to account for chips that only have block commands
2022-06-08 21:44:21 +10:00
Andy Piper
6cacdd1b34
AP_InertialSensor: properly reset MPU6000 signal path at startup
...
failure to reset the signal path as per the register spec leads to
very poor temperature response early on in startup.
2022-06-08 17:44:17 +10:00
Andy Piper
fe29324828
AP_RCProtocol: check for bad frames in CRSF decoding.
2022-06-08 17:35:03 +10:00
Iampete1
702245f89e
AP_Math: calc_lowpass_alpha_dt: remove unused constrain
2022-06-08 17:11:08 +10:00
Andrew Tridgell
eed14b3688
AP_Airspeed: fixed autotest for copter param parse
...
This command was failing:
Tools/autotest/param_metadata/param_parse.py --vehicle Copter
I don't understand why it starts to fail now, but this is the fix
2022-06-08 09:23:04 +10:00