Commit Graph

7592 Commits

Author SHA1 Message Date
Paul Riseborough
c0d23ffc30 AP_NavEKF: Filter accuracy and stability improvements
Improvements in PX4 firmware have reduced the computational load  and mkae the previous practicwe of splitting magnetometer and optical flow fusion across multiple time steps unnecessary and make it possible to perform a covariance prediction prior to fusing data on the same time step. This patch:

1) Ensures that a covariance prediction is always performed prior to fusion of any observation
2) Removes the splitting of magnetometer fusion so that fusion of the X,Y and Z components occurs on the same time time step
3) Removes the splitting of optical flow fusion so that fusion of X and Y components occurs on the same time step
2015-04-03 15:15:07 -07:00
Jonathan Challinger
de1f7f5e63 AP_NavEKF: use published delta velocities and delta angles if available 2015-04-03 15:15:07 -07:00
priseborough
3421a320b5 AP_NavEKF: Compensate for ground effect when takeoff or landing expected 2015-04-03 15:15:07 -07:00
Jonathan Challinger
20d92f5f9d AP_NavEKF: floor GPS velocity noise at parameter value for conservatism 2015-04-03 15:15:07 -07:00
priseborough
9a797a5d49 AP_NavEKF: Use GPS reported speed accuracy if available
UBlox receivers report an estimate of the speed accuracy that tests show correlates well to speed glitches. Using this to scale the GPS velocity observation noise will reduce the effect of bad GPS velocity data.
2015-04-03 15:15:06 -07:00
Andrew Tridgell
45e016ea5b AP_InertialSensor: check for zero delta_velocity dt 2015-04-03 15:10:47 -07:00
Jonathan Challinger
b306d7a356 AP_InertialSensor: accel cal sample for 400ms instead of 1s 2015-04-03 14:54:19 -07:00
Jonathan Challinger
1e1d8efa22 AP_InertialSensor: use expected update rate for accel cal sampling 2015-04-03 14:54:17 -07:00
Jonathan Challinger
bd84328440 AP_InertialSensor: hack to "reset" the accel filter before taking a cal sample 2015-04-03 14:54:15 -07:00
Jonathan Challinger
b2b42e081a AP_InertialSensor: use delta_velocity/dt for calibration if available 2015-04-03 14:54:10 -07:00
Jonathan Challinger
423160eaf8 AP_InertialSensor: publish delta_velocity_dt 2015-04-03 14:54:06 -07:00
Andrew Tridgell
4147825b87 AP_InertialSensor: fixed gyro calibration bug
we must not update _gyro_offset[] until we have completed calibration
of that gyro, or we will end up using the new offsets when asking for
the raw gyro vector
2015-04-03 06:57:30 -07:00
Andrew Tridgell
728dbf24db AP_Math: fixed vector inequality test
many thanks to cat888

fixes issue #2039
2015-04-01 20:40:37 -07:00
Randy Mackay
d738eda59d GCS_MAVLink: integrate Serial Manager instance 2015-04-01 14:59:23 -07:00
Randy Mackay
1ed7737669 Mount: integrate Serial Manager instance 2015-04-01 14:59:21 -07:00
Randy Mackay
cbcd32d698 GPS: integrate Serial Manager instance 2015-04-01 14:59:20 -07:00
Randy Mackay
c148330c2b FrSkyTelem: integrate Serial Manager instance 2015-04-01 14:59:18 -07:00
Randy Mackay
aef16160dc SerialManager: consolidate MAVLink1 and 2 2015-04-01 14:59:17 -07:00
Randy Mackay
ca92821445 Filter: LowPassFilter gets another div-by-zero check 2015-04-01 10:34:28 -07:00
Jonathan Challinger
57f8a4d29d Filter: add get_cutoff_frequency 2015-04-01 10:15:07 -07:00
Jonathan Challinger
1828515b3b AP_Motors: bug fix to _batt_voltage_filt 2015-04-01 10:15:06 -07:00
Jonathan Challinger
89cdd02f58 AP_Motors: remove duplicate get_throttle function 2015-04-01 10:15:05 -07:00
Jonathan Challinger
0e53c0a892 AP_Motors: make output_armed() and output_disarmed() pure virtual 2015-04-01 10:14:38 -07:00
Andrew Tridgell
5acc4c333b AP_Arming: accept accel/gyro if OK in last 10 seconds
this should prevent short periods of movement from triggering arming
status change alarms
2015-03-31 15:37:24 -07:00
Randy Mackay
3f3e622be5 AC_PID: fix example sketch 2015-03-30 16:07:56 -07:00
Andrew Tridgell
8ba043e593 AP_AHRS: fixed EKF startup bug
This fixes the EKF for when GPS lock takes more than 10 seconds

fixes issue #2010
2015-03-28 10:52:22 -07:00
Andrew Tridgell
3289d38339 AP_NavEKF: make the init functions return bool
we need to know if it has initialised successfully
2015-03-28 10:51:38 -07:00
Andrew Tridgell
7cd7ff89fd HAL_PX4: recover 12k of ram from USB buffers
faster NuttX means we don't need such larger buffers
2015-03-27 15:08:52 -07:00
Andrew Tridgell
10ec1b8290 DataFlash: example no longer builds with APM2 2015-03-26 06:32:00 -07:00
Andrew Tridgell
5cbfe4fd11 HAL_SITL: fixed copter interactive SITL 2015-03-25 12:27:27 -07:00
Andrew Tridgell
0c2232a4be HAL_SITL: don't sync clocks during system initialisation 2015-03-24 08:06:50 -07:00
Jonathan Challinger
127791127c AC_PosControl: fix double literals 2015-03-24 06:29:04 -07:00
Leonard Hall
09aa2f8114 AC_AttitudeControl: Fix function discription 2015-03-23 07:40:04 -07:00
Leonard Hall
6b104c0529 AC_AttitudeControl: No Overshoot limit for Stab
This maybe done in a more obvious way using a switch rather than just
making the overshoot larger than 180 degrees.
2015-03-23 07:40:02 -07:00
Andrew Tridgell
9748cb1e3e HAL_SITL: use a synthetic clock when possible
this decouples wall clock time from simulation time if the FDM
supports it
2015-03-22 18:57:30 -07:00
Randy Mackay
8a3a7bdcd1 Mount: add set_angle_target method 2015-03-21 21:52:22 +09:00
Randy Mackay
f6021010c5 Mission: support do-mount-control 2015-03-21 21:52:19 +09:00
Randy Mackay
2189b16165 Mount_SToRM: remove message throttling
recent versions of gimbal firmware can handle 50hz update rate
2015-03-21 05:56:18 +09:00
Randy Mackay
b3362d5829 Mount: calc_angle_to_location returns vehicle relative yaw 2015-03-21 05:56:16 +09:00
Randy Mackay
d2739c5ce5 Mount_SToRM: slow updates to 10hz, reverse yaw, pitch 2015-03-20 20:46:45 +09:00
Randy Mackay
c7dd6ae816 BattMon: SMBus becomes unhealthy after 5sec timeout
Also remove unused internal variable
2015-03-20 11:05:30 +09:00
Randy Mackay
c44f304253 BattMon: analog monitor always healthy 2015-03-20 11:05:27 +09:00
Randy Mackay
98efcd5f03 AHRS: always use EKF for copter 2015-03-19 15:15:51 +09:00
Andrew Tridgell
5a4ed85588 AP_TECS: added TECS_LAND_PMAX
this limits maximum pitch during the flare, which both reduces
integrator windup and prevents too high pitch which can cause a stall
2015-03-19 14:46:41 +11:00
Randy Mackay
9aba885231 AC_Fence: fix prearm check
before arming the EKF's pred_horiz_pos_abs flag should be used
2015-03-18 21:25:47 +09:00
Andrew Tridgell
ecd2a6f515 DataFlash: log temperature of IMUs
this is the first step towards supporting temperature calibration of
IMUs
2015-03-17 13:33:26 +11:00
Andrew Tridgell
23272e4013 AP_InertialSensor: added get_temperature() interface
this will allow logging of individual temperature sensors
2015-03-17 13:32:54 +11:00
Randy Mackay
7f25938834 AHRS: fix example sketch 2015-03-16 20:29:19 +09:00
Randy Mackay
b01f9505b1 Mission: fix example sketch
Also replace printf with print where possible
2015-03-16 20:29:05 +09:00
Randy Mackay
385b3744ea MotorTri: check servo_out above min_throttle 2015-03-16 14:49:38 +09:00
Randy Mackay
f9e29a7f77 MotorSingle: check servo_out above min_throttle
We need to recalc radio_out or the motors could fall below min throttle
2015-03-16 14:49:37 +09:00
Randy Mackay
8de5d16f96 MotorCoax: check servo_out above min_throttle
We need to recalc radio_out or the motors could fall below min throttle
2015-03-16 14:49:35 +09:00
Leonard Hall
9a3f48cc1f AC_PosControl: ensure throttle output above zero 2015-03-16 14:49:33 +09:00
Leonard Hall
31a55b2bd6 MotorsMatrix: fix div by zero by ensuring throttle is above min 2015-03-16 14:49:31 +09:00
Paul Riseborough
9c2f1ce869 AP_Mount: Fix bug in mavlink gimbal attitude control 2015-03-16 09:54:43 +11:00
ahcorde
103bb2a08d AP_InertialSensor: Fix orientation MPU6000 PXF 2015-03-16 09:50:51 +11:00
mirkix
d4d42599b0 AP_HAL_Linux: Add RcInput and RcOutput with only one PRU when using a BBB. BBBMINI use the RC AIO PRU firmware already 2015-03-16 09:33:54 +11:00
mirkix
a6b018eab9 AP_HAL_Linux: BBBMINI use kernel CS now 2015-03-16 09:15:06 +11:00
Jonathan Challinger
dff899647f AP_Mount: use AP_AHRS_TYPE instead of AP_AHRS_MOUNT 2015-03-16 09:14:03 +11:00
Jonathan Challinger
f92c711d14 AP_AHRS: define AP_AHRS_TYPE to be the type of AHRS in use 2015-03-16 09:14:03 +11:00
Andrew Tridgell
569626ac1a AP_TECS: fixed APM2 build 2015-03-16 08:40:18 +11:00
Andrew Tridgell
cf2445dc97 AP_InertialSensor: prevent nested accelerometer calibration 2015-03-15 15:22:59 +11:00
Andrew Tridgell
8fc58d1cbe AP_Vehicle: expose LAND_FLARE_SEC in vehicle parameters for fixed wing 2015-03-15 13:52:34 +11:00
Andrew Tridgell
060f553097 AP_TECS: provide a much smoother transition before flare
this moves the pitch constraint smoothly between unconstrained and
fully constrained over two time constants before the flare. This
greatly reduces the sudden pitch changes at flare
2015-03-15 13:52:17 +11:00
Andrew Tridgell
9c0614c7bb AP_RangeFinder: default test to I2C Lidar 2015-03-15 13:50:59 +11:00
Andrew Tridgell
c8b0970e61 AP_Compass: show compass count in example 2015-03-14 20:00:29 +11:00
Andrew Tridgell
c565d3b805 AP_Airspeed: fixed example build 2015-03-14 20:00:15 +11:00
Andrew Tridgell
f4455d063e AP_Compass: fixed example 2015-03-14 17:07:39 +11:00
Andrew Tridgell
585a105128 AP_AHRS: use compass->last_update_usec() 2015-03-14 12:31:50 +11:00
Andrew Tridgell
de3f461a55 AP_NavEKF: use compass->last_update_usec() 2015-03-14 12:31:39 +11:00
Andrew Tridgell
1962706a33 AP_Compass: fixed last_update, using last_update_usec()
this broke use of compass in the EKF
2015-03-14 12:31:23 +11:00
Andrew Tridgell
86fc90f54c AP_Compass: removed spurious rotation in PX4 backend
and cleanup rotation macros
2015-03-14 08:52:37 +11:00
Andrew Tridgell
d7bac39539 AP_Compass: removed two unused functions 2015-03-14 08:52:37 +11:00
Andrew Tridgell
73782c41a9 DataFlash: disable CLI on APM2 2015-03-13 22:52:55 +11:00
Andrew Tridgell
8a99cab535 AP_InertialSensor: load only HIL backend for hil_mode 2015-03-13 22:52:55 +11:00
Andrew Tridgell
fec2025469 AP_Compass: added set_hil_mode() 2015-03-13 22:52:55 +11:00
Andrew Tridgell
2e9d2e6449 AP_Baro: load only HIL backend for hil_mode 2015-03-13 22:52:55 +11:00
Randy Mackay
bb74b8dec8 AC_PosControl: fix twitch when entering RTL
Also removed slow_cpu flag
Fixed bug in update to _accel_target_jerk_limited.
2015-03-13 20:47:19 +09:00
Andrew Tridgell
8f6982860f AP_Compass: fixed devid for 2nd compass 2015-03-13 20:46:32 +11:00
Andrew Tridgell
7b51c907f5 AP_Compass: zero some more variables in constructor and init 2015-03-13 19:22:11 +11:00
Andrew Tridgell
4bc92b6373 AP_Compass: removed _product_id var 2015-03-13 18:59:52 +11:00
Andrew Tridgell
3a1cbaeb25 AP_Mission: fix for new compass API 2015-03-13 18:46:18 +11:00
Andrew Tridgell
b488d6de00 AP_AHRS: fix for new compass API 2015-03-13 18:46:17 +11:00
Andrew Tridgell
520c7c1306 AP_InertialSensor: always allow for AK8963 on MPU9250 2015-03-13 18:46:17 +11:00
Andrew Tridgell
d040318014 AP_Baro: removed unused define 2015-03-13 18:46:17 +11:00
Vic
033bd243d6 SITL: Changes in compass for SITL 2015-03-13 18:46:16 +11:00
Andrew Tridgell
60b8736cf1 AP_InertialSensor: use right AK8963 compass defines 2015-03-13 18:46:15 +11:00
Andrew Tridgell
b52918331a AP_HAL: make PXF use AK8963 compass by default 2015-03-13 18:46:15 +11:00
Andrew Tridgell
d186b82edc AP_HAL: consolidate AK8963 defines 2015-03-13 18:46:15 +11:00
Andrew Tridgell
0efd3bacea AP_Compass: make new backend match old PX4 behaviour
when a compass is internal only apply board orientation, not user
specified rotation
2015-03-13 18:46:15 +11:00
Andrew Tridgell
a871c87cad AP_Compass: use state array for compass variables 2015-03-13 18:46:15 +11:00
Víctor Mayoral Vilches
13f0aa5ecd AP_Compass: Separate common code into backend
_copy_to_frontend function takes care of abstracting
this code from the driver. For now the function takes
care of the offset and rotation that is common.
2015-03-13 18:46:15 +11:00
Víctor Mayoral Vilches
d3b76cd8d3 AP_Compass: split compass into frontend/backend 2015-03-13 18:46:15 +11:00
Randy Mackay
385558db4d OptFlow: fix example sketch 2015-03-13 16:41:01 +09:00
Randy Mackay
4772fd338c Mission: fix example sketch 2015-03-13 16:40:59 +09:00
Randy Mackay
c88ff00f5f AC_WPNav: remove example sketch
this only tested compiling anyway
2015-03-13 16:40:57 +09:00
Randy Mackay
ce2d0a14a6 AC_Sprayer: remove example sketch
This only tested compiling anyway
2015-03-13 16:40:54 +09:00
Randy Mackay
4754ecc9e2 AC_Fence: remove example sketch
This only tested compiling anyway
2015-03-13 16:40:52 +09:00
Randy Mackay
90702e2d79 AC_AttControl: remove example sketch
This sketch only tested compiling anyway
2015-03-13 16:40:50 +09:00
Randy Mackay
883e23b97d GPS_Glitch: remove class
This logic is now within the EKF
2015-03-13 16:40:48 +09:00
Randy Mackay
0344ec5d89 Arming: remove GPS glitch checks 2015-03-13 16:40:43 +09:00
Randy Mackay
0dc985a6ab Notify: remove GPS glitch notification 2015-03-13 16:40:41 +09:00
Randy Mackay
4461952534 InertialNav: remove GPS glitch protection and baro reference 2015-03-13 16:40:39 +09:00
Randy Mackay
9012c538fb InertialNav: remove example sketch 2015-03-13 16:40:35 +09:00
Randy Mackay
a76d970cc6 InertialNav_EKF: remove fall back to complementary filter 2015-03-13 16:40:33 +09:00
Randy Mackay
7221070533 InertialNav: make parent virtual 2015-03-13 16:40:31 +09:00
Randy Mackay
4e7d92094c Baro: remove glitch detection 2015-03-13 16:40:29 +09:00
Randy Mackay
c54b5b9af9 InertialNav: remove baro glitch protection 2015-03-13 16:40:25 +09:00
Randy Mackay
8e8487c699 Notify: remove baro_glitch reporting 2015-03-13 16:40:23 +09:00
Andrew Tridgell
1f70b34cbc AP_Baro: fixed baro startup on PXF cape 2015-03-13 13:48:41 +11:00
Andrew Tridgell
808c33d0a7 AP_InertialSensor: support both MPU9250 and MPU9255
seems to be just different WHOAMI register
2015-03-13 13:26:49 +11:00
Andrew Tridgell
8fee936ad7 HAL_SITL: fixed emulation of MTK1.6 GPS 2015-03-13 10:30:20 +11:00
Andrew Tridgell
e0870d5038 AP_GPS: disable NMEA and SiRF on AVR 2560
we are too low on flash space for plane on APM2 now
2015-03-13 10:30:00 +11:00
Andrew Tridgell
5da80f44b1 AP_GPS: fixed MTK1.6 time handling
my MTK1.6 does not use hectoseconds, it uses milliseconds
2015-03-13 10:29:36 +11:00
Randy Mackay
230ca583d1 NavEKF: support sending EKF_STATUS_REPORT 2015-03-12 12:20:00 +09:00
Randy Mackay
5ee67e63ec GCS_MAVLink: add EKF_STATUS_REPORT to enum 2015-03-12 12:19:58 +09:00
Randy Mackay
3c555fc396 GCS_MAVLink: version number after adding EKF_STATUS_REPORT 2015-03-12 12:19:56 +09:00
Randy Mackay
5aef7e6d1a GCS_MAVLink: generate after adding EKF_STATUS_REPORT 2015-03-12 12:19:54 +09:00
Randy Mackay
d464344c34 GCS_MAVLink: add EKF_STATUS_REPORT message to xml 2015-03-12 12:19:50 +09:00
Andrew Tridgell
07fd31c724 AP_InertialSensor: change copter filters to 20Hz
with the backend filters disabled 20Hz is closer to the old default of
30Hz
2015-03-12 13:11:17 +11:00
Andrew Tridgell
e0a0c3afcf AP_Arming: default to arming required 2015-03-12 12:53:27 +11:00
Andrew Tridgell
a1d43e39e0 AP_InertialSensor: added get_gyro_filter_hz() and get_accel_filter_hz() 2015-03-12 12:50:31 +11:00
Andrew Tridgell
3d7d46b9b0 AP_InertialSensor: replaced INS_MPU6K_FILTER with INS_ACCEL_FILTER and INS_GYRO_FILTER
this allows filtering to be set separately on accels and gyros where possible
2015-03-12 12:50:31 +11:00
Andrew Tridgell
f3314791f2 AP_InertialSensor: removed INS_CALSENSFRAME
it is no longer needed as we have shifted the accel cal indexes
2015-03-12 12:50:31 +11:00
Andrew Tridgell
4bc6c8e655 AP_InertialSensor: shift to new parameter indexes for accel calibration
this allows for users to switch between development trees and previous
stable versions while retaining their accel calibration values.
2015-03-12 12:50:30 +11:00
Andrew Tridgell
5d0eb49114 AP_InertialSensor: calculate queue depth based on requested sample rate
this auto-scales the queue depth for plane, rover and copter
2015-03-12 12:50:30 +11:00
Andrew Tridgell
f3706d63c7 Filter: prevent copying the filter parms on apply 2015-03-12 12:50:30 +11:00
Andrew Tridgell
ea49d1cd39 AP_InertialSensor: removed unused variable 2015-03-12 12:50:30 +11:00
Andrew Tridgell
b36122dec0 Filter: removed stdio.h
breaks AVR build
2015-03-12 12:50:30 +11:00
Andrew Tridgell
e6a4b9f68c AP_InertialSensor: check accel health during accel cal 2015-03-12 12:50:29 +11:00
Andrew Tridgell
875339f12a AP_InertialSensor: try to avoid a compiler fault in travis 2015-03-12 12:50:29 +11:00
Andrew Tridgell
031c81beee AP_AHRS: removed call to 1D accel cal 2015-03-12 12:50:29 +11:00
Andrew Tridgell
4deb136bb0 AP_Arming: require 3D accel cal always 2015-03-12 12:50:28 +11:00
Andrew Tridgell
786172aa4e AP_InertialSensor: removed 1D accel calibration
it is finally time to move on from this. We want to push people
towards better calibration and removing the 1D accel cal is the first
step
2015-03-12 12:50:28 +11:00
Andrew Tridgell
a975520033 AP_InertialSensor: check range of accels in 3D calibration
during 3D accel cal it is possible to get data which passes the sphere
fit but which has very poor coverage and does not provide sufficient
data for a good result. This checks that each axis covers a range of
at least 12 m/s/s in body frame
2015-03-12 12:50:28 +11:00
Andrew Tridgell
a8a8628515 AP_InertialSensor: added INS_CALSENSFRAME parameter
this allows us to detect if accel calibration was done in sensor frame
or not. If it was done in sensor frame then the accel calibration is
independent of AHRS_ORIENTATION, which makes it easier to move a board
to a new airframe without having to recalibrate.
2015-03-12 12:50:28 +11:00
Jonathan Challinger
bc655ff0cc AP_InertialSensor_PX4: add optional debug 2015-03-12 12:50:28 +11:00
Jonathan Challinger
074ee49cd0 AP_InertialSensor_PX4: interleave accel and gyro samples by time 2015-03-12 12:50:28 +11:00
Jonathan Challinger
addf80b669 AP_InertialSensor_PX4: explicitly configure sensors, publish deltas 2015-03-12 12:50:27 +11:00
Jonathan Challinger
b5131b7b64 AP_InertialSensor: add coning.py example 2015-03-12 12:50:27 +11:00
Jonathan Challinger
2a547f329b AP_InertialSensor: allow backends to publish delta velocities and angles 2015-03-12 12:50:27 +11:00
Jonathan Challinger
155c173ed1 AP_InertialSensor: rename _rotate_and_offset to _publish 2015-03-12 12:50:27 +11:00
Jonathan Challinger
502446d821 AP_InertialSensor: use LowPassFilter2pVector3f 2015-03-12 12:50:27 +11:00
Jonathan Challinger
0133f0bb57 LowPassFilter2p: split into LowPassFilter2pfloat and LowPassFilter2pVector3f 2015-03-12 12:50:27 +11:00
ustas
a2d5ac6805 AP_GPS: add includes for success build example sketch
include AP_Scheduler.h for achieve build GPS_UBLOX_passthrough example
2015-03-11 21:30:31 +09:00
mirkix
4f1dd85e47 AP_HAL: Add test sketch for RC input to RC output pass through 2015-03-11 21:14:15 +09:00
Randy Mackay
12724e9556 AC_PID: remove include of stdio.h 2015-03-11 20:40:05 +09:00
Randy Mackay
cc0d5b9ced AC_PI_2D: replace set_filt_hz method with filt_hz
Thanks to Jonathan Challinger for spotting this bug
2015-03-11 17:28:36 +09:00
Randy Mackay
c10b0b34ca AC_PID: replace set_filt_hz method with filt_hz
Thanks to Jonathan Challinger for spotting this bug
Also add sanity check to filt_hz
2015-03-11 17:28:20 +09:00
Jonathan Challinger
88ec13b10d AC_PosControl: fix build 2015-03-11 10:00:00 +09:00
Randy Mackay
50d2e98aa4 AC_AttControl: init throttle_hover in constructor 2015-03-10 22:10:36 +09:00
Randy Mackay
965db2c7f7 AC_PosControl: add comments and defines for jerk limits 2015-03-10 22:10:34 +09:00
Jonathan Challinger
4408c1b935 AC_PosControl: 2d jerk constraint in accel_to_lean_angles 2015-03-10 22:10:32 +09:00
Jonathan Challinger
9871b95586 AC_PosControl: fix dt sanity checking 2015-03-10 22:10:30 +09:00
Jonathan Challinger
e7efe23fb5 GCS_MAVLink: reserve message IDs for future feature additions 2015-03-10 15:30:14 +09:00
Randy Mackay
5e26450a6f AP_Motors: make THR_LOW_COMP a variable instead of param 2015-03-10 12:20:27 +09:00
Leonard Hall
007c96a3d8 AP_Motors: Low throttle compensation setters 2015-03-10 12:20:21 +09:00
Leonard Hall
6275ee0289 AP_Motors: Check for battery voltage reading fail 2015-03-10 12:20:19 +09:00
Randy Mackay
5f26a36060 INS: protect against two calibrations running at the same time 2015-03-09 17:58:38 +11:00
Randy Mackay
f9c6e35d19 INS: add calibrating method 2015-03-09 17:58:38 +11:00
Randy Mackay
b0e7990c90 INS: set gyro_cal_ok only after completing calibration 2015-03-09 17:58:37 +11:00
Andrew Tridgell
aec7907571 AP_InertialSensor: updated comment on accel check in gyro cal 2015-03-09 17:58:36 +11:00
Andrew Tridgell
494e909703 AP_InertialSensor: ensure accel cal completion messages get through 2015-03-09 07:36:50 +11:00
Andrew Tridgell
38bde56523 AP_InertialSensor: continue finding best gyro after convergence
with multiple gyros if we are still calibrating one of the gyros then
keep looking for better values for the already converged gyros.
2015-03-08 07:49:38 +11:00
Andrew Tridgell
20a4c98bac AP_InertialSensor: use accelerometers to prevent bad gyro cal
if the board is rotating at a steady rate we can end up with a bad
gyro calibration. This can happen on a steadily moving platform such
as a ship.

This uses the accelerometers to detect the steady movement and not
accept the gyro calibration
2015-03-08 07:48:16 +11:00
Andrew Tridgell
434d094993 AP_InertialSensor: allow MAVLink packets to flow during accelcal
this uses the snoop functionality of GCS_MAVLink to allow the delay
callback to be used during accel calibration
2015-03-07 21:56:39 +11:00
Andrew Tridgell
af7765c57c GCS_MAVLink: fixed typo 2015-03-07 13:54:58 +11:00
Andrew Tridgell
ac848dc103 GCS_MAVLink: zero packet data before reply in serial control 2015-03-07 13:53:44 +11:00
Randy Mackay
7675160e33 Notify: add firmware update flag and implement for OreoLED 2015-03-06 17:26:51 +09:00
Jace A Mogill
442d07a6c9 Notify: OreoLED fast startup with solid green
For manual flight modes: Solid white in front, red in rear
For automatic flight modes: Breathing white in front, red in rear
Loss of RC: Alternating red/black in front and rear

merge with fast green
2015-03-06 17:26:45 +09:00
Jonathan Challinger
e2383581cc AC_AttitudeControl: relax_bf_rate_controller resets rate integrators 2015-03-06 14:02:57 +09:00
Leonard Hall
3ad9b1a06b AP_MotorsMatrix: remove incorrect throttle limit flag 2015-03-06 14:02:55 +09:00
Leonard Hall
20de383084 AC_AttControl: accel limiting for angular control only if feed forward enabled 2015-03-06 14:02:52 +09:00
Jonathan Challinger
d148039f65 AP_Motors: stricter batt_voltage misconfiguration check 2015-03-06 14:02:49 +09:00
Leonard Hall
7de5bccc93 AC_PosControl: remove THR_HOVER parameter
Parameter is set by main code so no need to store to eeprom
2015-03-06 14:02:46 +09:00
Leonard Hall
9866eaded1 AC_PosControl: rename p_alt_pos to p_pos_z
Also pid_alt_accel to pid_accel_z
2015-03-06 14:02:44 +09:00
Leonard Hall
349f1aeceb AC_PosControl: use 2-axis PI controller 2015-03-06 14:02:42 +09:00
Leonard Hall
8d4f0ec80c AC_PosControl: integrate PID input filter 2015-03-06 14:02:39 +09:00
Randy Mackay
e4d48fdc92 AC_AttControlHeli: separate accel max for roll, pitch
renamed _accel_y_max to _accel_yaw_max
2015-03-06 14:02:36 +09:00
Leonard Hall
51455af51a AC_AttConHeli: integrate PID input filter 2015-03-06 14:02:35 +09:00
Leonard Hall
792b2a2eb3 AC_AttControl: separate accel max for roll, pitch, yaw
Also add:
Rate filters
rename rate filter defines
d-term only filter for roll, pitch rate control
accessors to save max accel for roll, pitch, yaw
fix for duplicate ACCEL_Y_MAX param
2015-03-06 14:02:33 +09:00
Leonard Hall
9833c91b2b AC_AttControl: get_max_rate_step_bf_roll, pitch and yaw 2015-03-06 14:02:30 +09:00
Leonard Hall
f00025e5c9 AC_AttControl: accessor for rate feedforward 2015-03-06 14:02:27 +09:00
Leonard Hall
691fb8947e AC_AttControl: accessor for rate_bf_targets 2015-03-06 14:02:25 +09:00
Leonard Hall
784a4ce51a AC_AttControl: increase max angle overshoot to 30deg 2015-03-06 14:02:23 +09:00
Leonard Hall
eb084f7c58 AC_AttControl: bf yaw control uses input filtered PID 2015-03-06 14:02:21 +09:00
Leonard Hall
11a19803e0 Motors: add accessors for motor logging
accessor include get_roll, get_pitch, get_yaw, throttle input
2015-03-06 14:01:58 +09:00
Leonard Hall
34a5bc8b33 AC_PI_2D: 2-axis PI controller 2015-03-06 14:01:56 +09:00
Leonard Hall
046949ea8a AC_HELI_PID: add input filter and restructure
Also removed unused initial_ff from construtor
2015-03-06 14:01:54 +09:00
Leonard Hall
517448e536 AC_PID: add input filtering and restructure 2015-03-06 14:01:52 +09:00
Andrew Tridgell
2aae594371 GCS_MAVLink: handle serial loopback in routing 2015-03-04 20:24:11 +11:00
Andrew Tridgell
086f878bdc HAL_PX4: split IO thread into separate IO and storage threads
this prevents a blocked microSD card from blocking IO to the FRAM,
causing parameter changes not to be sticky
2015-03-04 20:18:17 +11:00
Andrew Tridgell
58c92b0158 GCS_MAVLink: added SCALED_IMU3 logging 2015-03-04 19:30:08 +11:00
Andrew Tridgell
79be500e04 GCS_MAVLink: re-generate headers 2015-03-04 19:29:28 +11:00
Andrew Tridgell
eeacbe518b GCS_MAVLink: update from upstream XML 2015-03-04 19:21:24 +11:00
Randy Mackay
f5f7cd540f Motors: fix example sketches 2015-03-03 21:39:24 +09:00
Leonard Hall
cf8c211c35 Motors: fix thrust curve and add constraint 2015-03-03 15:49:07 +09:00
Leonard Hall
3e960dfc3b Motors: add get_voltage_comp_gain
This clarifies that lift_max is the inverse of the battery voltage gain
compensation
2015-03-03 15:49:04 +09:00
Leonard Hall
997c6f0868 Motors: move battery resistance calcs to parent
Moving from MotorsMatrix to parent Motors class allows these to be used
from other frame types
Also initialise battery resistance
2015-03-03 15:49:02 +09:00
Randy Mackay
09d7cdbc23 Motors: batt_voltage_filt becomes filter object 2015-03-03 15:49:00 +09:00
Randy Mackay
4b78b2ce80 Filter: add get method to LowPassFilter 2015-03-03 15:48:58 +09:00
Leonard Hall
529c6fed3a Motors: move over current throttle limiting to parent
Moving from MotorsMatrix to parent Motors class allows this to be used
from other frame types
2015-03-03 15:48:54 +09:00
Randy Mackay
812473fd9a MotorsMatrix: use get_hover_throttle_as_pwm 2015-03-03 15:48:52 +09:00
Randy Mackay
1a9d3125ef Motors: _hover_out to pct * 10 instead of pwm 2015-03-03 15:48:50 +09:00
Leonard Hall
6b7bdf64bd Motors: move batt voltage lift_max calcs to parent
Moving from MotorsMatrix to parent Motors class allows them to be used
by other frame types
Also added sanity check of batt_voltage_min
2015-03-03 15:48:48 +09:00
Randy Mackay
c549b58eb7 MotorsMatrix: remove check of throttle_curve_enabled 2015-03-03 15:48:46 +09:00
Randy Mackay
5fb3de48ee MotorsTri, Single, Coax: use new thrust curve 2015-03-03 15:48:44 +09:00
Randy Mackay
2eaa4a8445 Motors: remove old throttle curve 2015-03-03 15:48:42 +09:00
Leonard Hall
751dbb7df7 Motors: move thrust curve and volt scaling to parent
Moving from MotorsMatrix to Motors allows it to be used from other frames
2015-03-03 15:48:41 +09:00
Randy Mackay
80b498f598 Motors: add loop_rate to test sketch 2015-03-03 15:48:39 +09:00
Randy Mackay
7ab76dbd0e Motors: add loop_rate to constructor for all frames 2015-03-03 15:48:34 +09:00
Randy Mackay
77d4b3a2ae Motors: add loop_rate to constructor 2015-03-03 15:48:32 +09:00
Leonard Hall
ec9d7dd99e Motors: minor comment fixes 2015-03-03 15:48:30 +09:00
Leonard Hall
1d0ee68116 Motors: over current throttle limiting 2015-03-03 15:48:28 +09:00
Randy Mackay
1217ab9579 BattMon: add get_type method 2015-03-03 15:48:24 +09:00
Randy Mackay
f6523c0997 Motors: Add THR_LOW_CMP to adjust low throttle inputs affect on attitude control 2015-03-03 15:48:21 +09:00
Leonard Hall
83e3e2fec2 Motors: thrust curve and voltage scaling for matrix supported frames 2015-03-03 15:48:19 +09:00
Leonard Hall
5b0bd49ff2 Motors: configurable yaw headroom for matrix frames 2015-03-03 15:48:15 +09:00
Randy Mackay
51213235b4 OreoLED_PX4: available only on PX4 2015-03-02 16:58:17 +09:00
Randy Mackay
f1ce70e748 Notify: disable oreoled by default 2015-03-02 16:58:14 +09:00
Randy Mackay
89cd74c35f Notify: OreoLED supports handle_led_control
includes support for send bytes ioctl
2015-03-02 16:58:12 +09:00
Randy Mackay
90cac02bd7 Notify: OreoLED fix to fade-in when armed 2015-03-02 16:58:10 +09:00
Randy Mackay
35a3a52f29 Notify: add support for handle_led_control 2015-03-02 16:58:06 +09:00
Randy Mackay
9159c7107d GCS_MAVLink: version update after LED_CONTROL added 2015-03-02 16:58:03 +09:00
Randy Mackay
26d54398e2 GCS_MAVlink: generate after LED_CONTROL added 2015-03-02 16:58:01 +09:00
Randy Mackay
3fdabb3667 GCS_MAVlink: define LED_CONTROL in ardupilotmega.xml 2015-03-02 16:57:59 +09:00
Randy Mackay
b8ef765b3e Notify: add OreoLED to PX4 2015-03-02 16:57:56 +09:00
Randy Mackay
0a33a7c15a Notify: OreoLED_PX4 driver 2015-03-02 16:57:50 +09:00
Jonathan Challinger
e9bbe062f3 AC_PosControl: modify accel_to_lean_angles to apply filters before yaw rotation 2015-02-24 16:41:03 +09:00
Andrew Tridgell
1f417dce86 AP_SerialManager: added note on external converter requirement for Frsky
thanks to Luis for the suggestion
2015-02-24 10:19:42 +11:00
Andrew Tridgell
a6d76b4e03 AP_RangeFinder: added PX4-PWM rangefinder
uses PWM input driver to read a rangefinder
2015-02-23 14:15:14 +11:00
Randy Mackay
b650d39786 InertialSensor: remove product_id set to zero 2015-02-21 09:14:33 +09:00
Jonathan Challinger
7b0e806db1 AP_Mount: correct status_msg to conform to MAVLink specification 2015-02-21 08:33:50 +09:00
Andrew Tridgell
3a51bac0d0 AP_Arming: use new enum for home_is_set 2015-02-21 10:13:43 +11:00
Andrew Tridgell
a53395cdb8 AP_Common: added HomeState enum from copter 2015-02-21 10:13:17 +11:00
Andrew Tridgell
6781a8d329 AP_AHRS: fixed get_position for EKF to use correct relative altitude
we need to use the EKF relative height plus the current AHRS home
2015-02-21 10:12:53 +11:00
Andrew Tridgell
869fb23062 HAL_SITL: implement SIM_GPSDRIFTALT 2015-02-21 08:33:01 +11:00
Andrew Tridgell
63c792bc1c SITL: added SIM_GPSDRIFTALT simulation control 2015-02-21 08:32:49 +11:00
Randy Mackay
73e00108e4 Mount: SToRM32 remove unnecessary include 2015-02-20 11:27:15 +09:00
Randy Mackay
23f0bab5d6 Mount: integrate SToRM32 backend 2015-02-20 11:05:40 +09:00
Randy Mackay
92c7949355 Mount: SToRM32 mount backend 2015-02-20 11:05:31 +09:00
Andrew Tridgell
b21c00fcf9 AP_L1_Control: changed default L1 tuning to 20
this is more appropriate for most aircraft
2015-02-19 16:19:33 +11:00
Andrew Tridgell
ec70042d25 APM_Control: raise default IMAX to 3000
on the first flight users often need more I gain to overcome poor
choices for the P gain
2015-02-19 16:15:33 +11:00
Andrew Tridgell
6959cdbf15 RC_Channel: fixed usage of _reverse to be consistent
users could set RCn_REV to 0 and get very confusing results
2015-02-18 12:47:56 +11:00
Andrew Tridgell
26ac29840c AP_Common: added UNUSED_FUNCTION macro
useful for functions that are only in some builds
2015-02-18 11:12:43 +11:00
Andrew Tridgell
50a11c7d5a AP_Mount: added an alternative tilt-only gimbal control method
this adds some nice control characteristics based on work by Paul and
Arthur, but is tilt only
2015-02-16 16:48:55 +11:00
Andrew Tridgell
9b2d44d6ed AP_InertialSensor: use delay_microseconds_boost()
this gives much more consistent timing for PX4
2015-02-16 12:19:13 +11:00
Andrew Tridgell
18131eae13 HAL_PX4: added delay_microseconds_boost()
implemented using hrt callback with sem_post wrapper
2015-02-16 12:19:13 +11:00
Andrew Tridgell
c63540f7b1 AP_HAL: added delay_microseconds_boost()
this will be used by wait_for_sample() to boost priority for a short
period at the end of each delay_microseconds()
2015-02-16 11:52:37 +11:00
Andrew Tridgell
f54d799bff AP_InertialSensor: added TIMING_DEBUG code for finding loop timing issues 2015-02-16 10:12:10 +11:00
Randy Mackay
8e75c9580c InertialNav: get_origin returns zero when no origin
If the EKF has not yet set the origin return location of all zeros
instead of uninitialised location
2015-02-15 11:17:37 +09:00
Andrew Tridgell
04bef5ccf3 AP_InertialSensor: don't skip delay if we are a bit early
this produces a bit more even timing
2015-02-14 12:25:44 +11:00
Andrew Tridgell
619196b6b3 HAL_PX4: fixes for new PX4 device paths 2015-02-14 12:25:44 +11:00
Andrew Tridgell
38d63d51a5 AP_RangeFinder: change for new PX4 device paths 2015-02-14 12:25:44 +11:00
Andrew Tridgell
995311f807 AP_OpticalFlow: change for new PX4 device paths 2015-02-14 12:25:44 +11:00
Andrew Tridgell
9f7e20090c AP_Notify: change for new PX4 device paths 2015-02-14 12:25:43 +11:00
Andrew Tridgell
4537acb898 AP_InertialSensor: change for new PX4 device paths 2015-02-14 12:25:43 +11:00
Andrew Tridgell
99ed508903 AP_Compass: change for new PX4 paths 2015-02-14 12:25:43 +11:00
Andrew Tridgell
beeb9173ea AP_Baro: change for new PX4 paths 2015-02-14 12:25:43 +11:00
Andrew Tridgell
26a77dc502 AP_Airspeed: change for new PX4 paths 2015-02-14 12:25:43 +11:00
Andrew Tridgell
001643d5a3 HAL_PX4: always use the hrt semaphore based delay
the up_udelay() could cause too much timing jitter
2015-02-14 12:25:43 +11:00
Andrew Tridgell
7f0060b881 HAL_PX4: reduce the amount of time between loop() calls
500usec is too long for 400Hz copter
2015-02-14 12:25:43 +11:00
myly10
7bb079b348 AP_Parachute.cpp: Typo correction. 2015-02-13 16:16:10 +09:00
Staroselskii Georgii
75cd41a7c1 AP_HAL_Linux: added NavioAnalogIn 2015-02-12 12:57:45 +11:00
Staroselskii Georgii
b5aef01f72 AP_ADC: added ADS1115 support 2015-02-12 12:57:45 +11:00
Staroselskii Georgii
195aa5fc6b AP_HAL_Linux: take the semaphore in SPIUARTDriver for shorter periods of time 2015-02-12 12:52:56 +11:00
Staroselskii Georgii
64da7f0360 AP_HAL_Linux: fix macro that defines number of I/O callbacks 2015-02-12 12:52:56 +11:00
Staroselskii Georgii
5b21bd2f1d AP_HAL_Linux: make Ublox transactions shorter 2015-02-12 12:52:56 +11:00
Staroselskii Georgii
4034004194 AP_HAL_Linux: switch NavIO to kernel CS handling 2015-02-12 12:52:56 +11:00
Paul Riseborough
9f552eaa4b AP_NavEKF: Fix bug that resets position to origin when vehicle arms 2015-02-12 12:40:55 +11:00
Paul Riseborough
b8d3da3846 AP_NavEKF: Report last known position when vehicle is disarmed 2015-02-12 12:40:55 +11:00
Andrew Tridgell
4aa8a012de GCS_MAVLink: re-generate headers (updated stdint.h usage) 2015-02-12 09:13:17 +11:00
Andrew Tridgell
991afa9999 GCS_MAVLink: re-generate headers 2015-02-12 09:03:34 +11:00
Andrew Tridgell
7a6d91035e GCS_MAVLink: merge upstream changes 2015-02-12 09:03:22 +11:00
Andrew Tridgell
55041c7a7a AP_NavEKF: prevent division by zero in SmallEKF 2015-02-12 09:02:59 +11:00
Andrew Tridgell
db9c8548a5 HAL_VRBrain: call parent Util constructor 2015-02-11 20:57:28 +11:00
Andrew Tridgell
ebacb2b496 HAL_PX4: call parent Util constructor 2015-02-11 20:57:28 +11:00
Jonathan Challinger
59cf1c29ff AP_HAL_VRBRAIN: attempt to initialize USB while soft-disarmed 2015-02-11 20:57:28 +11:00
Jonathan Challinger
e908fcafb1 AP_HAL_PX4: attempt to initialize USB while soft-disarmed 2015-02-11 20:57:27 +11:00
Jonathan Challinger
50466848f7 AP_NavEKF: use hal.util soft_armed state 2015-02-11 20:25:11 +11:00
Jonathan Challinger
180c85817d AP_AHRS: remove armed state, use hal.util soft_armed state 2015-02-11 20:25:11 +11:00
Jonathan Challinger
aa7776ea59 AP_HAL: add soft_armed state to hal.util 2015-02-11 20:25:10 +11:00
Andrew Tridgell
fdcd5ca1a1 GCS_MAVLink: re-generate headers 2015-02-11 20:14:08 +11:00
Andrew Tridgell
b227f8463f GCS_MAVLink: merge upstream mavlink changes 2015-02-11 20:13:27 +11:00
Andrew Tridgell
8cfe8c5823 GCS_MAVLink: moved send_autopilot_version() to common code 2015-02-11 19:50:40 +11:00
Andrew Tridgell
8e35baaef8 GCS_MAVLink: re-generate headers 2015-02-11 19:13:31 +11:00
Jonathan Challinger
0d1f0f4eb0 GCS_MAVLink: add AUTOPILOT_VERSION_REQUEST 2015-02-11 19:11:30 +11:00
Andrew Tridgell
e43fe520e8 AP_BoardConfig: added BRD_SBUS_OUT parameter
when this is set to 1 it enables SBUS servo output on the SBUS
connector.
2015-02-11 18:35:34 +11:00
mirkix
460b434708 AP_InertialSensor: add apm1 oilpan support 2015-02-11 18:22:44 +11:00
mirkix
98b78e61c2 AP_InertialNav: fix apm1 oilpan support 2015-02-11 18:22:42 +11:00
mirkix
49d81a9c99 AP_AHRS: fix apm1 oilpan support 2015-02-11 18:22:39 +11:00
Grant Morphett
3a5eb33d86 GCS_MAVLink: Bug - CLI_ENABLED check should be in vehicle code only.
Changes to fix the warnings in rover sitl build.
We are starting the process of resolving all the warnings in the
ardupilot builds of all vehicles and platforms.
2015-02-11 18:16:46 +11:00
Grant Morphett
4860c84dff AP_NavEKF: Changes to fix the warnings in rover sitl build.
We are starting the process of resolving all the warnings in the
ardupilot builds of all vehicles and platforms.
2015-02-11 18:16:46 +11:00
Grant Morphett
300a02f4e4 AP_Math: Changes to fix the warnings in rover sitl build.
We are starting the process of resolving all the warnings in the
ardupilot builds of all vehicles and platforms.
2015-02-11 18:16:46 +11:00
Grant Morphett
b511410b48 AP_InertialSensor: Changes to fix the warnings in rover sitl build.
We are starting the process of resolving all the warnings in the
ardupilot builds of all vehicles and platforms.
2015-02-11 18:16:45 +11:00
Grant Morphett
525787078f AP_HAL: Changes to fix the warnings in rover sitl build.
We are starting the process of resolving all the warnings in the
ardupilot builds of all vehicles and platforms.
2015-02-11 18:16:45 +11:00
Grant Morphett
e7e9e1adf0 AP_GPS: Changes to fix the warnings in rover sitl build.
We are starting the process of resolving all the warnings in the
ardupilot builds of all vehicles and platforms.
2015-02-11 18:16:45 +11:00
Grant Morphett
52c5db8440 AP_Compass: Changes to fix the warnings in rover sitl build.
We are starting the process of resolving all the warnings in the
ardupilot builds of all vehicles and platforms.
2015-02-11 18:16:45 +11:00
Grant Morphett
0b4ac5d256 AP_Common: Changes to fix the warnings in rover sitl build.
We are starting the process of resolving all the warnings in the
ardupilot builds of all vehicles and platforms.
2015-02-11 18:16:45 +11:00
Andrew Tridgell
ac3dd87790 AP_Baro: added hil_mode support 2015-02-10 09:53:30 +11:00
Jonathan Challinger
5f7480b740 AP_Math: change fast_atan2 to use atan2f on fast CPUs 2015-02-09 22:24:09 +09:00
Andrew Tridgell
b64077ac2e GCS_MAVLink: fixed example build 2015-02-09 13:09:29 +11:00
Andrew Tridgell
af5f84f4e4 DataFlash: fixed example builds 2015-02-09 13:09:16 +11:00
Andrew Tridgell
d5e129457e AP_InertialNav: fixed example builds 2015-02-09 13:09:02 +11:00
Andrew Tridgell
84cda98bec HAL_AVR: fixed example build 2015-02-09 13:08:45 +11:00
Andrew Tridgell
78dadcb5c6 AC_AttitudeControl: fixed example build 2015-02-09 13:08:34 +11:00
Andrew Tridgell
dd0e45db41 GCS_MAVLink: fixed build of example sketches 2015-02-09 11:49:25 +11:00
Andrew Tridgell
2f3b5006e7 AP_Mount: fixed build of example sketches 2015-02-09 11:49:10 +11:00
Andrew Tridgell
a8c1d3a134 AP_GPS: fixed SerialManager for test sketches 2015-02-09 11:47:31 +11:00
Andrew Tridgell
9eb07ffde2 HAL_VRBRAIN: implement updated new_input() semantics 2015-02-09 10:39:14 +11:00
Andrew Tridgell
f548d48fdc HAL_PX4: implement updated new_input() semantics 2015-02-09 10:39:12 +11:00
Andrew Tridgell
7275d2b804 HAL_SITL: implement updated new_input() semantics 2015-02-09 10:39:10 +11:00
Andrew Tridgell
5d6f883887 HAL_AVR: implement updated new_input() semantics 2015-02-09 10:39:07 +11:00
Andrew Tridgell
3075cb058d AP_HAL: changed semantics of RCInput.new_input()
this makes calling new_input() in RCInput clear the new input
flag. This fixes an issue with calls to read() for auxillary channels
clearing the new_input flag, which could cause brief failsafe
conditions.
2015-02-09 10:39:05 +11:00
Andrew Tridgell
7a5ec6d75b GCS_MAVLink: allow use of RC_CHANNELS message on AVR too
can have up to 11 channels
2015-02-08 21:47:31 +11:00
Andrew Tridgell
33a3254d8b HAL_Linux: accept a smaller sync pulse width 2015-02-08 21:47:28 +11:00
Andrew Tridgell
7fb114752c AP_HAL_AVR: accept a much shorted sync pulse width on RCInput
this should fix issues with OpenLRSng default settings
2015-02-08 21:47:26 +11:00
Andrew Tridgell
f2a919c55e AP_HAL_PX4: moved size of main thread stack to Scheduler.h
make it more obvious
2015-02-07 08:06:53 +11:00
Andrew Tridgell
1c270d17a8 AP_Airspeed: ignore temperatures below -80
ETS driver on PX4 returns -1000
2015-02-06 21:41:15 +11:00
Andrew Tridgell
4ecd99eb76 AP_Arming: added check for logging available
this is used for refusing to fly without microSD inserted
2015-02-06 19:05:02 +11:00
Randy Mackay
fc4442bf61 AC_WPNav: rename xy_mode 2015-02-06 17:00:57 +09:00
Randy Mackay
186337f18e AC_PosControl: rename xy_mode enum values
Also added a few comments and fixed formatting
2015-02-06 17:00:55 +09:00
Jonathan Challinger
626521c366 AC_WPNav: update usage of update_xy_controller 2015-02-06 17:00:53 +09:00
Jonathan Challinger
3faca88423 AC_PosControl: allow control of xy rate constraint behavior 2015-02-06 17:00:48 +09:00
Andrew Tridgell
cabf21194a AP_Arming: improved docs 2015-02-06 08:40:59 +11:00
Emile Castelnuovo
5c68980f05 AP_Notify: removed unused VRBRAIN files 2015-02-05 14:22:08 +09:00
Randy Mackay
b66a1135d9 AHRS: fix example sketch compile error 2015-02-03 15:57:11 +09:00
Paul Riseborough
aa94ff629d AP_NavEKF: Prevent bad GPS pre-arming casuing initial position errors
If the vehicle moves significantly or the GPS changes position significantly pre-armed, then the GPS glitch logic was being invoked when the first GPs measurements were fused. This patch resets the position to the GPS when the vehicle arms.
2015-02-03 15:57:10 +09:00
priseborough
bc5581d634 AP_NavEKF: Prevent arming delays from failing GPS
Due to the way that gyro calibration is done, the EKF could be effectively not run for up to 30 seconds in extreme cases, making it possible that the GPS would be failed on arming and the copter put into a non-GPS mode.

the longer term solution is to update the gyro calibration so that it does not hold up other processing. the short tyermfix in thsi patch is to look for evidence of a 3D lock in the last received GPS message.
2015-02-03 15:57:09 +09:00
priseborough
2c012c2763 AP_NavEKF: Always check for new GPS data
This fixes a bug that meant that once the EKF had started up in a non-GPS mode, it would no longer read the GPS and therefore would never be able to use GPS again until reset.
2015-02-03 15:57:08 +09:00
Robert Lefebvre
14d76d158a AC_AttitudeControl: Correct comment. 2015-02-03 14:55:30 +09:00
Jonathan Challinger
baa3e802ee AC_WPNav: clean up atan2 2015-02-03 14:48:04 +09:00
Randy Mackay
112f6a1854 AP_InertialNav: add comments
No functional change
2015-02-03 12:05:24 +09:00
Jonathan Challinger
c95e7b2282 AP_InertialNav: add get_origin function 2015-02-03 11:38:21 +09:00
Andrew Tridgell
fa7c584733 AP_Mount: fixed build on non-EKF systems 2015-02-03 09:49:17 +11:00
Andrew Tridgell
f77f919588 AP_Mount: enable pan pointing in MAVLink backend 2015-02-03 09:49:17 +11:00
Andrew Tridgell
81f60bde06 AP_Mount: fill in all Location flags in ROI pointing 2015-02-03 09:49:17 +11:00
Andrew Tridgell
cf76dcfbf3 AP_Mount: fixed mount MAVLink backend to match SITL sim behaviour
Pair-Programmed-With: Paul Riseborough <p_riseborough@live.com.au>
2015-02-03 09:49:17 +11:00
Andrew Tridgell
75b1330843 AP_Mount: fixed radians to degrees error 2015-02-03 09:49:17 +11:00
Andrew Tridgell
032dcc3660 AP_Mount: fixed references to state in backends 2015-02-03 09:49:17 +11:00
Paul Riseborough
925d625ed1 AP_NavEKF: fix bug in small EKF velocity fusion 2015-02-03 09:49:17 +11:00
Paul Riseborough
8d6f0d08c9 AP_Mount: Update attitude control calculations and debug printing 2015-02-03 09:49:17 +11:00
Paul Riseborough
255252f387 AP_Math: Fix bug in quaternion division 2015-02-03 09:49:16 +11:00
Paul Riseborough
1660aefc90 AP_Mount: Add a simple attitude control loop to the gimbal report handling 2015-02-03 09:49:16 +11:00
Paul Riseborough
5f24603ceb AP_NavEKF: Publish small EKF quaternion and gyro bias outputs 2015-02-03 09:49:16 +11:00
Paul Riseborough
17445d03f0 AP_Math: Add quaternion division 2015-02-03 09:49:16 +11:00
Andrew Tridgell
79017096e2 AP_Mount: prototype code to send biases 2015-02-03 09:49:16 +11:00
Andrew Tridgell
da27a8696d AP_Mount: added initial ekf estimation of gimbal bias
Pair-Programmed-With: Paul Riseborough <p_riseborough@live.com.au>
2015-02-03 09:49:16 +11:00
Andrew Tridgell
ee9c778834 AP_AHRS: added a get_NavEKF_const() function
needed for AP_Mount_MAVLink

Pair-Programmed-With: Paul Riseborough <p_riseborough@live.com.au>
2015-02-03 09:49:16 +11:00
Andrew Tridgell
4c8b663200 AP_NavEKF: added initial version of SmallEKF
This will be used for gimbal bias estimations. 

Pair-Programmed-With: Paul Riseborough <p_riseborough@live.com.au>
2015-02-03 09:49:16 +11:00
Andrew Tridgell
1bbe633691 GCS_MAVLink: re-generate headers 2015-02-03 09:49:15 +11:00
Andrew Tridgell
b81cdf9250 GCS_MAVLink: change to delta_time in GIMBAL_REPORT 2015-02-03 09:49:15 +11:00
Andrew Tridgell
01b264951a AP_Mount: added handling of GIMBAL_REPORT messages 2015-02-03 09:49:15 +11:00
Andrew Tridgell
35c14c787e GCS_MAVLink: added handle_gimbal_report() function
Pair-Programmed-With: Randy Mackay <rmackay9@yahoo.com>
2015-02-03 09:49:15 +11:00
Andrew Tridgell
a1536d575b GCS_MAVLink: added GIMBAL msgs to routing 2015-02-03 09:49:14 +11:00
Andrew Tridgell
01325b701a GCS_MAVLink: re-generate headers 2015-02-03 09:49:14 +11:00
Andrew Tridgell
3b2332a0c7 GCS_MAVLink: added target_system/component to GIMBAL_REPORT 2015-02-03 09:49:14 +11:00
Andrew Tridgell
51ce4d3217 GCS_MAVLink: re-generate 2015-02-03 09:49:14 +11:00
Andrew Tridgell
df735e2ddb GCS_MAVLink: change euler312 order conventions 2015-02-03 09:49:13 +11:00
Andrew Tridgell
53adcc9a25 GCS_MAVLink: regenerate MAVLink headers 2015-02-03 09:49:13 +11:00
Andrew Tridgell
73670edda6 GCS_MAVLink: added GIMBAL messages, mavlink ID and type 2015-02-03 09:49:13 +11:00
Randy Mackay
6cfd48d0c6 Buzzer: handle arming_failed as event 2015-02-03 06:14:55 +09:00
Randy Mackay
a991b4a823 Linux: handle arming_failed as event 2015-02-03 06:14:54 +09:00
Randy Mackay
3361002379 ToneAlarm: handle arming_failed as event 2015-02-03 06:14:53 +09:00
Randy Mackay
bd1ae13fdb Notify: arming_failed flag moved to events 2015-02-03 06:14:53 +09:00
Randy Mackay
6a827459ad Notify: increase size of flags type 2015-02-03 06:14:52 +09:00
Randy Mackay
0a68d4ef39 Notify: clear all flags and events during init 2015-02-03 06:14:44 +09:00
Randy Mackay
272768bc0f Notify: init RGBLed members 2015-02-03 06:14:35 +09:00
Randy Mackay
3550e52560 MotorsTri: add 80% throttle limit
This limit was moved from the main copter flight code to the motors
library in order that the throttle_upper flag could be set properly.
2015-02-02 22:31:06 +09:00
Emile Castelnuovo
c044901f9f AP_Notify: added missing VRBRAIN led files 2015-02-02 08:44:01 +11:00
Emile Castelnuovo
ebc3dcd142 DataFlash: Clean up, VRBRAIN deleted unused boards. 2015-02-02 08:44:01 +11:00
Emile Castelnuovo
90663664f3 AP_BattMonitor: VRBRAIN deleted unused boards, corrected default batt volt divider. 2015-02-02 08:44:01 +11:00
Emile Castelnuovo
a863f0bca8 AP_Airspeed: VRBRAIN code clean up. Deleted unused boards. 2015-02-02 08:44:01 +11:00
Emile Castelnuovo
d78ff43971 AP_HAL_VRBRAIN: code clean up. Deleted unused boards. 2015-02-02 08:44:00 +11:00
Emile Castelnuovo
5e8c1b61b5 AP_Compass: AP_Compass_VRBRAIN.cpp added _is_external overwrite to deal with external compass attached to internal I2C BUS 2015-02-02 08:44:00 +11:00
LukeMike
61f4239e47 AP_Airspeed: enabled PX4 library for VR boards 2015-02-02 08:44:00 +11:00
LukeMike
6473ae2c37 Storage: updated to the PX4 library 2015-02-02 08:44:00 +11:00
Emile Castelnuovo
26432d6064 AP_Notify: use RGB driver for board led in VRBRAIN boards. 2015-02-02 08:43:59 +11:00
Emile Castelnuovo
3e97592e5c AP_Rangefinder: added #if for VRBRAIN boards. 2015-02-02 08:43:59 +11:00
Emile Castelnuovo
c38b11eec8 AP_RangeFinder: added VRBRAIN to use PX4 libraries 2015-02-02 08:43:59 +11:00
Emile Castelnuovo
dae32984f1 AP_InertialSensor: use PX4 library for VRBRAIN boards. 2015-02-02 08:43:59 +11:00
Emile Castelnuovo
25818f08a3 AP_Airspeed: added VRBRAIN board type 2015-02-02 08:43:59 +11:00
Emile Castelnuovo
ffd26e59cd DataFlash: added new VRBRAIN boards 2015-02-02 08:43:59 +11:00
Emile Castelnuovo
b0b892e578 AP_Rangefinder: added support for VRBRAIN boards 2015-02-02 08:43:59 +11:00
Emile Castelnuovo
731329fc55 AP_InertialSensor: correction to AP_InertialSensor_VRBRAIN 2015-02-02 08:43:58 +11:00
Emile Castelnuovo
92e0bc3a2f AP_HAL_VRBRAIN: updates to libraries for new boards 2015-02-02 08:43:58 +11:00
Emile Castelnuovo
a0673b56f9 AP_HAL: added new VRBRAIN boards and new subtypes 2015-02-02 08:43:58 +11:00
Emile Castelnuovo
de8a0ebc08 AP_Airspeed: added #defines for new VR boards. 2015-02-02 08:43:58 +11:00
LukeMike
edd0f13845 AP_HAL: mapped the different sizes of storage for all VR boards 2015-02-02 08:43:58 +11:00
LukeMike
6a93148b92 AP_InertialSensor: added library for VRBRAIN Inertial Sensor 2015-02-02 08:43:58 +11:00
LukeMike
b29f50ba9b AP_Airspeed: Defined AirSpeed analog inputs for ArduPlane on VR Micro Brain 5 2015-02-02 08:43:57 +11:00
LukeMike
7dc5541484 AP_HAL_VRBRAIN: Added analog inputs for ArduPlane on VR Micro Brain 5 2015-02-02 08:43:57 +11:00
Andrew Tridgell
a2adb9b1b0 AP_Arming: check for AHRS health and calibration for arming 2015-02-01 14:13:57 +11:00
Andrew Tridgell
6e62e1ca7b AP_InertialSensor: make calibrated() const 2015-02-01 14:13:54 +11:00
Andrew Tridgell
68f64fa11c AP_AHRS: make the healthy() method const 2015-02-01 14:13:52 +11:00
Andrew Tridgell
850af14949 AP_NavEKF: raise EKF_POS_GATE and EKF_GLITCH_RAD for planes
This weights GPS position more heavily for planes

Pair-Programmed-With: Paul Riseborough <p_riseborough@live.com.au>
2015-01-31 21:49:20 +11:00
Holger Steinhaus
8911dfd791 DataFlash: fix out-of-bounds read when logging
Checked in my rmackay9
2015-01-31 13:24:34 +09:00
Randy Mackay
0d94d5441f SerialManager: correct protocol comments
Correct value for 2nd MAVLink protocol
2015-01-31 12:18:47 +09:00
Matthias Badaire
b5b67cf68a SerialManager: Fix SERIALX_PROTOCOL comments
Fix SERIALX_PROTOCOL to have a proper documentation of the protocol types available
2015-01-31 12:18:36 +09:00
Randy Mackay
07a0388f25 AC_PosControl: move alt limit to set_alt_target_from_climb_rate
The alt limit is instead enforced when the target is set using the
set_alt_target_from_climb_rate function
Also updated comments
2015-01-30 14:13:52 +09:00