Commit Graph

17691 Commits

Author SHA1 Message Date
Gustavo Jose de Sousa 83c64daf19 APM_PI: standardize inclusion of libaries headers
This commit changes the way libraries headers are included in source files:

 - If the header is in the same directory the source belongs to, so the
 notation '#include ""' is used with the path relative to the directory
 containing the source.

 - If the header is outside the directory containing the source, then we use
 the notation '#include <>' with the path relative to libraries folder.

Some of the advantages of such approach:

 - Only one search path for libraries headers.

 - OSs like Windows may have a better lookup time.
2015-08-19 20:42:15 +09:00
Gustavo Jose de Sousa 60c0f160b3 APM_OBC: standardize inclusion of libaries headers
This commit changes the way libraries headers are included in source files:

 - If the header is in the same directory the source belongs to, so the
 notation '#include ""' is used with the path relative to the directory
 containing the source.

 - If the header is outside the directory containing the source, then we use
 the notation '#include <>' with the path relative to libraries folder.

Some of the advantages of such approach:

 - Only one search path for libraries headers.

 - OSs like Windows may have a better lookup time.
2015-08-19 20:42:14 +09:00
Gustavo Jose de Sousa a9acfcb615 APM_Control: standardize inclusion of libaries headers
This commit changes the way libraries headers are included in source files:

 - If the header is in the same directory the source belongs to, so the
 notation '#include ""' is used with the path relative to the directory
 containing the source.

 - If the header is outside the directory containing the source, then we use
 the notation '#include <>' with the path relative to libraries folder.

Some of the advantages of such approach:

 - Only one search path for libraries headers.

 - OSs like Windows may have a better lookup time.
2015-08-19 20:42:13 +09:00
Gustavo Jose de Sousa 664fbc9be8 AC_WPNav: standardize inclusion of libaries headers
This commit changes the way libraries headers are included in source files:

 - If the header is in the same directory the source belongs to, so the
 notation '#include ""' is used with the path relative to the directory
 containing the source.

 - If the header is outside the directory containing the source, then we use
 the notation '#include <>' with the path relative to libraries folder.

Some of the advantages of such approach:

 - Only one search path for libraries headers.

 - OSs like Windows may have a better lookup time.
2015-08-19 20:42:12 +09:00
Gustavo Jose de Sousa 13ba4c90f5 AC_Sprayer: standardize inclusion of libaries headers
This commit changes the way libraries headers are included in source files:

 - If the header is in the same directory the source belongs to, so the
 notation '#include ""' is used with the path relative to the directory
 containing the source.

 - If the header is outside the directory containing the source, then we use
 the notation '#include <>' with the path relative to libraries folder.

Some of the advantages of such approach:

 - Only one search path for libraries headers.

 - OSs like Windows may have a better lookup time.
2015-08-19 20:42:11 +09:00
Gustavo Jose de Sousa bdf33e91e4 AC_PID: standardize inclusion of libaries headers
This commit changes the way libraries headers are included in source files:

 - If the header is in the same directory the source belongs to, so the
 notation '#include ""' is used with the path relative to the directory
 containing the source.

 - If the header is outside the directory containing the source, then we use
 the notation '#include <>' with the path relative to libraries folder.

Some of the advantages of such approach:

 - Only one search path for libraries headers.

 - OSs like Windows may have a better lookup time.
2015-08-19 20:42:10 +09:00
Gustavo Jose de Sousa b69efc510d AC_Fence: standardize inclusion of libaries headers
This commit changes the way libraries headers are included in source files:

 - If the header is in the same directory the source belongs to, so the
 notation '#include ""' is used with the path relative to the directory
 containing the source.

 - If the header is outside the directory containing the source, then we use
 the notation '#include <>' with the path relative to libraries folder.

Some of the advantages of such approach:

 - Only one search path for libraries headers.

 - OSs like Windows may have a better lookup time.
2015-08-19 20:42:09 +09:00
Gustavo Jose de Sousa 45cd929074 AC_AttitudeControl: standardize inclusion of libaries headers
This commit changes the way libraries headers are included in source files:

 - If the header is in the same directory the source belongs to, so the
 notation '#include ""' is used with the path relative to the directory
 containing the source.

 - If the header is outside the directory containing the source, then we use
 the notation '#include <>' with the path relative to libraries folder.

Some of the advantages of such approach:

 - Only one search path for libraries headers.

 - OSs like Windows may have a better lookup time.
2015-08-19 20:42:08 +09:00
Gustavo Jose de Sousa 5aa7cd0e37 Tools: standardize inclusion of libaries headers
This commit changes the way libraries headers are included in source files:

 - If the header is in the same directory the source belongs to, so the
 notation '#include ""' is used with the path relative to the directory
 containing the source.

 - If the header is outside the directory containing the source, then we use
 the notation '#include <>' with the path relative to libraries folder.

Some of the advantages of such approach:

 - Only one search path for libraries headers.

 - OSs like Windows may have a better lookup time.
2015-08-19 20:42:06 +09:00
Gustavo Jose de Sousa c1b9ebc0e4 ArduPlane: standardize inclusion of libaries headers
This commit changes the way libraries headers are included in source files:

 - If the header is in the same directory the source belongs to, so the
 notation '#include ""' is used with the path relative to the directory
 containing the source.

 - If the header is outside the directory containing the source, then we use
 the notation '#include <>' with the path relative to libraries folder.

Some of the advantages of such approach:

 - Only one search path for libraries headers.

 - OSs like Windows may have a better lookup time.
2015-08-19 20:42:05 +09:00
Gustavo Jose de Sousa f91ef9382d ArduCopter: standardize inclusion of libaries headers
This commit changes the way libraries headers are included in source files:

 - If the header is in the same directory the source belongs to, so the
 notation '#include ""' is used with the path relative to the directory
 containing the source.

 - If the header is outside the directory containing the source, then we use
 the notation '#include <>' with the path relative to libraries folder.

Some of the advantages of such approach:

 - Only one search path for libraries headers.

 - OSs like Windows may have a better lookup time.
2015-08-19 20:42:04 +09:00
Gustavo Jose de Sousa 9a65b3e9ca AntennaTracker: standardize inclusion of libaries headers
This commit changes the way libraries headers are included in source files:

 - If the header is in the same directory the source belongs to, so the
 notation '#include ""' is used with the path relative to the directory
 containing the source.

 - If the header is outside the directory containing the source, then we use
 the notation '#include <>' with the path relative to libraries folder.

Some of the advantages of such approach:

 - Only one search path for libraries headers.

 - OSs like Windows may have a better lookup time.
2015-08-19 20:42:03 +09:00
Gustavo Jose de Sousa 01397cb00c APMrover2: standardize inclusion of libaries headers
This commit changes the way libraries headers are included in source files:

 - If the header is in the same directory the source belongs to, so the
 notation '#include ""' is used with the path relative to the directory
 containing the source.

 - If the header is outside the directory containing the source, then we use
 the notation '#include <>' with the path relative to libraries folder.

Some of the advantages of such approach:

 - Only one search path for libraries headers.

 - OSs like Windows may have a better lookup time.
2015-08-19 20:42:02 +09:00
Andrew Tridgell 5ce802b946 HAL_PX4: fixed USB connected on AUAV-X2
this is the 2nd attempt at a fix for the usb_connected status on
AUAV-X2
2015-08-19 20:42:01 +09:00
Randy Mackay 4ae8e36000 INS: accel offset parameter range desc to 3.5m/s/s 2015-08-19 20:42:00 +09:00
Daniel Frenzel 166a4f5b5a AP_Scheduler example
Fixed build problem with "make linux"

Signed-off-by: Daniel Frenzel <dgdanielf@gmail.com>
2015-08-19 20:41:59 +09:00
Andrew Tridgell 347c436394 GCS_MAVLink: fixed bug setting parameters to default values
in copter if you try to set RATE_RLL_D to 0 when you haven't
prevviously changed it then it would set it, but would revert on the
next reboot. This is because of the special case handling of a set to
the "default" value. That default value is unaware of the PID
constructors

this fixes that behaviour by forcing a save if the parameter changes
value
2015-08-19 20:41:58 +09:00
Andrew Tridgell cb8356a290 AP_Param: replaced set_param_by_name with set_float
read for bugfix in GCS_MAVLink
2015-08-19 20:41:57 +09:00
Andrew Tridgell ffefe425df PX4NuttX: submodule update 2015-08-19 20:41:56 +09:00
Jonathan Challinger abaebac11c Copter: bug fix to RTL_ALT_MIN feature
commited by Randy
2015-08-19 20:41:55 +09:00
Michael du Breuil 789a588b30 AP_HAL_SITL: Add hdop to ublox sitl sim (as well as vdop to be reported) 2015-08-19 20:40:19 +09:00
Lucas De Marchi d0014c4fe3 AP_InertialSensor: refactor constructors to avoid leak
We were previously leaking the AP_MPU6000_BusDriver if the
~AP_InertialSensor_MPU6000::detect*() failed. In order to avoid the
leak move the repeated code in a single private _detect() member that
receives everything as argument. Then this method takes ownership of the
objects.

By a adding a destructor to AP_InertialSensor_MPU6000 it becomes easier to
free the objects it takes ownership of.
2015-08-19 20:40:17 +09:00
Lucas De Marchi 5fbbdca9f9 AP_InertialSensor: MPU6000: be agnostic to I2C bus/address
This decision is better made by the caller rather than polluting the
driver with board-specific details.
2015-08-19 20:40:16 +09:00
Lucas De Marchi a9a0e228ac AP_InertialSensor: pass backend instead of pointer to function
Different detect() function might need different arguments and passing a
pointer to function here is cumbersome. For example, it forces to have a
method like "detect_i2c2" rather than allowing hal.i2c2 to be passed as
parameter.
2015-08-19 20:40:15 +09:00
Gustavo Jose de Sousa f31fe780eb AP_InertialSensor: L3G4200D: add probe code
This driver works properly but had the initialization logic missing. Add
the support to probe it.
2015-08-19 20:40:14 +09:00
Lucas De Marchi dd523c0301 AP_InertialSensor: remove out of place ifdef
AP_InertialSensor isn't a good place to comment about board issues.
2015-08-19 20:40:13 +09:00
Lucas De Marchi 886b302019 AP_InertialSensor: remove unused enum bus_speed
The methods actually use the enum from AP_HAL::SPIDeviceDriver, so don't
declare a new one. The I2C implementation is empty; if we actually start
to use it we'd better move the bus abstraction to HAL.
2015-08-19 20:40:12 +09:00
Lucas De Marchi 1c3728a585 AP_InertialSensor: fix copying wrong number of bytes
We should copy only the bytes we read, not the maximum number.
2015-08-19 20:40:11 +09:00
Lucas De Marchi 5b2ff84c06 AP_InertialSensor: fix whitespace usage 2015-08-19 20:40:10 +09:00
Lucas De Marchi abd0514319 AP_InertialSensor: remove unused drivers
Nobody is using these drivers, they need to be rewritten using the
backend logic and give the false impression they are supported.
2015-08-19 20:04:18 +09:00
Gustavo Jose de Sousa 6d89a8cf71 StorageManager: remove unnecessary calculations on addr for next area
When writting or reading a block, if the block doesn't fit the area where it begins, the next base address is always zero. Thus the calculations to define the next value of addr are unnecessary.

Here's a quick validity proof using the previous calculations:
    First: Considering the case where the block doesn't fit it's first area:
        That means that (count + addr > length), what makes:
            count = length - addr; (1)
        So the following operations:
            addr += count;
            addr -= length;
        Are the same as doing:
            addr = addr + count - length; (2)
        Using (1) and (2) we have:
            addr = addr + length - addr - length = 0

    Second: When the block fits the area where it's at:
        That means that variable count is not changed,
        thus (n -= count) evaluates to 0, which makes the loop exit.

Another change was (b += count;) being moved after the condition to break the loop, since we just need to move the block pointer when it doesn't fit the first area.
2015-08-19 20:04:17 +09:00
Andrew Tridgell 54b7a2db60 PX4Firmware: submodule update 2015-08-19 20:04:16 +09:00
Randy Mackay 53ed6c8f05 Motors_Multicopter: add MOT_THR_MIX_MAX parameter
Allows controlling the prioritisation of throttle vs attitude control
during active flight
2015-08-19 20:04:15 +09:00
Randy Mackay b0101eab91 OpticalFlow_Linux: reworked driver
remove PANICs from init
return semaphore if init fails
add successful initialisation check before attempting to read from sensor
structure made private where possible
formatting fixes
check I2C reads succeed
add request_measurement to request sensor to produce measurement
quit after 20 of previous 40 reads fail
throttle reads to 10hz max
2015-08-19 20:04:14 +09:00
Víctor Mayoral Vilches 46c30f94ef AP_OpticalFlow: Add support for Linux
Add a Linux userspace driver for the PX4FLOW sensor.
2015-08-19 20:04:13 +09:00
Randy Mackay 539c6fe525 BattMon_SMBus: remove unnecessary I2C semaphore give 2015-08-19 20:04:12 +09:00
Randy Mackay ac8c708327 Compass_HMC5843: remove unnecessary i2c semaphore give 2015-08-19 20:04:11 +09:00
Grant Morphett f181d7edbe Rover: Lets put Rover into BETA - v2.2.51
I also made myself the maintainer - ssshhh - don't tell Tridge.
2015-08-19 20:04:10 +09:00
Grant Morphett 0edffdb7d3 Rover: fixed bug when reverse throttle would increase speed in AUTO
Fixed this bug
https://github.com/diydrones/ardupilot/issues/840
If a Rover was in AUTO and the user moved the throttle stick into
reverse past 50% the rover would increase.  Basically the throttle
nudge behaviour was the same regardless of whether you moved the
throttle forward or backward.
2015-08-19 20:04:09 +09:00
squilter 7c575b251a Plane: init vehicle capabilities 2015-08-19 20:04:08 +09:00
Randy Mackay 328332d6c0 DataFlash: consolidate GPS, GPS2 messages
Remove unused dgps_numch, dgps_age from GPS2
Add U field (for use) to both GPS and GPS2
2015-08-19 20:04:07 +09:00
Grant Morphett 9284f30d95 Rover: scheduler remaining time loop calc made common
Just making the improved scheduler loop remaining time calculation in line with
Plane and Copter.
2015-08-19 20:04:06 +09:00
Andrew Tridgell 9fbd739ebe AP_AHRS: protect against zero deltat in DCM
fixes issue #2657
2015-08-19 20:04:05 +09:00
Randy Mackay 34a5c46bfd AC_WPNav: remove unused definitions 2015-08-19 20:04:04 +09:00
Randy Mackay 7fb7b4d74e AC_WPNav: replace hardcoded 0.02 with pos_control dt 2015-08-19 20:04:03 +09:00
Leonard Hall 2ec34b14fc AC_WPNav: fix spline height loss 2015-08-19 20:04:02 +09:00
Michael du Breuil 2e699095a6 AP_GPS: Default the value of hdop to 99.99 if no value has been read yet. 2015-08-19 20:04:00 +09:00
Randy Mackay aeef23c183 Rally: rename RALLY_HOME_INC param to INCL_HOME
Also default include-home to 1 only for copter
Also minor formatting and comment changes
2015-08-19 20:03:59 +09:00
KiwiHC16 7e99a052b8 Rally: add RALLY_HOME_INC param to use Home as a Rally point 2015-08-19 20:03:58 +09:00
Julien BERAUD 407bb5933b AP_Compass_AK8963: suspend timer while reading
Protection in case a timer falls while reading data, because it could end up
with corrupted data
2015-08-19 20:03:57 +09:00