Commit Graph

11284 Commits

Author SHA1 Message Date
Andrew Tridgell
4e4c575f16 AP_NavEKF2: added have_ekf_logging() 2016-05-07 18:27:20 +10:00
Andrew Tridgell
b7ba0fa458 AP_NavEKF2: added ad-hoc logging example to EKF2 2016-05-07 18:27:20 +10:00
Andrew Tridgell
4e5f1374da AP_GPS: added setHil_Accuracy() 2016-05-07 18:27:19 +10:00
Andrew Tridgell
88a1ebaf0e AP_Compass: allow setting of exact timestamp in HIL compass 2016-05-07 18:27:19 +10:00
Andrew Tridgell
4318fd0ab8 HAL_SITL: update for changed API 2016-05-07 18:27:19 +10:00
Andrew Tridgell
61da827c16 DataFlash: added sample timestamp to mag messages
allows for exact mag timings in replay
2016-05-07 18:27:19 +10:00
Andrew Tridgell
795080742e AP_AHRS: added have_ekf_logging() API 2016-05-07 18:27:19 +10:00
Andrew Tridgell
7ab1367ec4 DataFlash: removed logging of relative alt in GPS messages
not related to GPS and makes it impossible to do bit-identical replay
2016-05-07 18:27:18 +10:00
Andrew Tridgell
223c512188 AP_NavEKF2: added logging of sensor data in EKF2 2016-05-07 18:27:18 +10:00
Andrew Tridgell
2718b0649b HAL_SITL: fixed GPS rate in SITL when speedup used 2016-05-07 18:27:18 +10:00
Andrew Tridgell
8a987bf67d AP_Baro: removed filtering of baro data in HIL/SITL
this was just causing lag in replay and doesn't actually help in SITL
2016-05-07 18:27:18 +10:00
Andrew Tridgell
c85607b80c AP_GPS: added time_epoch_convert() function
used by replay to get identical timestamps
2016-05-07 18:27:18 +10:00
Andrew Tridgell
07060051cf AP_AHRS: added API for forcing EKF to start
used by Replay to sync start times
2016-05-07 18:27:18 +10:00
Andrew Tridgell
f92279f436 AP_NavEKF2: allow logging of IMT data from inside EKF2 2016-05-07 18:27:17 +10:00
Andrew Tridgell
2965e67d5d HAL_Linux: cope with non-root for Replay 2016-05-07 18:27:17 +10:00
Randy Mackay
4a06ca4be2 AC_AttControl: remove unused call to motors.set_stabilizing
Also minor change to order of a call to motors library to make stabilizing
and non-stabilizing calls consistent.

Non functional change
2016-05-07 10:08:38 +09:00
Randy Mackay
e41f798ba1 AP_Motors: remove unused set_stabilizing 2016-05-07 10:08:36 +09:00
Andrew Tridgell
ab0b76764f RC_Channel: added set_servo_failsafe_pwm() 2016-05-07 07:25:27 +10:00
Andrew Tridgell
46f257fd9b DataFlash: convert Log_Write() to use a linked list
this saves some memory and means we don't need to know how many we
will need in advance
2016-05-07 07:21:16 +10:00
Andrew Tridgell
9a1cbff850 DataFlash: allow access to DataFlash instance as a static singleton 2016-05-07 07:21:16 +10:00
Peter Barker
11dd254498 DataFlash: Log_Write optimisations 2016-05-07 07:21:16 +10:00
Peter Barker
cf15bb5f6e DataFlash: AllTypes example also covers Log_Write 2016-05-07 07:21:16 +10:00
Peter Barker
b273514cf9 DataFlash: create example outputting all field types 2016-05-07 07:21:16 +10:00
Peter Barker
518fabe035 DataFlash: StopLogging method, virtual stop_logging on backends 2016-05-07 07:21:16 +10:00
Peter Barker
77dd170e03 DataFlash: Log_Write support
A generic logging method to avoid the need to set up a format and structures etc
2016-05-07 07:21:16 +10:00
Peter Barker
334af1ecd7 DataFlash: base class method for resetting state on log open 2016-05-07 07:21:16 +10:00
Peter Barker
eea2d5dcb5 DataFlash_File: avoid integer wrap when checking minimum time 2016-05-07 07:21:15 +10:00
Michael Day
62a7074dd7 AP_Mission: Added mavlink_cmd_long_to_mission_cmd method. 2016-05-06 11:59:44 -07:00
Lucas De Marchi
fea084a596 Global: use ap_version.h
This header is used by waf to contain the generated version macros,
particularly using the git hash. For waf it's better to be in a separate
header since it then can keep track of changes on it a trigger
recompilation.

For the make build system, a dummy ap_version.h file has been added in
the missing/ folder so both implementations can co-exist.
2016-05-06 13:11:28 -03:00
Lucas De Marchi
1238c872a9 AP_Common: remove unused Arduino.h header 2016-05-06 13:11:27 -03:00
Allan Matthew
d01db0edd6 AC_PrecLand: remove PI controller, speed limits as they are unused 2016-05-06 11:04:12 +09:00
skyscraper
134ea338da RC_Channel: remove unused control_mix method 2016-05-05 18:58:17 -03:00
Andrew Tridgell
9c4dd024bf AP_NavEKF2: auto change EK2_GPS_TYPE for NMEA
this fixes a problem where users of NMEA GPS receivers could not arm
with default EK2 parameters.
2016-05-05 19:46:33 +10:00
Andrew Tridgell
826cb0887a AP_SerialManager: changed default for SERIAL4_PROTOCOL to 5
this makes it a documented protocol number. No functionality change
2016-05-05 08:08:30 +10:00
Lucas De Marchi
cf11776150 AP_HAL: fix signed and unsigned comparison warning
../../libraries/AP_HAL/examples/Printf/Printf.cpp:63:17: warning: comparison between signed and unsigned integer expressions [-Wsign-compare]
         if (ret != strlen(float_tests[i].result)) {
                 ^
...

ardupilot/modules/gtest/include/gtest/gtest.h:1448:16: warning: comparison between signed and unsigned integer expressions [-Wsign-compare]
   if (expected == actual) {
                ^
And similar ones.
2016-05-04 08:58:37 -03:00
Lucas De Marchi
9ac63d7128 AP_HAL: examples: fix coding style 2016-05-04 08:58:37 -03:00
Lucas De Marchi
b5d3094738 AP_ADC: fix warning on printf
../../libraries/AP_ADC/examples/AP_ADC_test/AP_ADC_test.cpp: In function ‘void show_timing()’:
../../libraries/AP_ADC/examples/AP_ADC_test/AP_ADC_test.cpp:61:88: warning: format ‘%lu’ expects argument of type ‘long unsigned int’, but argument 3 has type ‘uint32_t {aka unsigned int}’ [-Wformat=]
     hal.console->printf("timing: mint=%lu maxt=%lu avg=%lu\n", mint, maxt, totalt/count);
                                                                                        ^
../../libraries/AP_ADC/examples/AP_ADC_test/AP_ADC_test.cpp:61:88: warning: format ‘%lu’ expects argument of type ‘long unsigned int’, but argument 4 has type ‘uint32_t {aka unsigned int}’ [-Wformat=]
../../libraries/AP_ADC/examples/AP_ADC_test/AP_ADC_test.cpp:61:88: warning: format ‘%lu’ expects argument of type ‘long unsigned int’, but argument 5 has type ‘uint32_t {aka unsigned int}’ [-Wformat=]
2016-05-04 08:58:37 -03:00
Randy Mackay
53785d1f72 AP_RangeFinder: add Bebop and MAVLink types
Thanks OXINARF!
2016-05-04 15:00:48 +09:00
Randy Mackay
96f665061e AP_RangeFinder: call handle_msg for all backends 2016-05-04 12:10:58 +09:00
Randy Mackay
9b940687c1 AP_RangeFinder: rename CompanionComputer files to MAVLink 2016-05-04 12:10:58 +09:00
Randy Mackay
c541cb27f8 AP_RangeFinder: rename CompanionComputer to MAVLink 2016-05-04 12:10:58 +09:00
Allan Matthew
d3831e4a5d RangeFinder: add MAVLink rangefinder 2016-05-04 12:10:58 +09:00
Andrew Tridgell
7cdab2a6c9 SITL: FlightAxis can support 8 channels 2016-05-04 13:05:43 +10:00
Andrew Tridgell
9081310ff1 HAL_SITL: support simulator RC input 2016-05-04 12:51:28 +10:00
Andrew Tridgell
3b0cd9f101 SITL: added RC input from FlightAxis
use the interlink controller for input for 6 channels
2016-05-04 12:51:27 +10:00
Julien Beraud
33a699f29c AP_RangeFinder: Add support for bebop Rangefinder
This rangefinder uses an spi device to send pulses and an iio driver
in buffer mode to get data
The data is then analyzed and the maximum pulse received is considered to
represent the echo of the pulses that have been sent. The distance in time
between the pulse that is sent and the pulse with the maximum amplitude
is used to calculate the altitude based on the speed of sound.

There is a dependency with libiio, and in order to build, there is a need
to provide a rootfs that includes libiio.a.
The other solution is to build dynamically after having updated the rootfs
to use on compiled with a more recent toolchain and include libiio
2016-05-03 16:43:39 -03:00
Julien Beraud
c22d791bfc AP_HAL_Linux: Add SPI driver for bebop 2016-05-03 16:43:39 -03:00
Julien Beraud
d0114eac05 AP_HAL: Add bebop SPI Device to spi devices
Added to namespace
2016-05-03 16:43:39 -03:00
Julien Beraud
738096b3ae AP_HAL_Linux: Add support for Sonar GPIO 2016-05-03 16:43:39 -03:00
Andrew Tridgell
664ce5c16e AP_AHRS: don't use disabled gyro in rate controllers
obey INS_USE* parameters in gyro estimate
2016-05-01 22:16:06 +10:00
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