Commit Graph

26913 Commits

Author SHA1 Message Date
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