Commit Graph

11284 Commits

Author SHA1 Message Date
Andrew Tridgell
0e32c047c3 AP_Compass: allow for COMPASS_EXTERNAL=2 for forced external
this allows users with unusual compass bus connections to force the
compass to external
2016-05-01 10:54:46 +10:00
Michael du Breuil
a17ea5c121 GCS_MAVLink: Add POSITION_TARGET_GLOBAL_INT to the list of messages 2016-05-01 07:38:23 +10:00
Michael Oborne
848fa27d1c GCS_MAVLink: support MAVLINK_MSG_ID_MISSION_ITEM_INT 2016-05-01 07:13:45 +10:00
Michael Oborne
fb3fc118f1 AP_Mission: support MAVLINK_MSG_ID_MISSION_ITEM_INT 2016-05-01 07:13:23 +10:00
Andrew Tridgell
ed999a283f AP_Compass: added get_learn_type() API
this allows caller to determine if EKF offsets should be saved
2016-04-30 16:43:14 +10:00
Michael du Breuil
fff21a1db9 Mission: Remove support for CONDITION_CHANGE_ALT 2016-04-30 10:56:09 +09:00
Randy Mackay
85963cecb4 Location: add additional comments 2016-04-30 10:33:01 +09:00
Randy Mackay
5161d63f8b Location: operator= uses const reference 2016-04-30 10:33:01 +09:00
Randy Mackay
d6309a3a1a Location: remove unused methods 2016-04-30 10:33:01 +09:00
Randy Mackay
1bfb565e18 Location: rename set_alt to set_alt_cm 2016-04-30 10:33:01 +09:00
Randy Mackay
3d646a26e2 AP_HAL_SITL: calls to terrain:height_amsl provide extrapolate and corrected params 2016-04-30 10:33:01 +09:00
Randy Mackay
1c4b2be16a AC_WPNav: simplify use of terrain to just current location 2016-04-30 10:33:01 +09:00
Randy Mackay
c5a3781507 AC_WPNav: accept terrain library reference 2016-04-30 10:33:01 +09:00
Randy Mackay
e23c869c5d AC_WPNav: fix reporting of set_wp_destination failure 2016-04-30 10:33:01 +09:00
Randy Mackay
9fbfea951a AC_WPNav: spline handles terrain altitudes 2016-04-30 10:33:01 +09:00
Randy Mackay
8b2c479d62 AC_WPNav: straight line waypoints accept terrain 2016-04-30 10:33:01 +09:00
Randy Mackay
cd999a2091 Location: initial class implementation 2016-04-30 10:33:01 +09:00
Randy Mackay
83922f9b65 AP_Terrain: update comments for height_terrain_difference_home 2016-04-30 10:33:01 +09:00
Randy Mackay
d84321be2e AP_Terrain: height_amsl can correct for non-zero terrain alt at home position 2016-04-30 10:33:01 +09:00
Randy Mackay
7474e827ce AP_Terrain: get_statistics made public 2016-04-30 10:33:01 +09:00
AndersonRayner
74b9f624a3 Added temperature to the Airspeed.cpp example script
Fixed the formatting of the output data
2016-04-29 17:59:11 -03:00
Niti Rohilla
8fcf5cf0c1 Changed the prototype of handle_guided_request() to report error
while setting guided points.
2016-04-29 12:39:28 -03:00
Lucas De Marchi
6839ee4f37 AP_OpticalFlow: remove trailing whitespaces 2016-04-29 12:10:52 -03:00
Lucas De Marchi
5a52533084 AP_OpticalFlow: move bus definition to AP_HAL header 2016-04-29 12:10:21 -03:00
Ricardo de Almeida Gonzaga
46fb57fcf1 AP_OpticalFlow: use I2CDevice interface 2016-04-29 12:01:04 -03:00
Andrew Tridgell
68e17af070 SITL: allow for changing FlightAxis controller IP 2016-04-29 09:03:48 +10:00
Andrew Tridgell
e428d1e72d SITL: support tricopter quadplanes 2016-04-28 22:36:53 +10:00
Andrew Tridgell
ff96085bd3 AP_Motors: allow arbitrary motor mapping with tricopters 2016-04-28 22:36:41 +10:00
Andrew Tridgell
4908350ccb AC_WPNav: limit WPNAV_ACCEL to that implied by ANGLE_MAX
this prevents an overshoot and backtracking in the navigation code
when WPNAV_ACCEL is unachievable due to an angle limit
2016-04-28 17:47:50 +10:00
Andrew Tridgell
c7664291f9 AC_AttitudeControl: fixed comment on function 2016-04-28 17:46:58 +10:00
Andrew Tridgell
23a64e1227 AC_AttitudeControl: fixed accel limit trigonometry
Leonard had mentioned the limit should be tan(angle) not sin(angle). I
noticed this one was wrong.
2016-04-28 16:15:15 +10:00
Andrew Tridgell
9e01d7de6c SITL: added support for "quad-fast" frame
much more powerful copter for testing nav at high speed
2016-04-28 10:05:04 +10:00
Staroselskii Georgii
60426faa52 AP_HAL_Linux: changed ADC logic a bit for Navio 2
- make voltage_average_ratiometric() the same as voltage_average()
- make read_latest() the same as voltage_average()

wip
2016-04-27 17:14:21 +03:00
Staroselskii Georgii
3feade792a AP_Airspeed: changed default pin for Navio boards
Use channel 5 (i.e. /sys/kernel/adc/ch5) for Airspeed sensors instead of virtual 65 that doesn't
make sense on these boards.
2016-04-27 15:37:34 +03:00
Peter Barker
e83b10cbc5 AP_HAL: move definition of callbacks structure out of C linkage
This fixes all the examples which use the AP_HAL_MAIN macro.
2016-04-27 14:21:28 +10:00
Rustom Jehangir
4a10156b13 AP_HAL_Linux: Fix RCInput::read from stopping at any zero channel
This bug led to issues for us so it may help others to resolve it.
Currently, the AP_HAL_Linux RCInput::read(uint16_t*,uint8_t) function
only returns the first x nonzero channels. Once it hits a channel that
is set to zero, it stops and all remaining channels are returned as
zero, even if they are set. This causes discrepancies between the raw RC
input sent to the GCS and the RC input that is actually used on the
vehicle.

The fixes this issue and makes it behave exactly as it does on the
PX4_HAL code. We ran into this issue when sending rc_override messages
in which there were some channels set to zero.
2016-04-26 22:32:07 -03:00
Andrew Tridgell
197e72acc0 GCS_MAVLink: fixed null termination bug
found with ASAN
2016-04-26 18:20:49 +10:00
Andrew Tridgell
69e233a39d AP_GPS: fixed init string for SBF GPS
coverity #125042
2016-04-26 16:51:29 +10:00
Andrew Tridgell
785ad0614a SITL: fixed coverity 125055 2016-04-26 16:46:06 +10:00
Andrew Tridgell
ed4e8b635a SITL: fixed fd leak
coverity #125056
2016-04-26 16:43:54 +10:00
Andrew Tridgell
97d27ce58f AP_Math: fixed memory leak
found by coverity
2016-04-26 16:41:44 +10:00
Andrew Tridgell
847483d744 SITL: fixed coverity warning 2016-04-26 16:37:17 +10:00
Andrew Tridgell
be41d402b5 AP_InertialSensor: added set of delta angle time for replay 2016-04-26 15:50:46 +10:00
Andrew Tridgell
bcefb45e0a DataFlash: added DelaT to delta-angle logs 2016-04-26 15:50:29 +10:00
Andrew Tridgell
4401cbec72 AP_InertialSensor: cope with zero delta angle time from Replay 2016-04-26 15:37:11 +10:00
Michael du Breuil
831ae72908 AP_Mission: Remove DO_SET_PARAMETER 2016-04-25 09:59:59 +09:00
mirkix
6e546ba181 AP_HAL_Linux: Fix compiler warning unused hal 2016-04-24 11:09:55 -03:00
mirkix
b381045d5e AP_HAL: BBBmini rework for dual MPU9250 and external HMC5843 compass 2016-04-24 10:57:57 -03:00
mirkix
c3a6a56ebb AP_InertialSensor: Add second MPU9250 autodetection to BBBmini 2016-04-24 10:57:57 -03:00
mirkix
3df5a02448 AP_Compass: Add HMC5843 and second AK8963 autodetection to BBBmini 2016-04-24 10:57:57 -03:00
mirkix
2aba5a4643 AP_HAL_Linux: BBBmini add second MPU9250 2016-04-24 10:57:57 -03:00
Randy Mackay
f70072c54b AP_AccelCal: check return of get_calibrator
resolves compiler warning
2016-04-23 23:06:27 -07:00
Randy Mackay
39560f9af8 DataFlash: remove unused num_format_types and _structures
resolves compiler warning
2016-04-23 23:06:26 -07:00
Randy Mackay
6ef735c41e AP_RSSI: use fabsf instead of abs
resolves compiler warning
2016-04-23 23:06:26 -07:00
Randy Mackay
7af9892bd1 AP_MotorsMatrix: make const a float
resolves compiler warning
2016-04-23 23:06:25 -07:00
Randy Mackay
a50f5bfaf8 AP_L1_Control: replace fabsf with labs
resolves a compiler warning
2016-04-23 23:06:25 -07:00
Randy Mackay
b2153fb97f AP_L1_Control: remove unused _xtrackVelPos 2016-04-23 23:06:24 -07:00
Randy Mackay
58e65c836f HAL_Linux: remove unused pru_chan_map from RCOutput 2016-04-23 23:06:24 -07:00
Randy Mackay
d6d5bac419 RCInput_UART: remove unused _count, _direction
resolves a compiler warning
2016-04-23 23:06:23 -07:00
Randy Mackay
3c7b2232b0 AP_GPS_GSOF: remove unused last_hdop
resolves a compiler warning
2016-04-23 23:06:22 -07:00
Randy Mackay
ea3c44f9fa AP_Frsky_Telem: remove unnecessary abs
resolves a compiler warning
2016-04-23 23:06:22 -07:00
Randy Mackay
4aba25d2ef AP_Compass_AK8963: remove unused _bus_sem, _last_accum_time
Resolves a compiler warning
2016-04-23 23:06:21 -07:00
Randy Mackay
04b2e65627 AP_Airspeed: remove unused _last_pin
Resolves a compiler warning
2016-04-23 23:06:21 -07:00
Randy Mackay
722095e56d APM_Control: remove unused _last_error member
Resolves a compiler warning
2016-04-23 23:06:20 -07:00
Luis Vale Gonçalves
b64d28b825 Revising ardupilot.com to .org
Revising ardupilot.com to .org
2016-04-23 22:49:45 -07:00
Luis Vale Gonçalves
5b60d1514f Revising ardupilot.com to .org
Revising ardupilot.com to .org
2016-04-23 22:49:41 -07:00
Luis Vale Gonçalves
bbbb3047fa Revising ardupilot.com to .org
Revising ardupilot.com to .org
2016-04-23 22:49:40 -07:00
Luis Vale Gonçalves
4e70665f17 Revising ardupilot.com to .org
Revising ardupilot.com to .org
2016-04-23 22:49:39 -07:00
Luis Vale Gonçalves
0d9ea7597c Revising ardupilot.com to .org
Revising ardupilot.com to .org
2016-04-23 22:49:38 -07:00
Luis Vale Gonçalves
a16e9b3606 Revising ardupilot.com to .org
Revising ardupilot.com to .org
2016-04-23 22:49:36 -07:00
Randy Mackay
72a7f674ec AP_Motors: protect against out-of-bounds memory access
resolves a compiler warning
2016-04-23 21:06:18 +10:00
Andrew Tridgell
54f7aeed83 RC_Channel: extend channel mapping to 16 channels
this gives more flexibility, no reason to limit it to 8
2016-04-23 21:03:46 +10:00
Andrew Tridgell
3a5e4c80ca AP_Mission: support DO_VTOL_TRANSITION command
first 16 bit command ID
2016-04-23 21:03:46 +10:00
Andrew Tridgell
09c3c36c00 AP_Mission: allow for 16 bit command IDs
this uses command ID 0 to allow for 16 bit command IDs. When used it
limits the content to just 10 bytes.
2016-04-23 21:03:45 +10:00
Tom Pittenger
bcc2838a37 APM_OBC: changed param RC_FAIL_MS to RC_FAIL_TIME in float seconds 2016-04-22 16:05:07 -07:00
Tom Pittenger
f2d744b7c9 APM_OBC: non-functional change - cleaned up logic 2016-04-22 16:05:02 -07:00
James Stoyell
48a7363608 APM_OBC: Added params for AUVSI student competition 2016-04-22 11:48:31 -07:00
Francisco Ferreira
af6d8e3c36 AP_Param: explicitly cast to float to avoid Clang warning
/home/travis/build/ArduPilot/ardupilot/libraries/AP_Param/AP_Param.h:542:22: warning: using floating point absolute value function 'fabsf' when argument is of integer type [-Wabsolute-value]
        bool force = fabsf(_value - v) < FLT_EPSILON;
2016-04-22 17:33:06 +01:00
Randy Mackay
71692044f8 AP_Parachute: resolve compile warning re init order 2016-04-22 21:32:35 +09:00
Tom Pittenger
431b3c7160 AP-TECS: constrain proportion to 0-1 for spdweight scale so it doesn't grow backup after land point 2016-04-21 21:31:02 -07:00
Tom Pittenger
25c3367341 AP_L1 - add a stale flag
threading bug fix. When a mission wp updates, but the L1 controller had not yet, the data is stale. Example, On Plane when NAV_LAND starts for a moment your xtrack and bearing is most likely bear zero regardless if you have a big turn or not until 10 Hz later when the update() gets called and updates those values with correct values for the new waypoint.
2016-04-21 21:30:57 -07:00
Tom Pittenger
2ce964c8ac AP_L1_Controller: add accessor for xtrack_error_integrator 2016-04-21 21:30:54 -07:00
Tom Pittenger
595badce3e AP_TECS: rely on single flag for all land stage differences
recent fixes in Plane have made the stage more accurate so exceptions/hacks are no longer needed to differentiate between knowing if executing NAV_LAND vs being in stage_approach.
2016-04-21 21:30:52 -07:00
Tom Pittenger
0af878703f AP_TECS: move target land_airspeed logic to top layer 2016-04-21 21:30:49 -07:00
Tom Pittenger
525c7b24e3 AP_TECS: created accessor for TECS_LAND_ARSPD param 2016-04-21 21:30:48 -07:00
Andrew Tridgell
0af322e90d HAL_PX4: added comment on oneshot 2016-04-22 13:50:05 +10:00
Andrew Tridgell
5ce7ae71a7 HAL_PX4: fixed enabling oneshot on a subset of motors 2016-04-22 13:24:24 +10:00
Andrew Tridgell
fd7c87e629 AP_Motors: allow enabling oneshot on a subset of motors 2016-04-22 13:24:04 +10:00
Andrew Tridgell
bcd0d48ced HAL_PX4: fixed non-contiguous motor outputs
this fixes tricopter with chan3 never set
2016-04-22 11:51:08 +10:00
Andrew Tridgell
180a7905e5 SITL: make Z down in motors 2016-04-22 10:45:55 +10:00
Andrew Tridgell
46f368f17d HAL_SITL: support fireflyy6 as quadplane 2016-04-22 10:28:15 +10:00
Andrew Tridgell
aa80851138 SITL: support fireflyY6 quadplane model 2016-04-22 10:28:15 +10:00
Andrew Tridgell
8880635fe1 SITL: support vtail and elevon planes in builtin plane sim
remove old tiltrotor in favor of new tiltrotor code
2016-04-22 10:28:15 +10:00
Andrew Tridgell
b4d24d8e03 SITL: fixed rotations of motors by large angles 2016-04-22 10:28:15 +10:00
Andrew Tridgell
6165c42535 AP_Math: added from_axis_angle() method on Matrix3f
for arbitrary rotations in simulator
2016-04-22 10:28:15 +10:00
Andrew Tridgell
f2c63e24c5 AP_Motors: allow tricopter motor 7 to be moved to any output 2016-04-22 08:32:03 +10:00
Tom Pittenger
0e775f595d AP_BattMonitor: make param BATT_WATT_MAX plane only 2016-04-21 13:59:45 -07:00
Rimvydas Naktinis
df922dacfa Plane: Suppress throttle when parachute release initiated, not after release. 2016-04-21 09:53:22 -07:00
Andrew Tridgell
21fb38da8f HAL_SITL: support Y6 frame 2016-04-21 21:11:46 +10:00
Andrew Tridgell
71ca534ec6 SITL: added Y6 frame 2016-04-21 21:11:38 +10:00
Andrew Tridgell
41b3cb2ff7 HAL_SITL: support tri sim 2016-04-21 20:29:58 +10:00
Andrew Tridgell
49822effca SITL: added tricopter simulator 2016-04-21 20:29:49 +10:00
Andrew Tridgell
c262d6a1b4 SITL: break up multicopter into Motor/Frame/Multicopter classes
ready for more tiltrotors
2016-04-21 19:56:44 +10:00
Michael du Breuil
fd51c3cc16 AP_TECS: Remove hgt_afe from update_50hz() 2016-04-21 17:03:00 +10:00
Michael du Breuil
475e731e34 AP_SpdHgt_Control: Remove hgt_afe from update_50hz() 2016-04-21 17:03:00 +10:00
Andrew Tridgell
c765979f9a DataFlash: expose the number of lost log messages
will be logged in PM message
2016-04-21 16:45:02 +10:00
Andrew Tridgell
ced4cce358 AP_Scheduler: added optional perf counters at SCHED_DEBUG >= 4 2016-04-21 16:45:02 +10:00
Randy Mackay
4419b3c617 AHRS_NavEKF: fix get_position by using ekf origin
The EKF's getPosNED returns a vertical position relative to the EKF origin but previously this function was using it as if it was relative to ahrs's home
2016-04-21 11:23:07 +10:00
Jonathan Challinger
a7f959e6f9 AP_Notify: add ToneAlarm_PX4_Solo 2016-04-21 10:05:36 +10:00
Jonathan Challinger
d2ca2d2e0e AP_Notify: change OREOLED config to ifdef 2016-04-21 10:04:37 +10:00
Jonathan Challinger
06ccf88cc9 AP_BattMonitor_SMBus: set AP_Notify powering_off flag 2016-04-21 10:04:37 +10:00
Jonathan Challinger
dba55182af AP_Notify: add flags.powering_off 2016-04-21 10:04:37 +10:00
Andrew Tridgell
ac60901b0c AP_NavEKF2: use vector comparison for new mag vector 2016-04-21 09:56:22 +10:00
Jonathan Challinger
6a5f1c0bec AP_AHRS_NavEKF: reflect changes to getMagOffsets 2016-04-21 09:53:03 +10:00
Jonathan Challinger
97112ccd44 AP_NavEKF2: check mag instance id when returning mag offsets 2016-04-21 09:51:41 +10:00
Jonathan Challinger
6938e3d57b AP_NavEKF: check mag instance id when returning mag offsets 2016-04-21 09:51:41 +10:00
Jonathan Challinger
1185cd1be7 AP_NavEKF2: move getMagOffsets into outputs 2016-04-21 09:51:41 +10:00
Jonathan Challinger
acfaafe276 AP_NavEKF2: detect changes to magnetometer offset parameters and reset states 2016-04-21 09:51:41 +10:00
Andrew Tridgell
835c0b1759 HAL_SITL: follow sqrt law to 60m for wind
this makes testing wind in landings more useful
2016-04-20 17:26:16 +10:00
Andrew Tridgell
57aef8e1e9 SITL: added basic wind support in multicopter, plane and quadplane
this adds non-turbulent wind support for the built-in simulators. I
added it primarily for quadplane testing, but it should also be useful
for multicopter navigation testing.
2016-04-20 11:48:37 +10:00
Andrew Tridgell
28aa4c40cc HAL_PX4: fixed order of wifi and frsky on FMUv4
thanks to OXINARF for noticing!
2016-04-20 10:23:11 +10:00
Andrew Tridgell
4a35f8e9fc HAL_PX4: fixed comments for FMUv4 uarts 2016-04-20 10:08:48 +10:00
Andrew Tridgell
4ef977c68b HAL_SITL: fixed initial path for uartF 2016-04-20 10:08:35 +10:00
Andrew Tridgell
ef180710db AP_SerialManager: fixed doc strings 2016-04-20 10:03:45 +10:00
Andrew Tridgell
62986957b4 GCS_MAVLink: raise number of mavlink buffers to 5 2016-04-20 09:39:50 +10:00
Andrew Tridgell
0baf8ee2eb AP_SerialManager: added SERIAL5_* support 2016-04-20 09:39:49 +10:00
Andrew Tridgell
6120631977 HAL_VRBRAIN: added uartF 2016-04-20 09:39:49 +10:00
Andrew Tridgell
0d27409511 HAL_SITL: added uartF 2016-04-20 09:39:49 +10:00
Andrew Tridgell
9c9f66e5f3 HAL_QURT: added uartF 2016-04-20 09:39:49 +10:00
Andrew Tridgell
18ccaf7e2b HAL_PX4: added uartF 2016-04-20 09:39:49 +10:00
Andrew Tridgell
c7dabad02c HAL_Linux: added uartF 2016-04-20 09:39:49 +10:00
Andrew Tridgell
543604731f HAL_FLYMAPLE: added uartF 2016-04-20 09:39:49 +10:00
Andrew Tridgell
a78e23d6fb HAL_Empty: added uartF 2016-04-20 09:39:49 +10:00
Andrew Tridgell
76868dd070 AP_HAL: added uartF 2016-04-20 09:39:48 +10:00
Andrew Tridgell
2a214f1e46 AP_GPS: support a wider variety of NMEA receivers
some reeivers use a different talker ID. This allows us to accept
them.
2016-04-18 15:30:17 +10:00
Lucas De Marchi
0d9b9433da GCS_MAVLink: fix home position unit
As per documentation the home position is in mm. Since location stores
it in cm, convert to mm before sending.
2016-04-18 13:07:45 +10:00
Michael du Breuil
bb7cf6c0b6 AP_Math: Update location_sanitize to sanitize for lat/lng 2016-04-17 19:00:03 -07:00
Francisco Ferreira
b7135175c9 AC_AttitudeControl: fix heli documentation 2016-04-18 07:40:34 +09:00
Andrew Tridgell
8586b0ae5a APM_Control: added tuning accessors 2016-04-16 20:37:33 +10:00
Andrew Tridgell
a731caa4ab HLA_PX4: prevent timer disturbance in oneshot mode 2016-04-16 18:52:31 +10:00
Andrew Tridgell
6df4d11d3f AP_Motors: ensure OneShot125 is within 125 to 250usec 2016-04-16 18:52:12 +10:00
Andrew Tridgell
d9d6f87195 HAL_PX4: fixed bug in pwm send code
many thanks to Oxinarf for spotting this!
2016-04-16 08:32:04 +10:00
Andrew Tridgell
c9dfccfb26 HAL_PX4: improved oneshot support
this now supports oneshot properly on both IO and FMU
2016-04-16 07:30:44 +10:00
Andrew Tridgell
2304c41f44 AP_BoardConfig: use hal.rcout->enable_sbus_out() 2016-04-16 07:30:43 +10:00
Andrew Tridgell
6f284d673a HAL_PX4: enable oneshot support on px4io 2016-04-16 07:30:43 +10:00
Andrew Tridgell
b94e577cb8 AP_HAL: added enable_sbus_out() call in RCOutput 2016-04-16 07:30:43 +10:00
Lucas De Marchi
ff10d1136c AP_GPS: reorganize includes
Due to the way the headers are organized a single change in a
AP_GPS backend would trigger a rebuild for most of the files in the
project. Time could be saved by using ccache (since most of the things
didn't change) but we can do better, i.e.  re-organize
the headers so we don't have to re-build everything.

This makes internal headers internal and then other libraries only
depend on the AP_GPS.h header.
2016-04-14 21:01:51 -03:00
Andrew Tridgell
e83a3d8185 AP_Camera: clearer parameter docs for trigger pin 2016-04-15 09:33:47 +10:00
Andrew Tridgell
9f31fbb895 AP_Camera: support fast timer capture on AUX4 on Pixhawk
microsecond capture of hot-shoe
2016-04-15 09:28:51 +10:00
Andrew Tridgell
5b8401cbbc AP_BoardConfig: allow setup of more complex modes for aux pins on PX4
this allows for setting up of timer capture pins
2016-04-15 09:23:46 +10:00
Paul Riseborough
1ecc206eee AP_NavEKF2: Allow use in planes without a magnetometer
Implements the following techniques to enable planes to operate without magnetometers.

1) When on ground with mag use inhibited, a synthetic heading equal to current heading is fused to prevent uncontrolled covariance growth.
2) When transitioning to in-flight, the delta between inertial and GPS velocity vector is used to align the yaw.
3) The yaw gyro bias state variance is reset following an in-flight heading reset to enable the yaw gyro bias to be learned faster.
2016-04-15 08:31:47 +10:00
Peter Barker
daa210729c AP_HAL_PX4: correct systemid output for PX4v4 2016-04-14 13:40:27 -07:00
Jonathan Challinger
18240107f0 AP_AHRS_NavEKF: add getGpsGlitchStatus 2016-04-14 12:24:04 +09:00
Jonathan Challinger
a0e291bf89 DataFlash: add reason to MODE 2016-04-14 12:24:04 +09:00
Andrew Tridgell
16b3fe75d1 AP_RSSI: default to analog RSSI on pixracer 2016-04-14 11:13:47 +10:00
pepevalbe
abb667fac3 AP_Notify: enable/disable buzzer in Linux based boards 2016-04-14 08:59:11 +09:00
pepevalbe
c00cbcf076 AP_Notify: enable/disable buzzer in PX4 based boards 2016-04-14 08:59:08 +09:00
pepevalbe
c9862b1502 AP_Notify: New parameter to enable/disable buzzer 2016-04-14 08:59:06 +09:00
Grant Morphett
5861b754cc Rover: fixing a bug the Rover simulation
Just a small change to ensure the max_wheel_turn parameter is used
instead of a hard coded value.
2016-04-14 08:55:04 +09:00
mirkix
0366bce9c1 AP_SerialManager: Fix FrSky baudrate comment 2016-04-14 08:46:49 +09:00
Andrew Tridgell
fe2065cd72 AP_Motors: rename MOT_PWM_MODE to MOT_PWM_TYPE
Randy prefers TYPE
2016-04-14 08:05:07 +10:00
Andrew Tridgell
c3546dfbb0 AP_BoardConfig: default to 6 PWM on FMUv4
less likely to use relays
2016-04-14 08:05:06 +10:00
Andrew Tridgell
8b6322082e AP_SerialManager: default wifi port to MAVLink at 921600 on Pixracer 2016-04-14 08:05:06 +10:00
Andrew Tridgell
8695668da3 HAL_PX4: enable wifi port on FMUv4 2016-04-14 08:05:06 +10:00
Andrew Tridgell
5922e67785 HAL_PX4: allow sbus output on channels beyond BRD_PWM_COUNT 2016-04-14 08:05:06 +10:00
Andrew Tridgell
759b0d6629 HAL_PX4: only support oneshot on FMU outputs for now
oneshot on PX4IO gives some very weird results. I think it is doable,
but will take a bit more work
2016-04-14 08:05:06 +10:00
Andrew Tridgell
f54bcc6c7f AP_Motors: added oneshot support via MOT_PWM_MODE
MOT_PWM_MODE=0 is normal
MOT_PWM_MODE=1 is oneshot
MOT_PWM_MODE=2 is oneshot125
2016-04-14 08:05:05 +10:00
Andrew Tridgell
934b4dd475 HAL_PX4: support OneShot on PX4
this greatly lowers output latency
2016-04-14 08:05:05 +10:00
Andrew Tridgell
e24d600e78 AP_HAL: added hal.rcout->set_output_mode() 2016-04-14 08:05:05 +10:00
Andrew Tridgell
36528965f7 AP_BoardConfig: added 7s timeout on uavcan startup 2016-04-14 08:05:05 +10:00
Andrew Tridgell
1d5deed72a HAL_PX4: fixed build for new px4 param functions 2016-04-14 08:05:04 +10:00
Randy Mackay
8d77bdec15 AP_MotorsMulti: minor comment fix 2016-04-14 05:45:24 +09:00
Lucas De Marchi
affa759fb4 AP_GPS: add missing override 2016-04-13 11:27:19 -03:00
Michael du Breuil
bd6aa982e7 AP_Arming: Fetch GPS configuration failure reason 2016-04-13 11:24:01 -03:00
Michael du Breuil
2538c17ee0 AP_GPS: add fetching of gps configuration failure reasons 2016-04-13 11:24:01 -03:00
Andrew Tridgell
d03a232659 AC_AttitudeControl: added set_limit_accel_xy() API
for preventing integrator buildup
2016-04-10 22:01:18 +10:00
Andrew Tridgell
ed2f26d7b8 RC_Channel: allow for pass-thru from low channels to any channel
this makes it easier to setup things like ignition cut or bottle drop
with a 8 channel radio
2016-04-10 20:33:12 +10:00
hiro2233
7814841cd6 AP_HAL: Add RCOutput interactive example with Menu 2016-04-09 07:01:35 -07:00
Ricardo de Almeida Gonzaga
5bd034a5a8 Global: start using cmath instead of math.h 2016-04-05 21:06:19 -07:00
Ricardo de Almeida Gonzaga
60d141c717 missing: add cmath 2016-04-05 20:44:15 -07:00
Andrew Tridgell
9db618c73c AP_AHRS: disable EKF1 for plane
we are running too close to the 1MByte limit for pixhawk. This
recovers nearly 100kbyte of flash
2016-04-04 11:08:03 +10:00
Andrew Tridgell
7dcd17a2fa SITL: make multicopter motors only effective above 10% 2016-04-02 22:45:05 +11:00
Andrew Tridgell
6bff07397e AP_Math: added linear_interpolate() function 2016-04-02 22:44:47 +11:00
Andrew Tridgell
602ff03c41 AP_TECS: limit both negative and positive pitch on quadplane transition
this makes for smoother auto takeoff
2016-04-02 19:53:16 +11:00
Andrew Tridgell
86416e8f05 AP_Param: added set_default_by_name() 2016-04-01 16:39:51 +11:00
Andrew Tridgell
0530af93aa AP_Param: allow top level parameters to be pointers
this will allow for the attitude_control variable in quadplane to be a
pointer
2016-04-01 16:16:03 +11:00
Randy Mackay
87399776a3 AC_PosControl: hover throttle default to 0.5 2016-04-01 11:59:30 +09:00
Randy Mackay
f6eabfdab2 AP_MotorsMulticopter: formatting fixes 2016-04-01 11:59:30 +09:00
Randy Mackay
6807b961e2 AP_MotorsMulticopter: protect against div-by-zero if MOT_SPIN_ARMED is zero 2016-04-01 11:59:30 +09:00
Randy Mackay
b39798ad90 AP_Motors: remove unused DESIRED_SPIN_MIN_THROTTLE 2016-04-01 11:59:30 +09:00
Randy Mackay
dc86e1472c AP_MotorsTri: protect against div-by-zero if MOT_YAW_SV_ANGLE param was set to 90 2016-04-01 11:59:30 +09:00
Randy Mackay
9b5b6f3779 AP_MotorsHeli: constrain filtered throttle
This is required because we have removed the constraint on the throttle input.  This also insures that there is no lag caused by the filtered throttle straying far outside the 0 to 1 range
2016-04-01 11:59:30 +09:00
Randy Mackay
b4a61e6ccf AP_Motors: remove constrain on throttle input
This constraint is redundant because we already constrain the filtered throttle
2016-04-01 11:59:30 +09:00
Leonard Hall
fce426409e AP_MotorsTri: fix stab patch 2016-04-01 11:59:30 +09:00
Randy Mackay
49562c5ca3 AP_MotorsMulticopter: reduce num bits used for spool-up-down-mode 2016-04-01 11:59:30 +09:00
Randy Mackay
3ee88fd8c7 AP_MotorsCoax: remove output_min
This is now implemented by parent AP_MotorsMulticopter
2016-04-01 11:59:30 +09:00
Randy Mackay
8566a61660 AP_MotorsSingle: remove output_min
This is now implemented by parent AP_MotorsMulticopter
2016-04-01 11:59:30 +09:00
Randy Mackay
8621774040 AP_MotorsTri: remove output_min
This is now implemented by parent AP_MotorsMulticopter
2016-04-01 11:59:30 +09:00
Randy Mackay
f4d94806e5 AP_MotorsMatrix: remove output_min
This is now implemented by parent AP_MotorsMulticopter
2016-04-01 11:59:30 +09:00
Randy Mackay
b4b33db79b AP_MotorsMulticopter: promote output_min from Matrix class 2016-04-01 11:59:30 +09:00
Randy Mackay
2e8acf1f74 AP_MotorsHeli: calculate_scalars made protected
No functional change
2016-04-01 11:59:30 +09:00
Randy Mackay
165d739b45 AC_AttControl_Heli: roll, pitch, yaw passthrough to motors in -1 to +1 range 2016-04-01 11:59:30 +09:00
Randy Mackay
344d86a095 AC_AttControl_Heli: fix parameter description 2016-04-01 11:59:30 +09:00
Randy Mackay
685be4083c AC_AttControl_Heli: remove unnecessary cast to AC_HELI_PID 2016-04-01 11:59:30 +09:00
Randy Mackay
6c91e50f8c AC_AttControl_Heli: remove scaling for centi-degrees and legacy motor input 2016-04-01 11:59:30 +09:00
Randy Mackay
32d238187f AC_AttControl_Heli: get_althold_lean_angle_max in 0 to 1 range 2016-04-01 11:59:30 +09:00
Randy Mackay
db04dddba5 AC_AttControl_Heli: adjust rate gain param descriptions 2016-04-01 11:59:30 +09:00
Randy Mackay
35c6ea994d AC_AttControl_Multi: fix parameter descriptions 2016-04-01 11:59:30 +09:00
Randy Mackay
ace58d114f AC_AttControl_Multi: reduce rate gain defaults 2016-04-01 11:59:30 +09:00
Leonard Hall
b30606bb22 AC_AttControl: remove scaling for centi-degrees and legacy motor input 2016-04-01 11:59:30 +09:00
Randy Mackay
7f2c1f830f AC_AttControl_Heli: add rate PIDs 2016-04-01 11:59:30 +09:00
Randy Mackay
5edc16dfb4 AC_AttControl_Multi: add rate PIDs 2016-04-01 11:59:30 +09:00
Randy Mackay
75042e5e27 AC_AttControl: remove rate PIDs 2016-04-01 11:59:30 +09:00
Randy Mackay
17c9db08f3 AC_AttControl: add angle and rate PIDs 2016-04-01 11:59:30 +09:00
Randy Mackay
de537390c2 AC_HELI_PID: adjust parameter descriptions
ILMI range is now 0 to 1
2016-04-01 11:59:30 +09:00
Randy Mackay
3465f05bec AC_HELI_PID: shorten FILT_HZ to FILT, I_L_MIN to ILMI
Also minor formatting fix
2016-04-01 11:59:30 +09:00
Randy Mackay
425caeabf7 AC_PI_2D: fix parameter description 2016-04-01 11:59:30 +09:00
Randy Mackay
227e4f86d7 AC_PID: fix parameter description 2016-04-01 11:59:30 +09:00
Randy Mackay
920425567c AC_PID: shorten FILT_HZ to FILT 2016-04-01 11:59:30 +09:00
Randy Mackay
bc1b8f415a AP_Motors: example sketch output limit flags 2016-04-01 11:59:30 +09:00
Randy Mackay
c9055ccdb1 AP_Motors: example sketch tests Single and Coax 2016-04-01 11:59:30 +09:00
Randy Mackay
41c55ffbe7 AP_MotorsTri: use YAW_SV_REV to reverse yaw output 2016-04-01 11:59:30 +09:00
Leonard Hall
13d727c2c6 AP_MotorsTri: add YAW_SV_ANGLE parameter to capture yaw servo lean angle max 2016-04-01 11:59:30 +09:00
Randy Mackay
c939cc1551 AP_MotorsTri: clarify YAW_SV parameter descriptions and comments 2016-04-01 11:59:30 +09:00
Leonard Hall
267513d864 AP_MotorsTri: fixes to output_armed_stabilizing
Also minor comment fixes
2016-04-01 11:59:30 +09:00
Leonard Hall
250a444e57 AP_MotorsCoax: fixes to stab patch
Fix throttle_lower flag
Also some formatting changes
2016-04-01 11:59:30 +09:00
Randy Mackay
20565580ed AP_MotorsCoax: remove disabling of output ch7 2016-04-01 11:59:30 +09:00
Randy Mackay
63fefae7cf AP_MotorsCoax: use calc_pwm_output_1ot1 instead of local calc_pivot_radio_output 2016-04-01 11:59:30 +09:00
Leonard Hall
840e60c930 AP_MotorsSingle: fixes to stab patch
Fixes throttle_lower flag
Also some formatting changes
2016-04-01 11:59:30 +09:00
Randy Mackay
af9b18329c AP_MotorsSingle: use calc_pwm_output_1to1 instead of local calc_pivot_radio_output 2016-04-01 11:59:30 +09:00
Randy Mackay
c4b88aafef AP_MotorsHeli: swash and tail servo objects moved into class 2016-04-01 11:59:30 +09:00
Randy Mackay
4f1e62d551 AP_MotorsHeli: remove reset_radio_passthrough 2016-04-01 11:59:30 +09:00
Randy Mackay
b5593431bf AP_MotorsHeli_Single: replace collective_mid_pwm with collective_mid_pct 2016-04-01 11:59:30 +09:00
Randy Mackay
9790245bf1 AP_MotorsHeli: replace collective_mid_pwm with collective_mid_pct 2016-04-01 11:59:30 +09:00
Randy Mackay
a39bbc5421 AP_MotorsHeli: servo_test in range -1 to 1 2016-04-01 11:59:30 +09:00
Randy Mackay
a42706bdcc AP_Motors: remove unused example sketch to test timing
This test was only important on the slower AVR boards
2016-04-01 11:59:30 +09:00
Randy Mackay
a3450b712c AP_Motors: fix example sketch 2016-04-01 11:59:30 +09:00
Leonard Hall
753b72b28c AP_MotorsY6: call normalise_rpy_factors in motor setup 2016-04-01 11:59:30 +09:00
Leonard Hall
13ab3ecfea AP_MotorsQuad: call normalise_rpy_factors in motor setup 2016-04-01 11:59:30 +09:00
Leonard Hall
7ac4fc5569 AP_MotorsOctaQuad: call normalise_rpy_factors in motor setup 2016-04-01 11:59:30 +09:00
Leonard Hall
e182c10625 AP_MotorsOcta: call noramlise_rpy_factors in motor setup 2016-04-01 11:59:30 +09:00
Leonard Hall
733b89cf3c AP_MotorsHexa: call noramlise_rpy_factors in motor setup 2016-04-01 11:59:30 +09:00
Leonard Hall
8f8eb7e214 AP_MotorsMatrix: add normalise_rpy_factors 2016-04-01 11:59:30 +09:00
Randy Mackay
e7ba5ae451 AP_MotorsMulticopter: fix get_hover_throttle_as_high_end_pct 2016-04-01 11:59:30 +09:00
Randy Mackay
4514e8d100 AP_MotorsHeli: remove slow_start 2016-04-01 11:59:30 +09:00
Randy Mackay
c41a5dc3bd AP_MotorsMulticopter: remove slow_start
This has been replaced with the spool logic feature
2016-04-01 11:59:30 +09:00
Randy Mackay
b436dde60c AP_Motors: remove slow_start
This has been replaced with the spool logic feature
2016-04-01 11:59:30 +09:00
Randy Mackay
e863f0b9c0 AP_MotorsHeli: use AP_Motors set_radio_passthrough in 0 to 1 range 2016-04-01 11:59:30 +09:00
Randy Mackay
68a6408a23 AP_MotorsMulticopter: remove set_radio_passthrough
This has been moved up to the AP_Motors class
2016-04-01 11:59:30 +09:00
Randy Mackay
5ba3a6c536 AP_Motors: add set_radio_passthrough 2016-04-01 11:59:30 +09:00