Commit Graph

10359 Commits

Author SHA1 Message Date
Randy Mackay
b742ee9cfb AP_Motors: fix example sketch 2016-01-08 18:36:47 +09:00
Michael du Breuil
8c9eafeb3c AP_GPS: Fix param docs that had incorrect spaces
The spaces between values aren't stirpped by the autodoc tool that generates the XML files
2016-01-08 20:17:54 +11:00
Randy Mackay
8c7f36563c AC_AttControl: bug fix to angle_boost reporting
Thanks to OXINARF for finding this
2016-01-08 10:48:59 +09:00
Michael Oborne
a42b286c01 AP_GPS_SBF: update logging based on vendor recommendation. 2016-01-08 10:47:05 +11:00
Andrew Tridgell
b54bb757df AP_Param: fixed flymaple build 2016-01-08 10:33:45 +11:00
mirkix
1744bc0850 AP_Notify: Use display with bbbmini 2016-01-07 14:32:56 -02:00
mirkix
2457558624 AP_Notify: Add display support 2016-01-07 14:32:56 -02:00
mirkix
dee20a31f1 AP_Notify: Add gps_num_sats 2016-01-07 14:32:56 -02:00
Lucas De Marchi
a803cfd1e8 AP_HAL_Linux: RCInput: use GPIO5 for PPMSUM in bhat 2016-01-07 10:28:16 -02:00
Lucas De Marchi
321803919c Revert "AP_HAL_Linux: support PWM input for BH hat"
This reverts commit 8cca0beba9.

The PWM input using the RPI DMA is causing trouble with RPI boards using
PPMSUM. Let's revert it until the solution is found. We still leave the
ifdef in RCInput for BH hat.
2016-01-07 10:27:07 -02:00
Randy Mackay
c829ec0c2c AC_PrecLand: add missing parameter description
Thanks to Thomas Stone for finding this
2016-01-07 17:35:18 +09:00
Jonathan Challinger
8fdbb36827 AP_BattMonitor: add is_powering_off 2016-01-07 15:14:07 +09:00
Randy Mackay
5ddd332277 AC_AttControl: add ANGLE_BOOST param
This allows disabling angle boost
2016-01-07 12:31:52 +09:00
Randy Mackay
6c458b07cb MotorsHeli_RSC: resolve compiler warning re init order 2016-01-07 12:31:49 +09:00
Randy Mackay
f6b909d0a5 AHRS_NavEKF: resolve compiler warning re signed vs unsigned comparison 2016-01-07 12:31:47 +09:00
Tom Pittenger
70a45680ed AP_TECS: fixed param desc for TECS_LAND_THR 2016-01-07 09:36:54 +11:00
Andrew Tridgell
415d800957 AP_Param: use get_custom_defaults_file() 2016-01-07 09:09:54 +11:00
Andrew Tridgell
b4cc3d9668 HAL_SITL: implement get_custom_defaults_file() 2016-01-07 09:09:40 +11:00
Andrew Tridgell
5f4bd10477 AP_HAL: added get_custom_defaults_file() to Util 2016-01-07 09:09:09 +11:00
Andrew Tridgell
f8b52c6a67 AP_AHRS: try to start EKF2 slightly before EKF2
this gives priority to EKF2 on memory
2016-01-07 08:34:32 +11:00
Andrew Tridgell
a6c39dee84 AP_NavEKF: don't allocate EKF1 unless it will leave 4k free memory 2016-01-07 08:33:33 +11:00
Andrew Tridgell
9188670e03 AP_TECS: added get_height_rate_demand() call 2016-01-06 22:47:38 +11:00
Andrew Tridgell
a07a8aece1 RC_Channel: added pwm_to_angle_dz_trim() 2016-01-06 22:47:21 +11:00
Andrew Tridgell
7c9ee9363b AP_Motors: added rc_map_mask() function 2016-01-06 22:09:40 +11:00
Andrew Tridgell
dfccf8f713 AP_Motors: also wrap set_freq and enable_ch for motor mapping 2016-01-06 22:09:40 +11:00
Andrew Tridgell
77af00c5e1 AP_Motors: allow arbitrary mapping of channels on multirotors
using RCn_FUNCTION with motor1, motor2 etc
2016-01-06 22:09:40 +11:00
Andrew Tridgell
2777ff63ba SITL: heli-sim: prevent ground rotation and reduced affect of ground impact 2016-01-06 21:59:56 +11:00
Paul Riseborough
e80fb8b3fa AP_NavEKF2: Improve non-GPS in-flight attitude accuracy
The non-GPS mode was not being activated for small height gains - eg indoor flight.
The incorrect innovation consistency check was being applied to the synthetic velocity observations.
2016-01-06 20:49:21 +11:00
Andrew Tridgell
a3d781bf3f GCS_MAVLink: fixed a valgrind error 2016-01-06 19:54:00 +11:00
Andrew Tridgell
0e8dbe92f0 GCS_MAVLink: fixed string overrun found by asan 2016-01-06 19:53:14 +11:00
Andrew Tridgell
519afc7a06 HAL_PX4: debug code for FRAM corruption 2016-01-06 19:16:16 +11:00
Andrew Tridgell
9941c91d36 RC_Channel: prevent a warning message for assigned RC channels 2016-01-06 19:16:12 +11:00
Andrew Tridgell
6c064ae8bd HAL_SITL: flow control is enabled on SITL
faster parameter download
2016-01-06 19:16:08 +11:00
Andrew Tridgell
68a46bc1ff GCS_MAVLink: use AP_Param::count_parameters() 2016-01-06 14:44:37 +11:00
Andrew Tridgell
93f0707679 AP_Param: added count_parameters() API
this auto-clears when an ENABLE parameter changes
2016-01-06 14:44:34 +11:00
Peter Barker
ff8008d81a DataFlash: remove unused callbacks, unimplemented functions
Closes #3269
2016-01-05 17:08:07 -02:00
Víctor Mayoral Vilches
d73fc4c0b2 AP_Notify: Add PXFmini support 2016-01-05 15:35:56 -02:00
Víctor Mayoral Vilches
fa3dad928b HAL_Linux: Add PXFmini to Linux_Class 2016-01-05 15:35:56 -02:00
Víctor Mayoral Vilches
e1de1f5f80 HAL_Linux: Util, add PXFmini support 2016-01-05 15:35:56 -02:00
Víctor Mayoral Vilches
e493bfcae4 AP_InertialSensor: add PXFmini support 2016-01-05 15:35:56 -02:00
Víctor Mayoral Vilches
a0b9181198 HAL_Linux: Scheduler add PXFmini support 2016-01-05 15:35:55 -02:00
Víctor Mayoral Vilches
1c49b086eb HAL_Linux: SPIDriver add PXFmini support 2016-01-05 15:35:55 -02:00
Lucas De Marchi
e0d19dc87d AP_HAL_Linux: RCInput_RPI: fix coding style 2016-01-05 15:35:34 -02:00
Víctor Mayoral Vilches
fdf490dad1 HAL_Linux: RCInput support for PXFmini 2016-01-05 15:34:50 -02:00
Lucas De Marchi
4e883e033f AP_HAL_Linux: GPIO: remove ifdef comment
It just clutters the source code and review process when a new similar
board is added.
2016-01-05 15:34:49 -02:00
Víctor Mayoral Vilches
8ce8045033 HAL_Linux: GPIO, add support for PXFmini 2016-01-05 15:31:43 -02:00
Víctor Mayoral Vilches
0aee50b99e HAL: Add PXFmini board 2016-01-05 15:31:43 -02:00
Andrew Tridgell
ea823a818c AP_AHRS: enable EKF2 by default in AHRS 2016-01-05 16:42:01 +11:00
Andrew Tridgell
a0a4b698f6 AP_NavEKF: disable EKF1 by default
use EKF2 instead
2016-01-05 16:41:48 +11:00
Andrew Tridgell
c34626ec4e AP_NavEKF2: automatically cut back EK2_IMU_MASK to suit number of IMUs 2016-01-05 16:40:43 +11:00
Andrew Tridgell
cc25575b3a AP_Scheduler: prevent a startup crash in autotest for Rover 2016-01-05 16:31:06 +11:00
Andrew Tridgell
62b2a2117d SITL: only report ground contact at most once per second 2016-01-05 09:47:58 +11:00
Andrew Tridgell
dd07ffce08 HAL_SITL: enable debug of rcoutput channel enable and frequency 2016-01-05 09:47:55 +11:00
Andrew Tridgell
526fb65dd1 HAL_PX4: fixed setting of rcout frequency on alt channels 2016-01-05 09:47:52 +11:00
Andrew Tridgell
224b2e2dda AP_Param: allow group entries as duplicates
otherwise this breaks heli attitude control object
2016-01-05 07:50:23 +11:00
Andrew Tridgell
b6155d2cb6 RC_Channel: fixed output for k_motor* 2016-01-05 06:41:51 +11:00
Andrew Tridgell
1b682e3c8f AP_Motors: swash servos are output only 2016-01-05 06:41:51 +11:00
Andrew Tridgell
238e912000 RC_Channel: allow find_channel() to be called early
and fix a bug!
2016-01-05 06:40:48 +11:00
Lucas De Marchi
47f25a0aa0 AP_HAL_Linux: remove _export_pins() method
The initial idea was to export all pins to be used at once, so we
created _export_pins() to take all of them and a wrapper method,
_export_pin() to export a single one. However we never export more than
one pin at once.
2016-01-04 15:12:49 -02:00
José Roberto de Souza
ba0ed84039 AP_HAL_Linux: Refactor GPIO_Sysfs
- Replaced PATH_MAX by the maximum stack memory it will use for GPIO
  paths
- Added more information to error logs
- Removed the '/n' when writing to GPIO sysfs files
- Using Linux Util write_file() on _pinMode()
2016-01-04 15:12:49 -02:00
José Roberto de Souza
0c0d595b55 AP_HAL_Linux: Export GPIO pin inside of pinMode()
Make sure pinMode() method exports the pin before using it. Otherwise
the export method would need to be called, differently from other GPIO
implementations.

Since now export_pin and export_pins are called only internally, reduce
their visibility to protected.
2016-01-04 15:12:49 -02:00
Ricardo de Almeida Gonzaga
7033e4d8ed AP_HAL_Linux: OpticalFlow swap crop and scale order
In order to be easier to understand the image manipulation for the ones
who read this part, since the order makes no difference in this stage.
2016-01-04 09:24:01 -02:00
Ricardo de Almeida Gonzaga
cbb313ec2c AP_HAL_Linux: Fix OpticalFlow crop calculation
'left' value should be the lateral edges size
2016-01-04 09:24:01 -02:00
Andrew Tridgell
9123ef9f38 RC_Channel: added find_channel() and channel numbers 2016-01-04 17:06:57 +11:00
Andrew Tridgell
d31ba2b380 AP_Motors: added rc_write function
this is intended to make remapping motors and rescaling output easier
2016-01-04 16:56:54 +11:00
Andrew Tridgell
79c90d37f6 AP_Motors: apply HELI_RSC output type if available 2016-01-04 16:14:09 +11:00
Andrew Tridgell
6a58264c6b RC_Channel: added set_aux_channel_default() API
this will allow for a default channel for aux functions. Also adds
heli_rsc and heli_tail_rsc functions
2016-01-04 16:14:09 +11:00
Randy Mackay
ccd3725f63 AP_Mount_Servo: remove out of date comment 2016-01-04 11:23:41 +09:00
Andrew Tridgell
e1f4814068 AP_Motors: only set output side of range for RSC 2016-01-04 11:23:38 +09:00
Andrew Tridgell
7cc53b6449 RC_Channel: setup only in or out part of channels for aux channels
this allows separate use of input and output
2016-01-04 11:23:36 +09:00
Andrew Tridgell
48b774bc63 RC_Channel: allow more complete separation of input and output of channels
this allows for the type and range of channels to be different on
input and output
2016-01-04 11:23:30 +09:00
Andrew Tridgell
0ef61b1637 AP_NavEKF: moved ENABLE param to front of list
and mark as FLAG_ENABLE. This removes the EKF_* parameters when
EKF_ENABLE is 0
2016-01-04 11:14:43 +11:00
Andrew Tridgell
ac64effc74 AP_Param: allow group entries in any order
this will make the ENABLE flag more useful
2016-01-04 11:14:43 +11:00
Andrew Tridgell
57f580fdfc AP_Param: enable param debug by default 2016-01-04 11:14:43 +11:00
Andrew Tridgell
60af7a6087 AP_Math: removed matrix3 parameter support 2016-01-04 11:14:43 +11:00
Andrew Tridgell
1b8cf84801 AP_Param: allow for up to 512 top level vehicle parameters
this will make life a bit easier for copter
2016-01-04 11:14:43 +11:00
Andrew Tridgell
0831661b3c AP_NavEKF2: mark EK2_ENABLE as an ENABLE parameter 2016-01-04 11:14:42 +11:00
Andrew Tridgell
29cb0dcf2c AP_Param: enable variables to be marked as enable variables
used to hide unused subtrees of variables
2016-01-04 11:14:42 +11:00
Andrew Tridgell
37b2e23322 AP_Param: allow objects containing parameters to be dynamically loaded
this makes it possible for objects containing parameters to be
dynamically loaded.
2016-01-04 11:14:42 +11:00
Andrew Tridgell
2dd8a0af74 HAL_SITL: allow visualisation of quad motor speeds in flightgear 2016-01-04 11:09:27 +11:00
Andrew Tridgell
c3829dfb64 AP_Scheduler: allow for arbitrary loop rates
it turns out 300Hz is pretty useful as it allows for triple EKF on
pixhawk
2016-01-04 08:37:31 +11:00
Andrew Tridgell
27b43f4036 AC_PID: fixed example build warning 2016-01-04 08:22:17 +11:00
Andrew Tridgell
1450f33b51 HAL_SITL: support 16 RC input channels in SITL 2016-01-04 08:22:02 +11:00
Andrew Tridgell
0966398d8d SITL: improved realism of fixed wing sim somewhat
still not good, but a bit better for manual flight
2016-01-04 08:03:46 +11:00
Andrew Tridgell
83c8505b3c HAL_SITL: send state to flightgear viewer 2016-01-04 08:02:37 +11:00
Lucas De Marchi
f3ee7a9a85 AP_AccelCal: use union instead of reference
The current approach to access the same memory location by using a
reference is giving this warning:

	../libraries/AP_AccelCal/AccelCalibrator.cpp: In constructor ‘AccelCalibrator::AccelCalibrator()’:
	../libraries/AP_AccelCal/AccelCalibrator.cpp:34:64: warning: dereferencing type-punned pointer will break strict-aliasing rules [-Wstrict-aliasing]
	 _param_struct(*reinterpret_cast<struct param_t *>(&_param_array))
									^
	../libraries/AP_AccelCal/AccelCalibrator.cpp: In member function ‘void AccelCalibrator::run_fit(uint8_t, float&)’:
	../libraries/AP_AccelCal/AccelCalibrator.cpp:336:79: warning: dereferencing type-punned pointer will break strict-aliasing rules [-Wstrict-aliasing]
	     struct param_t &fit_param(*reinterpret_cast<struct param_t *>(&param_array));
                                                                               ^
Using a union allows us to get rid of the warning, make sure the sizes of the
different structs match and have a more elegant solution.
2016-01-02 10:04:16 +11:00
Tom Pittenger
841f34effa AP_Arming: add param for accel error threshold
This is the threshold error to determine inconsistent accelerometers.
2016-01-02 10:01:46 +11:00
Andrew Tridgell
b2745bb545 AP_InertialSensor: we only need peak hold for negative X for now 2016-01-02 09:58:32 +11:00
Tom Pittenger
3aaf2b1d2b AP_InertialSensor: add pos/neg peak detector
new functions that get a filtered min/max accel peaks on each axis with fixed 500ms timeout:
    Vector3f get_accel_peak_hold_pos()
    Vector3f get_accel_peak_hold_neg()

This allows slower mechanisms, such as is_flying, to detect accel spikes which would indicate ground or object impacts. Vibe is too filtered. Independent positive and negative peaks are available
2016-01-02 09:58:31 +11:00
Andrew Tridgell
b052959c61 GCS_MAVLink: re-generated headers 2016-01-02 08:44:49 +11:00
Jonathan Challinger
c2b4235662 GCS_MAVLink: merge mavlink-solo 2016-01-02 08:42:33 +11:00
Jonathan Challinger
41c881cc9e GCS_MAVLink: temporarily remove GIMBAL_ and GOPRO_ messages pending solo sync 2016-01-02 08:42:33 +11:00
Jonathan Challinger
2a3fe35731 GCS_MAVLink: run xmlpretty.py on ardupilotmega.xml 2016-01-02 08:42:33 +11:00
Andrew Tridgell
22873ee687 SITL: reduced drag in plane model 2016-01-01 18:40:22 +11:00
Andrew Tridgell
619a4c0925 SITL: use common dynamics code for QuadPlane 2016-01-01 17:20:30 +11:00
Andrew Tridgell
33998a58ac SITL: prevent aircraft going below ground level 2016-01-01 17:01:23 +11:00
Andrew Tridgell
d425965f6d SITL: expose home yaw to FDMs 2016-01-01 17:00:57 +11:00
Andrew Tridgell
630d4410d4 SITL: removed debug code from QuadPlane 2016-01-01 15:48:56 +11:00
Andrew Tridgell
8a98ce427c SITL: moved to common code for attitude/pos update 2016-01-01 15:12:33 +11:00
Andrew Tridgell
e6555aae6d HAL_SITL: added quadplane model 2016-01-01 14:35:15 +11:00
Andrew Tridgell
d0896a1fb2 HAL_SITL: fixed init of channel 8 out in plane and rover
should be low
2016-01-01 14:35:15 +11:00
Andrew Tridgell
f2c8193f8b SITL: added a QuadPlane model 2016-01-01 14:35:15 +11:00
Andrew Tridgell
6f9e9d761f SITL: move calculations into multicopter frame class
this will enable a QuadPlane model
2016-01-01 14:35:15 +11:00
Andrew Tridgell
c6b6d7137d HAL_SITL: added plane simulator 2016-01-01 12:41:06 +11:00
Andrew Tridgell
16e0a6d7b0 AP_Math: fixed angle between two vector3s 2016-01-01 12:41:05 +11:00
Andrew Tridgell
fcfd11ef53 SITL: very simple fixed wing simulator
useful for debugging
2016-01-01 12:41:05 +11:00
Randy Mackay
bea69521c8 AC_PrecLand: velocity PI controller into parent class 2015-12-31 15:30:33 +09:00
Andrew Tridgell
8e4586b4a2 AP_Param: allow for nested groups without subclassing
this allows for param tables containing other unrelated objects
2015-12-31 15:30:31 +09:00
Tom Pittenger
4e4c1831f0 AP_ADSB: added guided mode handling 2015-12-31 15:36:49 +11:00
Randy Mackay
4e9f82a0e7 Notify: fix parameter description 2015-12-31 11:33:02 +09:00
pepevalbe
0d5e59eaa3 AP_Notify: configurable RGB LED brightness 2015-12-31 11:32:59 +09:00
Lucas De Marchi
180359d6dd AP_Math: fix unit test
For ROTATION_ROLL_90_PITCH_68_YAW_293 consider the angles as 90, 68.8
and 293.3 degrees to pre-calculate rotation. This matches the rotation
matrix used in code.

While at it, check not only the values are close enough but also the
length of the vector.
2015-12-30 20:22:28 -02:00
Lucas De Marchi
ba3325ffd3 AP_Math: rename rotation
The rotations are supposed to follow the name of the enum, in order. The
ROTATION_YAW_293_PITCH_68_ROLL_90 was added with the name of an
intrinsic 321 rotation, but the matrix is actually a 123 rotation,
following the other rotations already present.

Change the name to follow the other names.
2015-12-30 20:22:27 -02:00
Jonathan Challinger
bae16a61e2 AP_InertialSensor: fix segfault 2015-12-29 23:10:56 -08:00
Jonathan Challinger
83d5a6664a AP_Math: minor changes to matrix_alg in response to review 2015-12-29 22:57:21 -08:00
Jonathan Challinger
0a3c2774e9 AP_InertialSensor: fixes in response to review 2015-12-29 22:55:04 -08:00
Jonathan Challinger
24e413c6af AP_AccelCal: fixes in response to review 2015-12-29 22:55:04 -08:00
Jonathan Challinger
660d9e86d5 AP_AccelCal: basic sanity check on fit parameters 2015-12-29 11:00:20 -08:00
Jonathan Challinger
1482614a7d AP_Arming: add accel cal requires reboot 2015-12-29 10:46:35 -08:00
Jonathan Challinger
137ace473d AP_InertialSensor: add accel_cal_requires_reboot 2015-12-29 10:46:35 -08:00
Jonathan Challinger
f6a41a8936 AP_InertialSensor: ensure that accel calibration object isn't allocated more than once 2015-12-29 10:46:35 -08:00
bugobliterator
1a4b4fa85e AP_Math: add inverse matrix test to check if inverse(mat)*mat = I
where I is an identity matrix (a matrix with diagonal elements = 1)
2015-12-29 10:46:35 -08:00
Jonathan Challinger
65915bbe71 StorageManager: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
027e622a3c RC_Channel: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
2c0657f326 GCS_MAVLink: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
b85631bec3 DataFlash: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
94543d55bb AP_Scheduler: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
780d0de4bb AP_RangeFinder: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
b0de3957ea AP_OpticalFlow: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
99636b3e8b AP_Notify: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
62701448ca AP_Mount: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
b803907163 AP_Motors: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
30a563044e AP_Mission: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
f376510524 AP_HAL_PX4: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
ac152b564f AP_HAL_FLYMAPLE: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
d7639ce03a AP_HAL: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
04dc7130f5 AP_GPS: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
9b5644fdb6 AP_Compass: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
a3789542cd AP_BattMonitor: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
dcfc95fadf AP_Baro: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
a1c7b32387 AP_Airspeed: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
5cb7331095 AP_AHRS: fix example build 2015-12-29 10:46:35 -08:00
Jonathan Challinger
9e6be648b9 AC_PID: fix example build 2015-12-29 10:46:35 -08:00
bugobliterator
fe62a049bd AP_Math: implement LU decomposition based matrix inverse
Replaces previous matlab generated code, which was giving imprecise results
2015-12-29 10:46:34 -08:00
Siddharth Bharat Purohit
a0c3cbffee AP_Math: add inverse matrix test example
fix example build
2015-12-29 10:46:34 -08:00
Siddharth Bharat Purohit
5af0cc8eaf AP_Math: add inverse rotate example function 2015-12-29 10:46:34 -08:00
Jonathan Challinger
7ed8b3814f AP_Math: add rotate_inverse to Vector3 2015-12-29 10:46:34 -08:00
Jonathan Challinger
492223cb84 AP_InertialSensor: support AP_AccelCal 2015-12-29 10:46:34 -08:00
bugobliterator
d24b5023f4 AP_AccelCal: Add separate lib for accel calibration 2015-12-29 10:46:34 -08:00
Andrew Tridgell
f70d9d26ba HAL_QURT: fixed README formatting 2015-12-29 19:23:14 +11:00