Peter Barker
d131cf01d3
AP_AHRS: use compass reference rather than pointer
2021-07-30 17:37:08 +10:00
Peter Barker
d5ea202c20
AP_Compass: mark COMPASS_ENABLED as @RebootRequired
2021-07-30 12:19:42 +10:00
Peter Barker
431c186306
GCS_MAVLink: use AP::compass().available in place of enabled()
2021-07-30 12:19:42 +10:00
Peter Barker
c351150a46
AP_Compass: use AP::compass().available in place of enabled()
2021-07-30 12:19:42 +10:00
Peter Barker
78e63a8852
AP_NMEA_Output: stop using AHRS as conduit for Compass pointer
2021-07-30 12:19:42 +10:00
Peter Barker
c34284b6eb
AP_NavEKF3: stop using AHRS as conduit for Compass pointer
2021-07-30 12:19:42 +10:00
Peter Barker
dec4ba86b6
AP_NavEKF2: stop using AHRS as conduit for Compass pointer
2021-07-30 12:19:42 +10:00
Peter Barker
dc82487fae
AP_Mount: stop using AHRS as conduit for Compass pointer
2021-07-30 12:19:42 +10:00
Peter Barker
b5b4ec94c9
AP_DAL: stop using AHRS as conduit for Compass pointer
2021-07-30 12:19:42 +10:00
Peter Barker
1d9bfdf8dd
AP_Compass: stop using AHRS as conduit for Compass pointer
2021-07-30 12:19:42 +10:00
Peter Barker
ca58aa9c5f
AP_AHRS: stop using AHRS as conduit for Compass pointer
2021-07-30 12:19:42 +10:00
Peter Barker
74859095a9
AP_DAL: add and use compass.available()
...
Covers both being enabled and initialised
2021-07-30 12:19:42 +10:00
Peter Barker
658c978c9d
AP_Compass: add and use compass.available()
...
Covers both being enabled and initialised
2021-07-30 12:19:42 +10:00
Peter Barker
8bbed968de
AP_Compass: remove unused variable
2021-07-30 12:19:42 +10:00
Tatsuya Yamaguchi
4f12c94346
AC_Avoidance: handle upward proximity enable and disable
2021-07-30 12:04:50 +10:00
Peter Barker
e4bceb2417
AP_AHRS: move AOA/SSA to AP_AHRS, don't recalc on fetch
2021-07-30 11:23:06 +10:00
Andrew Tridgell
4df62ce719
HAL_ChibiOS: added mRo-M10095 G491 peripheral
2021-07-30 10:20:52 +10:00
Andrew Tridgell
4fce1ae092
HAL_ChibiOS: added G491 support
2021-07-30 10:20:52 +10:00
Andrew Tridgell
0e7c2a27a6
AP_GPS: added arming checks for yaw available on ublox RTK rover
2021-07-30 06:51:21 +10:00
Iampete1
bb624074dd
APM_Control: remove outdated tuning guide
2021-07-28 18:26:31 +10:00
Iampete1
4b28f53644
AP_Scripting: add change alt frame method to location userdata
2021-07-28 18:19:23 +10:00
Iampete1
88d4ada96d
AP_Vehicle: #ifdef scripting specific functions
2021-07-28 18:18:32 +10:00
Iampete1
e5d4620372
AP_Compass: update orientation param values
2021-07-28 18:09:05 +10:00
Iampete1
9cceb2d5c1
AP_AHRS: update orientation param values
2021-07-28 18:09:05 +10:00
Iampete1
22100dd37c
AP_Math: move to 32 digit rotation constants
2021-07-28 18:09:05 +10:00
Iampete1
78e025af39
AP_Compass: add Calibrator index test
2021-07-28 18:09:05 +10:00
Iampete1
5ecfd3fbce
AP_Math: remove unused ROTATION_MAX_AUTO_ROTATION define
2021-07-28 18:09:05 +10:00
Iampete1
36a80d46e3
AP_Compass: support auto orientation for new rotations
2021-07-28 18:09:05 +10:00
Iampete1
dbd95f8163
AP_Math: make duplicate rotations clear
2021-07-28 18:09:05 +10:00
Iampete1
080f6c295c
AP_Math: examples: rotations: add test for duplicate rotations.
2021-07-28 18:09:05 +10:00
Iampete1
f8220a8adf
AP_Math: tests: test quaternion rotation is the same as vector
2021-07-28 18:09:05 +10:00
Iampete1
6c5424aad6
AP_Math: add roll +- 45 rotations
2021-07-28 18:09:05 +10:00
Andrew Tridgell
4b9311d87d
AP_Motors: added new MOT_PWM_TYPE=8 for PWM range
...
this allows multirotors to set individual PWM ranges per motor. This
is needed for heliquads flying as multirotors
2021-07-28 17:40:40 +10:00
Hwurzburg
8b7b4d6796
AP_HAL_Chibios: Change RC in to RCINT to free a DMA channel
2021-07-28 17:24:06 +10:00
Peter Barker
f557d41145
AP_AHRS: rotate quaternions into vehicle body frame
...
DCM was having it both ways depending on whether it was
primary/secondary.
These are mostly uses for reporting, in which case you would expect the
quaternion to match the eulers.
2021-07-28 17:20:28 +10:00
Peter Barker
ad89e9777c
GCS_MAVLink: send primary quat in ATTITUDE_QUATERNION
2021-07-28 17:20:28 +10:00
Peter Barker
118d3f085f
AP_Math: quaternion: add from_euler(Vector3&)
2021-07-28 17:20:28 +10:00
Andrew Tridgell
0f3dc195b6
AP_InertialSensor: fixed build warning
2021-07-27 19:50:21 +10:00
Andrew Tridgell
aa0a77049e
AP_Compass: fixed build warning on g++ 10.2
2021-07-27 19:50:21 +10:00
Peter Barker
5160b4f6ca
AP_AHRS: move AP_NMEA_Output to AHRS frontend
2021-07-27 16:55:35 +10:00
Iampete1
7d3fa242d7
RC_Channel: add AUTO RTL option
2021-07-27 09:00:11 +09:00
Iampete1
32b3c8ea08
AP_Mission: caculate distance to do_land_start with no location correctly
2021-07-27 09:00:11 +09:00
Iampete1
cea54c48cd
AP_BattMoniter: add Auto RTL option
2021-07-27 09:00:11 +09:00
Iampete1
9047b19e59
AP_Scripting: bindings for CANFrame and ScriptingCANBuffer
2021-07-27 09:04:17 +10:00
Iampete1
44276be3a1
AP_Scripting: add CANSensor and manaul bindings to load.
2021-07-27 09:04:17 +10:00
Iampete1
e29dd0e7e7
AP_Scripting: add CAN read and write examples
2021-07-27 09:04:17 +10:00
Iampete1
8c7cad8663
AP_Scripting: generator support depends keyword on AP_Object
2021-07-27 09:04:17 +10:00
Iampete1
432793a18a
AP_Arming: support scripting CAN driver
2021-07-27 09:04:17 +10:00
Iampete1
bd36053abc
AP_CANManager: support scripting CAN driver
2021-07-27 09:04:17 +10:00
mateksys
08cd1171bf
Tools: added MatekF765-SE to autobuild
2021-07-26 18:13:46 +10:00
Hwurzburg
207de0ed4d
AP_Landing: remove DeepStall from 1MB boards
2021-07-26 16:19:12 +10:00
Hwurzburg
8ec4b77cd7
AP_SerialManager: relabel protocol 29 to avoid confusion with CRSF RC
2021-07-26 14:40:43 +09:00
Andrew Tridgell
cbb2ba8d62
SRV_Channel: added doc of SERVOn_FUNCTION=-1 for GPIO
2021-07-26 15:12:17 +10:00
Peter Barker
2cdc4f5698
AP_HAL: add basic tests for ringbuffer
2021-07-26 15:10:01 +10:00
Andrew Tridgell
90aed6f338
AP_HAL: fixed get_size() on ObjectBuffer to be consistent with set_size()
2021-07-26 15:10:01 +10:00
bugobliterator
3d03979b16
GCS_MAVLink: add support for mavlink out on AP_Periph
2021-07-26 13:45:43 +10:00
Isaac Alich
35beae6037
AP_HAL_ChibiOS: Make final tweaks to MambaF405US-I2C
2021-07-25 17:44:22 +10:00
Isaac Alich
bdcb32456e
AP_HAL_ChibiOS: Add support for MambaF405US-I2C based boards
2021-07-25 09:28:17 +10:00
MHefny
280788bfdf
AP_HAL_LINUX:toggle gpio port
2021-07-24 09:16:08 -07:00
Andrew Tridgell
d95f6c8c2f
AP_Arming: added button arming check
2021-07-24 18:18:57 +10:00
Andrew Tridgell
d8b8facdd0
HAL_ChibiOS: fixed off by 1 bug in GPIO check
2021-07-24 18:18:57 +10:00
Andrew Tridgell
ef93165f28
AP_Button: added arming check
2021-07-24 18:18:57 +10:00
Andrew Tridgell
45cf726a4b
APM_Control: new autotune scheme
...
this separately tunes D and then P, which more closely follows the
technique used for a manual tune
2021-07-24 15:32:55 +10:00
bugobliterator
98f5eb28db
AP_RangeFinder: use separate register_driver method while contructing CAN Driver
2021-07-23 16:01:29 +10:00
bugobliterator
59242739c7
AP_EFI: use separate register_driver method while contructing CAN Driver
2021-07-23 16:01:29 +10:00
bugobliterator
e553acd3e3
AP_BattMonitor: use separate register_driver method while contructing CAN Driver
2021-07-23 16:01:29 +10:00
bugobliterator
6e61867e7f
AP_CANSensor: create a separate register driver method
2021-07-23 16:01:29 +10:00
Andrew Tridgell
c5ef672fb5
AP_Math: fixed expo_curve()
...
doesn't make sense as constexpr
2021-07-23 14:47:14 +10:00
Tatsuya Yamaguchi
a3e176284d
AP_Scripting: add AP_InertialSensor binding
2021-07-23 09:32:04 +09:00
Peter Barker
88d49effe7
AP_AHRS: move variable init into variable declaration
2021-07-23 09:55:14 +10:00
Peter Barker
15e5831002
AP_AHRS: remove unused get_expected_mag_field method
...
there's get_mag_field_NED on AP_AHRS....
2021-07-23 09:55:14 +10:00
Peter Barker
5b372dae06
AP_AHRS: stop storing gyro drift rate as variable
...
This is constant and is just folded into whereever it is used.
2021-07-23 09:55:14 +10:00
Peter Barker
a4d98a457b
AP_AHRS: move init of dcm state into variable declarations
2021-07-23 09:55:14 +10:00
Peter Barker
4f9201a160
AP_AHRS: move parameters back into AP_AHRS.h
...
metadata collection kind of dies otherwise
2021-07-22 21:21:40 +10:00
Peter Barker
d351b7c7dc
AP_AHRS: fix includes for moved files
2021-07-22 21:21:40 +10:00
Peter Barker
b7d4166b28
AP_AHRS: rename AP_AHRS_NavEKF.* to AP_AHRS.*
2021-07-22 21:21:40 +10:00
Peter Barker
97b394a5ef
AP_AHRS: rename AP_AHRS.* to AP_AHRS_Backend.*
2021-07-22 21:21:40 +10:00
Paul Riseborough
17ead96250
AP_NavEKF3: Revert IMU and wind speed process noise parameter defaults
...
These give noisier state estimates, but are more robust to rapid changes in IMU biases.
TODO implement a means of using the modified parameters when there are more than one EKF instance running with IMU's that are sampling at a higher rate.
2021-07-22 18:20:45 +10:00
Paul Riseborough
aa6ac4a874
AP_NavEKF3: retune wind process noise for better airspeed fault detection
2021-07-22 18:20:45 +10:00
Paul Riseborough
8fd1e98701
AP_NavEKF3: Fix bug preventing copter wind estimation at low speed
...
Also re-tunes process noise default for smoother wind velocity state estimates.
2021-07-22 18:20:45 +10:00
Paul Riseborough
0088b0f3fe
AP_NavEKF3: Revert EK3_BETA_MASK parameter extension
...
These are not required due to use of bit 7 in FLIGHT_OPTIONS to achieve the same function.
2021-07-22 18:20:45 +10:00
Paul Riseborough
59d31cc7d5
AP_NavEKF3: Rework non-airspeed wind estimation
...
Faster wind estimation when not using airspeed with acceptable noise in wind velocity estimates.
2021-07-22 18:20:45 +10:00
Paul Riseborough
5fa3ed5755
AP_NAvEKF3: use #define value for bad IMU hold time
2021-07-22 18:20:45 +10:00
Paul Riseborough
7497590363
AP_NavEKF3: Increase lower state variance limit when vibration affected
...
This makes state corrections from GPS and baro observations more aggressive
2021-07-22 18:20:45 +10:00
Paul Riseborough
3e123c0a30
AP_NavEKF3: Use sensor variance when checking for bad IMU
2021-07-22 18:20:45 +10:00
Paul Riseborough
e3bdbcd8ea
AP_NavEKF3: Make bad IMU status more persistent
2021-07-22 18:20:45 +10:00
Paul Riseborough
8f1b98a0cb
AP_AHRS: Add accessor function for vibration affected status
...
AP_AHRS: fix rebase build error
2021-07-22 18:20:45 +10:00
Paul Riseborough
ccc95d8726
AP_NavEKF3: Add accessor function for vibration affected status
2021-07-22 18:20:45 +10:00
Paul Riseborough
ed61287410
AP_NavEKF3: Don't update accel bias states if vibration affected
2021-07-22 18:20:45 +10:00
Paul Riseborough
62d70a628e
AP_NavEKF3: Use large accel process noise when IMU data is bad
2021-07-22 18:20:45 +10:00
Paul Riseborough
5eb7751682
AP_NavEKF3: Adjust gyro bias process noise tuning
...
NEw value is a compromise between roll/pitch angle and horizontal state velocity estimation errors and the noise in the gyro bias estimate
2021-07-22 18:20:45 +10:00
Paul Riseborough
72dc998509
AP_NavEKF3: Allow smaller dvel bias state variances for improved tuning
2021-07-22 18:20:45 +10:00
Paul Riseborough
0f2661c31c
AP_NavEKF3: Retune IMU process noise
...
Required to achieve equivalent fusion noise and weighting on IMU vs other sources to previous param defaults with the old covariance prediction equations.
2021-07-22 18:20:45 +10:00
Paul Riseborough
171eed5d85
AP_NavEKF3: Make gyro bias learning less noisy
2021-07-22 18:20:45 +10:00
Paul Riseborough
ce4d13091a
AP_NavEKF3: Fix bug preventing learning of XY IMU dvel bias in flight
2021-07-22 18:20:45 +10:00
Paul Riseborough
6242ce19fa
AP_NavEKF3: Change powf(x,2) to sq(x)
2021-07-22 18:20:45 +10:00
Paul Riseborough
bb9eed28a9
AP_NavEKF3: Update covariance prediction equations
2021-07-22 18:20:45 +10:00
Paul Riseborough
7b8e935880
AP_NavEKF3: Use alternate form for quaternion to rotmat equations in derivation
2021-07-22 18:20:45 +10:00
Andrew Tridgell
0048167f16
SITL: added SIM2 message
...
useful for EKF debugging
2021-07-22 10:19:02 +10:00
Randy Mackay
e9f6a5afdf
AR_WPNav: integrate PathPlanner returning path_planner_used
...
Rover does not need to handle the results differently based on the planner used
2021-07-22 08:51:41 +09:00
Randy Mackay
83e85c7125
AC_WPNav_OA: minor formatting and comment fixes
2021-07-22 08:51:41 +09:00
Randy Mackay
cf797dfca9
AC_WPNav_OA: separate handlers for results from Dijkstra's and BendyRuler
...
also bendy ruler uses pos controller
2021-07-22 08:51:41 +09:00
Randy Mackay
dd4b3295f4
AC_Avoidance: BendyRuler returned destination are shortened
2021-07-22 08:51:41 +09:00
Randy Mackay
faadaafd53
AC_Avoidance: bendy ruler format fixes
2021-07-22 08:51:41 +09:00
Randy Mackay
6d6324a328
AC_Avoidance: OA_PathPlanner returns which planner was used
...
this replaces get_bendy_type
2021-07-22 08:51:41 +09:00
Randy Mackay
d7d41aea38
AC_Avoidance: BendyRuler returns which type was used
...
also make serach_xxx_path methods private
2021-07-22 08:51:41 +09:00
Randy Mackay
70c6694798
AP_Common: add Location::linear_interpolate_alt
2021-07-22 08:51:41 +09:00
Randy Mackay
7daacfd63e
AP_Math: vector2f gets float.h include
2021-07-22 08:51:41 +09:00
Randy Mackay
52bb8112b3
AP_Math: control.h needs vector2/3 includes
2021-07-22 08:51:41 +09:00
Andrew Tridgell
95cbb69d3c
AP_Parachute: added CHUTE_OPTIONS
...
allow for servo release forever to cope with high altitude drops where
servo may be frozen
2021-07-22 07:49:14 +10:00
Andrew Tridgell
f91e995e98
AP_Arming: check pin arming_checks
2021-07-22 07:48:12 +10:00
Andrew Tridgell
8660e98b57
AP_Parachute: added arming_checks()
2021-07-22 07:48:12 +10:00
Andrew Tridgell
09ad43dea3
AP_Relay: added arming_checks
2021-07-22 07:48:12 +10:00
Andrew Tridgell
d827b35e57
AP_RPM: implement arming_checks()
2021-07-22 07:48:12 +10:00
Andrew Tridgell
9b78fa7fb8
HAL_SITL: implement valid_pin()
2021-07-22 07:48:12 +10:00
Andrew Tridgell
d302d3c90a
HAL_ChibiOS: implement valid_pin()
2021-07-22 07:48:12 +10:00
Andrew Tridgell
4dcff3d900
AP_HAL: added valid_pin() GPIO API
2021-07-22 07:48:12 +10:00
Andrew Tridgell
a0ef4f76e2
AP_RangeFinder: replaced Pixhawk with more appropriate wording in docs
2021-07-22 07:48:12 +10:00
Andrew Tridgell
6888ddc4cc
AP_LeakDetector: replaced Pixhawk with more appropriate wording in docs
2021-07-22 07:48:12 +10:00
Andrew Tridgell
b6dbc618dc
AP_Compass: replaced Pixhawk with more appropriate wording in docs
2021-07-22 07:48:12 +10:00
Andrew Tridgell
fdd294b0f3
AP_BoardConfig: replaced Pixhawk with more appropriate wording in docs
2021-07-22 07:48:12 +10:00
Andrew Tridgell
b0fc5c3041
AP_WindVane: replaced PixhawkAUX1 with AUX1
...
not everything is a pixhawk
2021-07-22 07:48:12 +10:00
Andrew Tridgell
8b388f80c5
AP_WheelEncoder: replaced PixhawkAUX1 with AUX1
...
not everything is a pixhawk
2021-07-22 07:48:12 +10:00
Andrew Tridgell
9691581c81
AP_RSSI: replaced PixhawkAUX1 with AUX1
...
not everything is a pixhawk
2021-07-22 07:48:12 +10:00
Andrew Tridgell
095ab7c9d7
AP_RPM: replaced PixhawkAUX1 with AUX1
...
not everything is a pixhawk
2021-07-22 07:48:12 +10:00
Andrew Tridgell
25057d26a0
AP_WindVane: default pins to -1
2021-07-22 07:48:12 +10:00
Andrew Tridgell
d0a26b6dc6
AP_WheelEncoder: default pins to -1
2021-07-22 07:48:12 +10:00
Andrew Tridgell
958843c0a9
AP_RSSI: default RSSI pin to -1
2021-07-22 07:48:12 +10:00
Andrew Tridgell
7eaab583d4
AP_RPM: stop defaulting RPM_PIN to 54
2021-07-22 07:48:12 +10:00
Andrew Tridgell
bbcce717dc
HAL_ChibiOS: stop defaulting relay pins to 54 and 55
...
this just leads to confusion
2021-07-22 07:48:12 +10:00
Andrew Tridgell
0f70b4d8e3
AP_BoardConfig: removed BRD_PWM_COUNT
2021-07-22 07:48:12 +10:00
Andrew Tridgell
54e53ed71c
HAL_ChibiOS: use is_GPIO() instead of BRD_PWM_COUNT
2021-07-22 07:48:12 +10:00
Andrew Tridgell
874757a955
SRV_Channel: added k_GPIO and is_GPIO()
2021-07-22 07:48:12 +10:00
Peter Barker
a6a18fe193
AP_AHRS: punt to correct parent class when no index for getCorrectedDeltaVelocityNED
2021-07-21 21:01:39 +10:00
Peter Barker
b450a96698
AP_AHRS: shuffle AP_AHRS classes
2021-07-21 21:01:39 +10:00
Peter Barker
e1b839f739
GCS_MAVLink: rename for AHRS restructuring
2021-07-21 21:01:39 +10:00
Peter Barker
1ae7d68988
AP_VisualOdom: rename for AHRS restructuring
2021-07-21 21:01:39 +10:00
Peter Barker
7cca7513a1
AP_Vehicle: rename for AHRS restructuring
2021-07-21 21:01:39 +10:00
Peter Barker
e1162f0a66
AP_SmartRTL: rename for AHRS restructuring
2021-07-21 21:01:39 +10:00
Peter Barker
ed5303d1b8
AP_OpticalFlow: rename for AHRS restructuring
2021-07-21 21:01:39 +10:00
Peter Barker
48e9fa7ebd
AP_NMEA_Output: rename for AHRS restructuring
2021-07-21 21:01:39 +10:00
Peter Barker
ee069a081b
AP_Mount: rename for AHRS restructuring
2021-07-21 21:01:39 +10:00
Peter Barker
da11b6be77
AP_Module: rename for AHRS restructuring
2021-07-21 21:01:39 +10:00
Peter Barker
b1bd699a73
AP_Logger: rename for AHRS restructuring
2021-07-21 21:01:39 +10:00
Peter Barker
dbc24d5cd3
AP_InertialNav: rename for AHRS restructuring
2021-07-21 21:01:39 +10:00
Peter Barker
2bd8a45c58
AP_Common: rename for AHRS restructuring
2021-07-21 21:01:39 +10:00
Peter Barker
8396925ece
AC_WPNav: rename for AHRS restructuring
2021-07-21 21:01:39 +10:00
Peter Barker
63015e9e9a
AC_PrecLand: fixes
2021-07-21 21:01:39 +10:00
Peter Barker
6aba6c83c6
AC_PrecLand: rename for AHRS restructuring
2021-07-21 21:01:39 +10:00
Peter Barker
5046083863
AC_AttitudeControl: rename for AHRS restructuring
2021-07-21 21:01:39 +10:00
Peter Barker
ec17abce2e
GCS_MAVLink: remove ability to use DCM as AHRS
2021-07-21 21:01:39 +10:00
Peter Barker
2926ffcd2f
AP_Vehicle: remove ability to use DCM as AHRS
2021-07-21 21:01:39 +10:00
Peter Barker
b9c4d40c46
AP_NMEA_Output: remove ability to use DCM as AHRS
2021-07-21 21:01:39 +10:00
Peter Barker
85bd9de903
AP_Mount: remove ability to use DCM as AHRS
2021-07-21 21:01:39 +10:00
Peter Barker
a3ee979b9c
AP_InertialNav: remove ability to use DCM as AHRS
2021-07-21 21:01:39 +10:00
Peter Barker
0d391533b0
AP_AHRS: remove ability to use DCM as AHRS
2021-07-21 21:01:39 +10:00
Pierre Kancir
a7f14efef2
AC_WPNav: remove unused variable following https://github.com/ArduPilot/ardupilot/pull/18076
2021-07-21 19:00:15 +10:00
Peter Barker
d2102ce9b7
APM_Control: stop taking references to ahrs in APM_Control
2021-07-21 18:27:23 +10:00
Andrew Tridgell
cbf549b1eb
AP_Airspeed: fixed display of ARSPD_DEVID when ARSPD2_TYPE=0
2021-07-21 18:22:11 +10:00
Peter Barker
795f412264
AP_NavEKF3: pass NavEKF failures back up to callers
2021-07-21 18:02:26 +10:00
Peter Barker
b5f165ce2e
AP_NavEKF2: pass NavEKF failures back up to callers
2021-07-21 18:02:26 +10:00
Peter Barker
141e2aae91
AP_AHRS: pass NavEKF failures back up to callers
2021-07-21 18:02:26 +10:00
Andrew Tridgell
fc2118f42b
AP_NavEKF3: process GPS yaw independently of GPS fix
...
this processes GPS yaw with its own timestamp and as a separated step
from fusing position and velocity. This makes the yaw time handling
more accurate as yaw for moving baseline GPS comes in as a separate
piece of data from the position and velocity
2021-07-21 17:59:49 +10:00
Andrew Tridgell
17f93b8a94
AP_DAL: update GPS yaw API to add timestamp
2021-07-21 17:59:49 +10:00
Andrew Tridgell
e5d878eebd
AP_GPS: change handling of moving baseline yaw
...
this changes yaw handling in a few ways:
- GPS yaw now has a timestamp associated with the yaw separate from
the timestamp associated with the GPS fix
- we no longer force the primary to change to the UBLOX MB rover when
it has a GPS yaw. This means we don't change GPS primary due to GPS
loss, which keeps the GPS more stable. It also increases accuracy
as the rover is always less accurate in position and velocity than
the base
- now we force the primary to be the MB base if the other GPS is a
rover and the base has GPS lock
2021-07-21 17:59:49 +10:00
Andrew Tridgell
0b9cde5812
AP_NavEKF3: fixed indentation in readGpsData()
2021-07-21 17:59:49 +10:00
Andy Piper
ca477d09ed
AP_BLHeli: ensure correct rotation through telemetry ESCs
2021-07-21 17:18:12 +10:00
bugobliterator
48b8fdfd48
AP_HAL_ChibiOS: make linecoding objects static arrays
2021-07-21 17:06:41 +10:00
bugobliterator
4b8b0f834d
AP_HAL: add support for usb passthrough with baud changes
2021-07-21 17:06:41 +10:00
bugobliterator
d1b0438412
AP_HAL_ChibiOS: add support for usb passthrough with baud changes
2021-07-21 17:06:41 +10:00
bugobliterator
f3bc75c538
GCS_MAVLink: add support for passthrough with baud changes
2021-07-21 17:06:41 +10:00
Michael Oborne
d622aad592
AP_HAL_ChibiOS: add get_usb_baud - support for usb baudrate
2021-07-21 17:06:41 +10:00
Willian Galvani
57c6f54a51
AP_LeakDetector: update leak pin for navigator r3 in metadata
...
follow-up to 397def7b9e
2021-07-21 17:04:27 +10:00
Randy Mackay
c55c160f48
AC_WPNav: use get_terrain_margin instead of constant
2021-07-21 16:03:44 +09:00
Randy Mackay
fb5c458132
AC_WPNav: add TER_MARGIN param
2021-07-21 16:03:44 +09:00
Leonard Hall
ff1843a79c
AC_AttitudeControl: AC_PosControl: Auto Terain following update
2021-07-21 16:03:44 +09:00
Leonard Hall
5dcfee07d9
AC_WPNav: Auto Terain following update
2021-07-21 16:03:44 +09:00
Leonard Hall
9d845759f8
AC_PosControl: Add MAX(bla,0) because safe_sqrt isn't safe
2021-07-21 15:40:41 +09:00
Leonard Hall
ce254153c1
WP_Nav: Return Crosstrack error
2021-07-21 15:40:41 +09:00
Leonard Hall
f130503cc7
AC_AttitudeControl: AC_PosControl: calculate cross track
2021-07-21 15:40:41 +09:00
Peter Barker
b89824b3ba
AP_NavEKF: log EKF data source set in XKFS
2021-07-21 16:31:53 +10:00
Peter Barker
a4410a4b2e
AP_NavEKF3: log EKF data source set in XKFS
2021-07-21 16:31:53 +10:00
bugobliterator
6988bf862b
AP_NavEKF: fix running out of max stack limit on debug builds
2021-07-21 11:27:52 +10:00
Peter Barker
a92fc7845c
AP_AHRS: remove unused active_accel_instance
...
Not a great member function as only DCM updates this
2021-07-20 20:37:40 +10:00
Peter Barker
b185d84dc5
AP_AHRS: remove unused _gps_delay variable
2021-07-20 15:24:45 +09:00
honglang
ef109721fe
AP_HAL_ChibiOS: hwdef: reorder CUAV-X7 IMUs
...
adjust the sequence of IMU sensors to have good performance.
2021-07-20 16:10:50 +10:00
Peter Barker
dc5656d34a
AP_AHRS: remove accessors only used internally
2021-07-20 12:38:57 +10:00
Iampete1
ffe91fc80e
AP_BLHeli: update rover motors include
2021-07-20 10:48:01 +09:00
Iampete1
e75d3b68e6
AP_Motors: move AP_MotorsUGV to new AR_Motors directory
2021-07-20 10:48:01 +09:00
Iampete1
d158199a7a
AP_Scripting: add bindings and example for dynamic motor mixer
2021-07-20 09:19:28 +10:00
Iampete1
6848cbc241
AP_Motors: add scripting dynamic mixer, allowing varable geometry vehicles
2021-07-20 09:19:28 +10:00
Iampete1
a6795a8e45
AP_Scripting: support depends keyword on userdata
2021-07-20 09:19:28 +10:00
Iampete1
aad459d447
AP_Scripting: support array userdata feilds
2021-07-20 09:19:28 +10:00
Andrew Tridgell
f969dbe411
RC_Channel: added training mode RC option
2021-07-20 09:00:46 +10:00
Willian Galvani
9083c97acf
AP_BattMonitor: add Navigator to pins metadata
2021-07-19 12:21:40 -07:00
Josh Henderson
84fb03cb79
AP_BattMonitor: SMBus remove unused bool returns
2021-07-18 16:13:06 -07:00
Josh Henderson
0d64782220
AP_BattMonitor: remove temp var for SMBus read_full_charge_capacity
2021-07-18 16:13:06 -07:00
Josh Henderson
8af12608df
AP_BattMonitor: make NeoDesign obey SMBUS_ENABLE
2021-07-18 15:16:57 -07:00
Peter Barker
d47a032a09
AP_Vehicle: explicitly number ModeReason enumeration values
...
These are logged, and mapping back is much easier if you have this
numbering
2021-07-17 09:27:38 +10:00
Andrew Tridgell
2bd04c14fd
AP_OSD: move OSD_LINK_Q_* to a new param table
...
this gives us room for up to 63 more entries
2021-07-16 13:27:38 +10:00
Hwurzburg
ca92d73f25
AP_OSD: Add RX Link Quality Panel
2021-07-16 13:27:38 +10:00
Hwurzburg
55af794a2f
RC_Channel: add Link Quality reporting to RC protocols
2021-07-16 13:27:38 +10:00
Hwurzburg
983c7aba2f
AP_RSSI: add Link Quality reporting to RC protocols
2021-07-16 13:27:38 +10:00
Hwurzburg
c5f53fc0b6
AP_RCProtocol: add Link Quality reporting to RC protocols
2021-07-16 13:27:38 +10:00
Hwurzburg
df0c9a42cb
AP_Logger: Add Link Quality reporting to RC protocols
2021-07-16 13:27:38 +10:00
Hwurzburg
d806d8a26d
AP_HAL: add Link Quality reporting to RC protocols
2021-07-16 13:27:38 +10:00
Hwurzburg
0f2f6ccc80
AP_HAL_ChibiOS: add Link Quality reporting to RC protocols
2021-07-16 13:27:38 +10:00
Andrew Tridgell
a098c80671
HAL_ChibiOS: use DNA for node allocation on Matek GPS
...
this works as MSP is now active when a DNA server is not found
2021-07-15 14:38:11 +10:00
Andrew Tridgell
db1df9d3a8
HAL_ChibiOS: raise DMA contention threshold for H7
2021-07-15 11:31:55 +10:00
Andrew Tridgell
8430f48375
AP_SerialManager: document DisableFIFO bit
2021-07-15 11:31:55 +10:00
Andrew Tridgell
e517a47f9b
AP_SerialManager: call set_options() before first UART use
...
this ensures options are set before the first begin() call
2021-07-15 11:31:55 +10:00
Andrew Tridgell
926d4ad71c
HAL_ChibiOS: implement NOFIFO option for uarts
2021-07-15 11:31:55 +10:00
Andrew Tridgell
269c4084d2
AP_HAL: added serial option for disabling FIFO on uarts
2021-07-15 11:31:55 +10:00
Siddharth Purohit
0138266fee
AP_HAL: disable cast align check while casting char* read pointer to object
2021-07-15 07:50:12 +10:00
bugobliterator
0e7571c733
AP_EFI: fix casting without ensuring alignment
2021-07-15 07:50:12 +10:00
bugobliterator
0b505c491c
AP_CANManager: fix casting without ensuring alignment
2021-07-15 07:50:12 +10:00
bugobliterator
e8e5f49640
AP_BLHeli: fix casting without ensuring alignment
2021-07-15 07:50:12 +10:00
Andy Piper
60b0df0a25
AP_HAL_ChibiOS: only control widest pulse for dshot and oneshot
2021-07-14 17:50:06 +10:00
Peter Barker
78e0e52542
SITL: add simulated ms5611 baro
2021-07-14 17:46:15 +10:00
Peter Barker
b184341424
SITL: add subclass for MS5525
2021-07-14 17:46:15 +10:00
Peter Barker
aa97c5b714
SITL: adjust MS5XXX to be new base class
2021-07-14 17:46:15 +10:00
Peter Barker
50d7fc353f
SITL: rename SIM_MS5525 to SIM_MS5XXX
2021-07-14 17:46:15 +10:00
Andrew Tridgell
416c0724d2
AP_Common: use double precision for more location functions when available
...
this makes the location functions more accurate at long distances when
EKF double enabled
2021-07-14 17:34:40 +10:00
Andrew Tridgell
7550368fc7
HAL_SITL: update for changed SITL API
2021-07-14 17:34:40 +10:00
Andrew Tridgell
5eaf76cdc8
SITL: separate origin and home in SITL
...
this allows for accurate sensor data when flying a very long distance
from the takeoff location
2021-07-14 17:34:40 +10:00
Andrew Tridgell
6b73c2151a
AP_NavEKF3: implement moving origin
...
this shifts EKF_origin to the current location at 1Hz, while leaving
public_origin alone. All output APIs and logging are relative to
public_origin.
The effect of this change is to remove the distortion caused by a
spherical earth, which allows the EKF to operate without errors at
very long distances from the public_origin.
2021-07-14 17:34:40 +10:00
Andrew Tridgell
3ded1e6c10
AP_Common: added ftype precision offset call
2021-07-14 17:34:40 +10:00
Peter Barker
7375d1949c
SITL: add support for ms5525 i2c sensor
2021-07-13 12:00:37 +10:00
Randy Mackay
50ce79bcf6
AP_Torqeedo: simple driver to control torqeedo 1003 motor
...
includes fixes from peer review
2021-07-13 10:01:14 +09:00
Randy Mackay
7e68ce5c86
AP_SerialManager: add torqeedo to list of supported protocols
...
note that serial7_protocol and serial8_protocol param lists were missing 37:SmartAudio so this was also added
2021-07-13 10:01:14 +09:00
Randy Mackay
6c180994cd
AP_Math: add support for crc8_maxim
...
Thanks to FastCRC
2021-07-13 10:01:14 +09:00
Hwurzburg
448ae368b1
RC_Channel: fix ELRS systems spamming CRSF mode/rate messages
2021-07-13 09:52:53 +10:00
Hwurzburg
ceeabb85a5
AP_RCTelemetry: fix ELRS systems spamming CRSF mode/rate messages
2021-07-13 09:52:53 +10:00
Leonard Hall
a32b5b3bb0
AC_AttitudeControl: Allow yaw rate reset to be de-selected
2021-07-13 09:51:36 +10:00
Peter Barker
ddb7378bdd
AP_Terrain: add setter for terrain-enabled
...
Currently only useful for unit test
2021-07-12 17:34:44 +10:00
Peter Barker
fc2338612e
AP_Common: stop setting terrain pointer in test_location
...
Also enable/disable as required for testing
2021-07-12 17:34:44 +10:00
Peter Barker
0a068d4d4b
AP_Terrain: default terrain to off in Sub
2021-07-12 17:34:44 +10:00
Peter Barker
f75e258606
SITL: SIM_Ship: correct GLOBAL_POSITION_INT message altitude
2021-07-12 17:34:44 +10:00
Peter Barker
05a0205c21
SITL: change to use terrain singleton
2021-07-12 17:34:44 +10:00
Peter Barker
b625596dfa
AP_Common: use singleton to access AP_Terrain data
2021-07-12 17:34:44 +10:00
Peter Barker
2d28c1065e
AC_WPNav: use singleton to access AP_Terrain data
2021-07-12 17:34:44 +10:00
Peter Barker
de404b1999
AP_Terrain: allow AP_TERRAIN_AVAILABLE to be set in hwdef
...
Use AP_TERRAIN_AVAILABLE instead
2021-07-12 17:34:44 +10:00
Andrew Tridgell
98fb4fcbe7
AP_NavEKF3: convert code_gen.py to ftype
2021-07-12 17:27:08 +10:00
Andrew Tridgell
44f098c86d
AP_NavEKF3: convert powF(xx,2) calls to sq(xx)
2021-07-12 17:27:08 +10:00
Andrew Tridgell
ae8dbe36bb
AP_NavEKF3: convert EKF3 derivation to ftype
2021-07-12 17:27:08 +10:00
Andrew Tridgell
5f87335325
AP_Airspeed: review updates
...
Co-authored-by: Peter Barker <pb-gh@barker.dropbear.id.au>
2021-07-12 17:14:59 +10:00
Andrew Tridgell
70bb470eb0
AP_Airspeed: fixed AP_Periph build
2021-07-12 17:14:59 +10:00
Andrew Tridgell
0bdd8231cf
AP_Airspeed: added ARSPD_OPTIONS bit for disabling voltage correction
...
if the MS4525 has its own LDO then we are should disable the
correction
2021-07-12 17:14:59 +10:00
Andrew Tridgell
ca1508b02e
AP_Airspeed: added DEVID parameters for airspeed
...
this makes log analysis easier
2021-07-12 17:14:59 +10:00
Andrew Tridgell
7f85b413f2
AP_Airspeed: use GCS_SEND_TEXT instead of printf for sensor probe messages
2021-07-12 17:14:59 +10:00
Andrew Tridgell
e6c7970a19
AP_Airspeed: support 3 I2C addresses for MS4525
...
and if bus number is configured then use only that bus number,
otherwise probe all buses as per existing behaviour
2021-07-12 17:14:59 +10:00
Peter Barker
a52e823967
AP_HAL_SITL: implement read(buf, length)
2021-07-12 12:11:30 +10:00
Andy Piper
40ec8c723b
AP_RCTelemetry: correct firmware string length for CRSF
2021-07-12 11:25:31 +10:00
Leonard Hall
59909970fa
AC_WPNav: Remove unused function
2021-07-10 20:25:05 +09:00
Leonard Hall
ac0b320922
AC_AttitudeControl: Add accessor for yaw slew limit
2021-07-10 20:25:05 +09:00
Leonard Hall
e2b5d3d585
AC_AttitudeControl: AC_PosControl: support accel only input in the vertical
2021-07-10 20:25:05 +09:00
Leonard Hall
e0e283f13e
AC_AttitudeControl: AC_PosControl: support terrain following
2021-07-10 20:25:05 +09:00
Leonard Hall
7bc6c19306
AC_WPNav: seperate kinimatic shaping from pid limit setting
2021-07-10 20:25:05 +09:00
Leonard Hall
8a2f75d742
AC_AttitudeControl: AC_PosControl: seperate kinimatic shaping from pid limit setting
2021-07-10 20:25:05 +09:00
Leonard Hall
6e82bff55b
AC_AttitudeControl: Add terain following to guided
2021-07-10 20:25:05 +09:00
Randy Mackay
430492469b
AC_WPNav: get_terrain_offset and get_vector_NEU made public
2021-07-10 20:25:05 +09:00
Leonard Hall
620d066a2e
AC_WPNav: move code to generate terrain following kinematic path
2021-07-10 20:25:05 +09:00
Leonard Hall
de36398ebf
AC_Math: Control: Support Accel only input
2021-07-10 20:25:05 +09:00
Leonard Hall
b3acdd49d6
AC_AttitudeControl: AC_PosControl: Support Accel only input
2021-07-10 20:25:05 +09:00
Leonard Hall
8e084a0879
AC_AttitudeControl: AC_PosControl: Change input_pos_xyz name
2021-07-10 20:25:05 +09:00
Andrew Tridgell
75411afd21
AP_Math: added test for SCurve::calculate_path
...
this was the values shown in the core dump for failing guided mode
test in CI
2021-07-10 10:34:01 +09:00
Andrew Tridgell
498220b9f3
AP_Math: fixed error where t4_out could be negative in SCurve::calculate_path
...
this case cropped up in SITL due to floating point accuracies
2021-07-10 10:34:01 +09:00
Andrew Tridgell
b11450c18c
AP_NavEKF: review feedback
2021-07-10 07:20:41 +10:00
Andrew Tridgell
f343c8501b
AP_Math: fixed double fill_nanf()
2021-07-10 07:20:41 +10:00
Andrew Tridgell
168e860f70
AP_Math: fixed a few more single precision calls
2021-07-10 07:20:41 +10:00
Andrew Tridgell
56d9134e38
AP_Common: adjust test_location values
...
for adjusted longitude scale accuracy
2021-07-10 07:20:41 +10:00
Andrew Tridgell
1486a473bd
AP_Math: remove unused rotation_matrix_norm()
2021-07-10 07:20:41 +10:00
Andrew Tridgell
a924f66f70
AP_Common: fixed comment
2021-07-10 07:20:41 +10:00
Andrew Tridgell
5319e3910f
AP_NavEKF3: moved checkUpdateEarthField to be called less often
2021-07-10 07:20:41 +10:00
Andrew Tridgell
d91397f2f2
AP_Math: change wrap_PI to ftype
...
prevent loss of precision
2021-07-10 07:20:41 +10:00
Andrew Tridgell
afb928081a
AP_Math: use ftype for a few internal trig fns
2021-07-10 07:20:41 +10:00
Andrew Tridgell
338ab28dea
AP_NavEKF: larger frame limit for --enable-math-check-indexes
2021-07-10 07:20:41 +10:00
Andrew Tridgell
31a6663797
AP_Math: fixed vel correction test build
2021-07-10 07:20:41 +10:00
Andrew Tridgell
6a3b12956a
AP_Common: make longitude_scale() a static
...
this changes the use of longitude_scale() to use the average latitude
instead of the lattitude at one end of the line when calculating
positions and distances. It means we obey the basic geometry rule
that:
pos1 + offs = pos2
pos2 - offs == pos1
2021-07-10 07:20:41 +10:00
Andrew Tridgell
a8c6d742aa
AP_NavEKF3: update earth field at 1Hz
...
this prevents large mag errors on long distance flights
2021-07-10 07:20:41 +10:00
Andrew Tridgell
4f32fa537a
HAL_ChibiOS: define HAL_HAVE_HARDWARE_DOUBLE on F765, F777 and H7
2021-07-10 07:20:41 +10:00
Andrew Tridgell
885e518741
AP_NavEKF3: allow for double EKF build
2021-07-10 07:20:41 +10:00
Andrew Tridgell
6aca0bb08a
AP_NavEKF2: allow for double EKF build
2021-07-10 07:20:41 +10:00
Andrew Tridgell
3235747ef8
AP_NavEKF: allow for double EKF build
2021-07-10 07:20:41 +10:00
Andrew Tridgell
32a83ef347
AP_Mount: use ZERO_FARRAY()
2021-07-10 07:20:41 +10:00
Andrew Tridgell
83158ceadb
AP_Motors: fixup build for ftype conflict
2021-07-10 07:20:41 +10:00
Andrew Tridgell
b8e42be5d1
AP_Common: added double methods for SITL
2021-07-10 07:20:41 +10:00
Andrew Tridgell
01062cccd7
SITL: fixup offset calls
2021-07-10 07:20:41 +10:00
Andrew Tridgell
0f2f0d4cb2
AP_Math: allow for double EKF build
2021-07-10 07:20:41 +10:00
Andrew Tridgell
6c712c9001
HAL_ChibiOS: use SRAM1 as first ram segment on H7
...
this is needed to give the linker more than 128k for static variables
with double precision maths.
2021-07-10 07:20:41 +10:00
Andrew Tridgell
f60330c4ef
AP_HAL: allow for double EKF build
2021-07-10 07:20:41 +10:00
Andrew Tridgell
4ed0b03f35
HAL_ChibiOS: implement set_RTS/CTS_pin methods
2021-07-09 13:27:57 +10:00
Andrew Tridgell
162cecadec
AP_HAL: added set_CTS_pin and set_RTS_pin
2021-07-09 13:27:57 +10:00
Peter Barker
7a9dd8127a
AP_HAL_SITL: generate a core file for a given PID
...
Similarly to dumpstack.sh, uses gdb to dump a core file
2021-07-08 15:46:07 +10:00
Peter Barker
2f7603e08e
AP_HAL: generate a core file for a given PID
...
Similarly to dumpstack.sh, uses gdb to dump a core file
2021-07-08 15:46:07 +10:00
mateksys
40200654af
AP_HAL_ChibiOS: add MatekF765-SE hwdef as a variant of MatekF765-Wing
2021-07-08 13:01:44 +10:00
CallanDaniel
396a27b17e
AP_AHRS: add semaphore around set_origin
...
added semaphore around set_origin() to prevent thread racing
2021-07-08 11:54:37 +09:00
CallanDaniel
c34322f6ce
AP_Scripting: add set_origin and initialised bindings
...
added bindings and example scripts
2021-07-08 11:54:37 +09:00
Siddharth Purohit
0217d1c3dc
AP_UAVCAN: add BatteryInfoAux dsdl message
2021-07-08 11:56:06 +10:00
Andrew Tridgell
587ce2fd62
AP_Arming: fixed arming checks for no baro
2021-07-08 07:56:51 +10:00
Andrew Tridgell
cd3ac639fe
AP_AHRS: added AHRS_GPS_USE=2 for no baro
...
this allows DCM to use the GPS instead of the baro for height
2021-07-08 07:56:51 +10:00
Andrew Tridgell
8e4d67a7c1
AP_Baro: fixed SITL with SIM_BARO_COUNT==0
...
this allows for testing of SITL with no baro
2021-07-08 07:56:51 +10:00
Siddharth Purohit
2f8dec7c9b
AP_ONVIF: make onvif test empty if ONVIF not enabled
2021-07-07 18:57:25 +10:00
Siddharth Purohit
94a09f1426
AP_ONVIF: move to using hal util random
2021-07-07 18:57:25 +10:00
Siddharth Purohit
2c6659930a
AP_ONVIF: remove dependency on C++ STL and std::string
2021-07-07 18:57:25 +10:00
bugobliterator
5f82ef83ad
AP_ONVIF: remove init method and move initialisation to start
2021-07-07 18:57:25 +10:00
bugobliterator
d3fce3c41d
AP_Vehicle: add method to enable onvif camera control using script
2021-07-07 18:57:25 +10:00
bugobliterator
027d8b4aea
AP_Scripting: add support for controlling onvif camera using lua script
2021-07-07 18:57:25 +10:00
Michael Oborne
a81da13c13
AP_Scripting: add support for configuring ONVIF using scripting
2021-07-07 18:57:25 +10:00
Michael Oborne
1db1da9ee5
AP_ONVIF: add support controlling onvif cam using scripting
2021-07-07 18:57:25 +10:00
Siddharth Purohit
45f58367d0
AP_ONVIF: add initial wsdl2h generated header for onvif devicemgmt
2021-07-07 18:57:25 +10:00
Siddharth Purohit
6a0c4ec3f7
AP_HAL: add Random Number Generation test
2021-07-07 18:57:25 +10:00
Siddharth Purohit
1082046134
AP_HAL_SITL: add support for hw random number generation
2021-07-07 18:57:25 +10:00
Siddharth Purohit
f2e947589d
AP_HAL_Linux: add support for hw random number generation
2021-07-07 18:57:25 +10:00
Siddharth Purohit
2b93b17fae
AP_HAL: add support for hw random number generation
2021-07-07 18:57:25 +10:00
Andrew Tridgell
dd156d8da6
HAL_ChibiOS: run storage writes at 1kHz not 100Hz
...
The 100Hz update rate means there is a significant chance of an arming
failure after mission upload if you try to arm shortly after the
update.
Each mission item is 15 bytes, so with a 1200 item mission we need to
write 18000 bytes to storage. At 100Hz, with 8 bytes per storage line,
that takes over 22 seconds.
2021-07-07 17:32:21 +10:00
Siddharth Purohit
f4b2b3b214
AP_DAL: move to using tool instead of tools program group
2021-07-07 17:31:09 +10:00
Stephen Dade
035f65fe03
GCS_MAVLink: Add support for HIGH_LATENCY2 messages
2021-07-07 17:10:05 +10:00
yaapu
afa6e30b94
AP_Frsky_Telem: added airspeed flag to frame 0x5005 enabled by a new parameter
2021-07-07 11:53:12 +10:00
Michelle Rossouw
3bfd577a49
RC_Channel: Add blimp param frame values
2021-07-06 14:56:02 +10:00
Michelle Rossouw
3379a1a215
Filter: Add Vector2f option to notch filter
2021-07-06 14:56:02 +10:00
Michelle Rossouw
f95cb16434
AP_Math: Add Vector2f+z initialiser for Vector3f
2021-07-06 14:56:02 +10:00
Michelle Rossouw
ad2aca4900
AP_BattMonitor: Add blimp param frame values
2021-07-06 14:56:02 +10:00
Michelle Rossouw
c7e71874c3
AP_Arming: Add blimp param frame to rudder arming
2021-07-06 14:56:02 +10:00
Peter Barker
a7ab766fda
AP_Landing: enable deepstall landing to be compiled out of the code
2021-07-06 12:38:21 +10:00
Michel Pastor
765b71adb6
AP_OSD: rename BLH elements to ESC
2021-07-06 12:18:21 +10:00
Michel Pastor
61073de909
AP_MSP: fix DJI FPV temperature and RPM
2021-07-06 12:18:21 +10:00
Michel Pastor
26c6224b2e
AP_ESC_Telem: add method to get the temperature of the motor with highest temperature
2021-07-06 12:18:21 +10:00
Michel Pastor
f9b149e793
AP_ESC_Telem: add method to get average motor RPM
2021-07-06 12:18:21 +10:00
Andy Piper
e9f0c59e61
AP_HAL_ChibiOS: re-enable LEDs on MatekF405-bdshot
2021-07-06 10:10:04 +10:00
Andrew Tridgell
1633afb6cd
APM_Control: adjust fixed wing filter defaults
...
adjust defaults based on discussions with Paul, and initialise the
FLTT value based on the controller time constant
2021-07-05 20:07:47 +10:00
Rishabh
290174f9d9
AC_PrecLand: NFC: Refactor EKF code
2021-07-05 15:21:27 +09:00
Randy Mackay
4fde26aa01
AP_NavEKF3: EK3_RNG_USE_HGT param references EK3_SRCx_POSZ
2021-07-05 08:42:06 +09:00
Andrew Tridgell
31a31963c9
AP_Notify: disable DShot buzzer by default
2021-07-05 07:36:28 +10:00
Andy Piper
a6eaa77ff8
AP_Notify: re-enable display on 1Mb boards
2021-07-04 08:21:47 +10:00
Andrew Tridgell
7ac895db77
HAL_ChibiOS: always send zero DShot when disarmed
...
this prevents a misconfigured system (for example SERVOn_REVERSED=1)
from running a motor while disarmed.
See https://discuss.ardupilot.org/t/plane-4-1-0-beta/72434/34?u=tridge
2021-07-03 11:37:28 +10:00
yaapu
28905a1e67
AP_RPM: fixed #ifdef HAL_WITH_ESC_TELEM to #if HAL_WITH_ESC_TELEM
2021-07-02 15:35:05 +10:00
yaapu
cdc874c366
AP_RPM: added a new RPM driver based on ESC telem
...
this adds a new RPM driver based on average RPM of selected motors.
A new bitmask parameter has been added to select which motor to average.
2021-07-02 15:35:05 +10:00
yaapu
b4d54cf565
AP_ESC_Telem: added methods to get average rpm data by motor mask
2021-07-02 15:35:05 +10:00
Samuel Tabor
326b65c7ad
AP_Soaring: Vario filter cleanup and convert in-line filters to LowPassFilter instances
2021-07-02 15:31:27 +10:00
Siddharth Purohit
9a19a86a81
GCS_MAVLink: omit code that breaks build for herepro
2021-07-02 08:50:16 +10:00
Siddharth Purohit
fcca8564a2
AP_Volz_Protocol: omit code that breaks build for herepro
2021-07-02 08:50:16 +10:00
Siddharth Purohit
a5a29fe3ec
AP_Vehicle: solve for undefined vehicle object in herepro build
2021-07-02 08:50:16 +10:00
Siddharth Purohit
347872f6d6
AP_RobotisServo: omit code that breaks build for herepro
2021-07-02 08:50:16 +10:00
Siddharth Purohit
1ffc18006b
AP_Rally: omit code that breaks build for herepro
2021-07-02 08:50:16 +10:00
Siddharth Purohit
503a676e44
AP_Logger: omit code that breaks build for herepro
2021-07-02 08:50:16 +10:00
Siddharth Purohit
9b2359b34c
AP_HAL_ChibiOS: allow option to enable ChibiOS features in bootloader
2021-07-02 08:50:16 +10:00
Siddharth Purohit
c18652f35a
AP_GPS: add option to enable configuring PPS pin in UBLOX driver
2021-07-02 08:50:16 +10:00
Siddharth Purohit
7cbb3d8a3f
AP_Compass: allow compass cal option for AP_Periph if defined
2021-07-02 08:50:16 +10:00
Siddharth Purohit
8a062ab9a1
AP_Arming: place defines to omit parts that break HerePro build
2021-07-02 08:50:16 +10:00
Siddharth Purohit
e22ca19640
AP_Notify: add support for ProfiLED over SPI
2021-07-02 08:50:16 +10:00
Siddharth Purohit
1a1dd76a4c
AP_HAL_ChibiOS: add initial herepro hwdef
2021-07-02 08:50:16 +10:00
Andrew Tridgell
421faa0ada
AP_Logger: fixed log creation on forced arm
...
when we force arm we need to ask the IO thread to create the log, not
create it ourselves
2021-07-01 15:30:11 +10:00
Andrew Tridgell
b4b02b4ffc
HAL_ChibiOS: use nargs='+' for chibios_hwdef.py
2021-07-01 09:33:16 +10:00
willpiper
ce1ee6334f
AP_HAL_ChibiOS: addressed reviewed comments
2021-07-01 09:33:16 +10:00
willpiper
fb4a4e609a
AP_HAL_ChibiOS: added --extra-hwdef option
2021-07-01 09:33:16 +10:00
Siddharth Purohit
245f9d21b3
AP_HAL_ChibiOS: update clock config for FDCAN and External Flash
2021-06-30 19:34:36 +10:00
Siddharth Purohit
babcb31c1a
AP_FlashIface: remove any delay from is device busy
2021-06-30 19:33:17 +10:00
Siddharth Purohit
be28a55364
AP_FlashIface: fix comments and correct ms to us in vars
2021-06-30 19:33:17 +10:00
Andy Piper
bc65bfa3f3
AP_FlashIface: add more wait_ready() and support XIP on W25Q
2021-06-30 19:33:17 +10:00
Siddharth Purohit
7156493242
AP_FlashIface: remove references to 4-4-4 mode
2021-06-30 19:33:17 +10:00
Siddharth Purohit
28dbbc2bc4
AP_HAL_ChibiOS: do not even initialise empty qspi driver
2021-06-30 19:33:17 +10:00
Siddharth Purohit
2af3864b61
AP_HAL: add support for entering XIP mode
2021-06-30 19:33:17 +10:00
Siddharth Purohit
d3e081c100
AP_HAL_ChibiOS: add support for entering XIP mode
2021-06-30 19:33:17 +10:00
Siddharth Purohit
1a66b5afd7
AP_FlashIface: panic if we haven't found a matching flash device
2021-06-30 19:33:17 +10:00
Siddharth Purohit
30eb5501ce
AP_FlashIface_JEDEC: adjust for where only one mmode clock is req
2021-06-30 19:33:17 +10:00
Siddharth Purohit
dd9f3257cc
AP_FlashIface_JEDEC: make delays support bootloader builds
2021-06-30 19:33:17 +10:00
Siddharth Purohit
1d3c001963
AP_FlashIface: fix build for non bootloader example
2021-06-30 19:33:17 +10:00
Andy Piper
676f90c595
AP_FlashIface: support Winbond W25Q
2021-06-30 19:33:17 +10:00
Siddharth Purohit
bc1474ed52
AP_FlashIface: limit flash size to how much we can address
2021-06-30 19:33:17 +10:00
Siddharth Purohit
3797bdc4b8
AP_FlashIface: move to using 1-4-4 read mode instead of 4-4-4
2021-06-30 19:33:17 +10:00
Siddharth Purohit
6b0f6f3bc0
AP_FlashIface: add support for entering XIP mode
2021-06-30 19:33:17 +10:00
Siddharth Purohit
e09e3fe59f
AP_FlashIface_JEDEC: allow for different print setting for bl and fw
2021-06-30 19:33:17 +10:00
Siddharth Purohit
17e6cab729
AP_FlashIface: setup examples and driver for use with bootloader
2021-06-30 19:33:17 +10:00
Siddharth Purohit
0120d8eeec
AP_DAL: take into account for addition of QSPIDevice in AP_HAL
2021-06-30 19:33:17 +10:00
Siddharth Purohit
6a284ea59d
AP_HAL_Empty: add QSPIDevice empty HAL Iface
2021-06-30 19:33:17 +10:00
Siddharth Purohit
f0cfaa17dc
AP_HAL_SITL: add empty qspi mgr instance
2021-06-30 19:33:17 +10:00
Siddharth Purohit
eed706c46b
AP_HAL_Linux: add empty qspi mgr instance
2021-06-30 19:33:17 +10:00
Siddharth Purohit
263fbbbdb0
AP_HAL_ChibiOS: add echo safe debug flag bouncebuffer
2021-06-30 19:33:17 +10:00
Siddharth Purohit
3b3cc0b194
AP_FlashIface: add initial files for AP_FlashIface library
2021-06-30 19:33:17 +10:00
Siddharth Purohit
c962292bae
AP_HAL_ChibiOS: add support for H757I Evaluation board
2021-06-30 19:33:17 +10:00
Siddharth Purohit
a323807644
AP_HAL: add support for QSPIDevice
2021-06-30 19:33:17 +10:00
Siddharth Purohit
abc26d1993
AP_HAL_ChibiOS: add QSPI Device Driver in HAL
2021-06-30 19:33:17 +10:00
Siddharth Purohit
4cb48da984
modules: update ChibiOS
2021-06-30 19:33:17 +10:00
Samuel Tabor
0c381435cc
AP_Soaring: Reduce the number of messages emmitted.
2021-06-30 18:21:03 +10:00
Siddharth Purohit
0d393a3cf7
AP_AccelCal: do not add accelcal if no GCS iface available
2021-06-30 17:06:02 +10:00
Siddharth Purohit
c4caf2ff54
AP_InertialSensor: add HAL_INS_ENABLED
2021-06-30 17:06:02 +10:00
Siddharth Purohit
69009568b2
AP_HAL: add HAL_INS_ENABLED
2021-06-30 17:06:02 +10:00
Siddharth Purohit
0e4fbe7c46
AP_HAL_ChibiOS: allow using internal compasses onboard
2021-06-30 17:06:02 +10:00
Siddharth Purohit
447935bf4c
AP_InertialSensor: remove dependence on gcs for AP_Periph builds
2021-06-30 17:06:02 +10:00
Randy Mackay
3900a4f14a
GCS_MAVLink: send water depth and temp
2021-06-30 12:05:09 +09:00
Andrew Tridgell
a7f31929ea
AP_Common: use longitude scaling from definitions.h
2021-06-29 17:26:34 +09:00
Andrew Tridgell
978ea307b0
AP_Math: fixed the value LATLON_TO_CM
...
it didn't have enough digits of precision, and was inconsistent with
LOCATION_SCALING_FACTOR
2021-06-29 17:26:34 +09:00
Peter Barker
819c331acd
AP_BattMonitor: correct static_assert call
2021-06-28 11:05:00 +09:00
Peter Barker
67ebdc300b
AP_HAL_SITL: reduce scope of loop variable
2021-06-27 10:57:07 +10:00
Leonard Hall
fcde1e7370
AC_WPNav: use shaping_tc_z_s for terrain following time constant.
2021-06-25 16:54:05 +09:00
Leonard Hall
8f493e3021
AC_AttitudeControl: Add shaping_tc_z_s accessor
2021-06-25 16:54:05 +09:00
Andrew Tridgell
f12a7dd04b
AP_Mount: fixed longitude subtraction
2021-06-25 15:33:55 +10:00
Peter Barker
f69e2a49f6
AP_Common: add test for longitude wrapping
2021-06-25 15:33:55 +10:00
Andrew Tridgell
77d83b9c77
AP_Common: fixed Location class for wrap at 180 degrees longitude
...
this allows us to fly missions across the date line
2021-06-25 15:33:55 +10:00
Leonard Hall
5475d1153c
AC_PosControl: fixup ekf reset
2021-06-25 10:01:49 +09:00
Andrew Tridgell
4895a08ab2
AP_IRLock: convert SITL backends to double precision position
2021-06-24 21:34:30 +10:00
Andrew Tridgell
f209504a12
AC_PrecLand: convert SITL backends to double precision position
2021-06-24 21:34:30 +10:00
Andrew Tridgell
aa03afafa7
AP_Math: added matrix3 tofloat and todouble
2021-06-24 21:34:30 +10:00
Andrew Tridgell
61faeb2d7f
AP_Common: added double methods for SITL
2021-06-24 21:34:30 +10:00
Andrew Tridgell
fb275c9874
SITL: convert to double precision for positions
2021-06-24 21:34:30 +10:00
Andrew Tridgell
1d00cab9e6
AC_WPNav: convert circle, loiter and WPNav to double position
2021-06-24 21:34:30 +10:00
Andrew Tridgell
66186e5221
AC_AttitudeControl: convert poscontrol to use double position
2021-06-24 21:34:30 +10:00
Andrew Tridgell
c8079a318c
AC_PID: convert AC_P_2D to double
2021-06-24 21:34:30 +10:00
Andrew Tridgell
9b91cfe4ee
AP_Math: implement double versions of some position control methods
2021-06-24 21:34:30 +10:00
Andrew Tridgell
3a3a30ab22
AP_Math: define postype_t and vectors
2021-06-24 21:34:30 +10:00
Andrew Tridgell
3fc88b19b8
HAL_SITL: implement initial GPS position offsets
2021-06-24 21:34:30 +10:00
Andrew Tridgell
3315ec5acc
AP_Math: added tofloat() and todouble() methods to Vector2 and Vector3
2021-06-24 21:34:30 +10:00
Andrew Tridgell
cf149a9d18
SITL: added SIM_INIT_LAT_OFS and SIM_INIT_LON_OFS
...
these give an initial lat/lon offset to the GPS in SITL so we can end
up with an origin a long way from the final position
2021-06-24 21:34:30 +10:00
Andrew Tridgell
7819cc6400
AC_AttitudeControl: cleanup poscontrol comments with input from Leonard
2021-06-24 20:28:45 +10:00
Andrew Tridgell
639570505b
AP_Math: cleanups from Leonards feedback
2021-06-24 20:28:45 +10:00
Andrew Tridgell
5f053bd53a
AC_AttitudeControl: fixed comment
2021-06-24 20:28:45 +10:00
Andrew Tridgell
566dd8ca8b
AP_Math: cleanup API comments on control code
2021-06-24 20:28:45 +10:00
Andrew Tridgell
bf91168cd6
AC_WPNav: cleanup position control APIs
...
use Vector2 for xy, float for z
2021-06-24 20:28:45 +10:00
Andrew Tridgell
fd68233fed
AC_AttitudeControl: cleanup position control APIs
...
use Vector2 for xy, float for z
2021-06-24 20:28:45 +10:00
Andrew Tridgell
86f09cad09
AP_Math: cleanup position control APIs
...
use Vector2 for xy, float for z
2021-06-24 20:28:45 +10:00
Andrew Tridgell
fe4abc521a
AP_Math: make vector3 xy() method return a reference
2021-06-24 20:28:45 +10:00
Siddharth Purohit
43bb543aff
AP_PiccoloCAN: fix missing _telem_sem
2021-06-24 17:15:08 +10:00
Oliver
9aba85dadc
AP_PiccoloCAN: Explicit initialization of AP_HAL::CANFrame instances
2021-06-24 15:51:21 +10:00
Oliver
dade859ff9
AP_PiccoloCAN: Remove unncessary floating point operations
2021-06-24 15:51:21 +10:00
Oliver
06eb844ede
AP_PiccoloCAN: Update code to match new esc telemetry / logging architecture
2021-06-24 15:51:21 +10:00
Oliver Walters
de3c4cc9da
AP_PiccoloCAN: Increase number of supported channels from 12 -> 16
2021-06-24 15:51:21 +10:00
Oliver Walters
fb16b085c0
AP_PiccoloCAN: Record servo telemetry information to log
...
- Servo position
- Servo speed
- Servo force / torque
- Servo duty cycle
Updated servo protocol file to accommodate extra variable data
2021-06-24 15:51:21 +10:00
Oliver Walters
115c1224de
AP_PiccoloCAN: Send servo commands for active channels
...
- For each channel, check if a non-motor function is assigned
- If so, send the function value out to the servo
2021-06-24 15:51:21 +10:00
Oliver Walters
7b0da02a18
AP_PiccoloCAN: Framework for CAN servo outputs
2021-06-24 15:51:21 +10:00
Oliver Walters
43b7b4eb3b
AP_PiccoloCAN: Add support for CBS servo protocol
...
- Adds protocol files for the servo protocol
- Generated using Protogen tool
2021-06-24 15:51:21 +10:00
Siddharth Purohit
9494a439ec
AP_UAVCAN: Use HAL_ENABLE_LIBUAVCAN_DRIVERS instead of HAL_MAX_CAN_PROTOCOL_DRIVERS
2021-06-24 09:02:42 +10:00
Siddharth Purohit
69cc0b4615
SRV_Channel: Use HAL_CANMANAGER_ENABLED instead of HAL_ENABLE_LIBUAVCAN_DRIVERS
2021-06-24 09:02:42 +10:00
Siddharth Purohit
02c74a8fa1
GCS_MAVLink: Use HAL_CANMANAGER_ENABLED instead of HAL_ENABLE_LIBUAVCAN_DRIVERS
2021-06-24 09:02:42 +10:00
Siddharth Purohit
5d8a6d167f
AP_ToshibaCAN: Use HAL_CANMANAGER_ENABLED instead of HAL_ENABLE_LIBUAVCAN_DRIVERS
2021-06-24 09:02:42 +10:00
Siddharth Purohit
0795225475
AP_RangeFinder: Use HAL_CANMANAGER_ENABLED instead of HAL_ENABLE_LIBUAVCAN_DRIVERS
2021-06-24 09:02:42 +10:00
Siddharth Purohit
6d8972e63b
AP_PiccoloCAN: Use HAL_CANMANAGER_ENABLED instead of HAL_ENABLE_LIBUAVCAN_DRIVERS
2021-06-24 09:02:42 +10:00
Siddharth Purohit
895039cdce
AP_Notify: Use HAL_CANMANAGER_ENABLED instead of HAL_ENABLE_LIBUAVCAN_DRIVERS
2021-06-24 09:02:42 +10:00
Siddharth Purohit
1a2c51d6df
AP_KDECAN: Use HAL_CANMANAGER_ENABLED instead of HAL_ENABLE_LIBUAVCAN_DRIVERS
2021-06-24 09:02:42 +10:00
Siddharth Purohit
81f6e3c585
AP_HAL_SITL: Use HAL_CANMANAGER_ENABLED instead of HAL_ENABLE_LIBUAVCAN_DRIVERS
2021-06-24 09:02:42 +10:00
Siddharth Purohit
35344d1aef
AP_HAL_Linux: Use HAL_CANMANAGER_ENABLED instead of HAL_ENABLE_LIBUAVCAN_DRIVERS
2021-06-24 09:02:42 +10:00
Siddharth Purohit
882b01bae3
AP_HAL_ChibiOS: Use HAL_CANMANAGER_ENABLED instead of HAL_ENABLE_LIBUAVCAN_DRIVERS
2021-06-24 09:02:42 +10:00
Siddharth Purohit
c7185a1e7f
AP_HAL: split into HAL_CANMANAGER_ENABLED and HAL_ENABLE_LIBUAVCAN_DRIVERS
2021-06-24 09:02:42 +10:00
Siddharth Purohit
5acce3055f
AP_HAL: Use HAL_ENABLE_CANMANAGER instead of HAL_ENABLE_LIBUAVCAN_DRIVERS
2021-06-24 09:02:42 +10:00
Siddharth Purohit
ee22747b48
AP_Filesystem: Use HAL_CANMANAGER_ENABLED instead of HAL_ENABLE_LIBUAVCAN_DRIVERS
2021-06-24 09:02:42 +10:00
Siddharth Purohit
603b302ffd
AP_CANManager: Use HAL_CANMANAGER_ENABLED instead of HAL_ENABLE_LIBUAVCAN_DRIVERS
2021-06-24 09:02:42 +10:00
Leonard Hall
47b0ac663a
AC_AttitudeControl: AC_PosControl: Init and stopping point fixes
2021-06-24 09:01:07 +10:00
bugobliterator
7e8f11b749
AP_HAL_ChibiOS: allow embedded bootloader to be excluded
...
Co-authored-by: Peter Barker <pb-gh@barker.dropbear.id.au>
2021-06-24 08:36:30 +10:00
Peter Barker
183cee3f2c
AP_Motors: remove @Values from param metadata where @Bitmask exists
2021-06-23 18:37:34 +10:00
Peter Barker
dd8af14e57
AP_Logger: remove @Values from param metadata where @Bitmask exists
2021-06-23 18:37:34 +10:00