Commit Graph

10669 Commits

Author SHA1 Message Date
Tom Pittenger a139789693 AP_TECS: add TECS_LAND_TDAMP for land damp
+     // @Description: This is the damping gain for the throttle demand loop during and auto-landing. Same as TECS_THR_DAMP but only in effect during an auto-land. Increase to add damping to correct for oscillations in speed and height. When set to 0 landing throttle damp is controlled by TECS_THR_DAMP.
2016-03-02 10:54:19 -08:00
Tom Pittenger 035f3b16a1 AP_BattMonitor: add new param BATT_WATT_MAX
Description: If battery wattage (voltage * current) exceeds this value then the system will reduce max throttle (THR_MAX and TKOFF_THR_MAX) to satisfy this limit. This helps limit high current to low C rated batteries regardless of battery voltage. The max throttle will slowly grow back to THR_MAX (or TKOFF_THR_MAX) if demanding the current max and under the watt max.
2016-03-02 10:14:25 -08:00
Tom Pittenger 278fb2e60d AP_Math: add location sanity checker/fixer util 2016-03-02 08:48:26 -08:00
Tom Pittenger 1c513a99a0 AP_Mission: removed LOITER_TO_ALT heading requirement param field
- and increased loiter radius max size (8bit to 16bit), it will soon always have heading requirement along with all loiter cmds
2016-03-02 08:48:24 -08:00
Alexey Bulatov 3933ac2a63 AP_GPS: Added ERB to AP_GPS 2016-03-02 06:04:52 -08:00
Alexey Bulatov 7e2c822499 AP_GPS: Structure for detect ERB 2016-03-02 06:04:46 -08:00
Alexey Bulatov 97190c89d1 AP_GPS: ERB GPS driver
ERB - Emlid Reach Binary protocol.
That driver designed for communication between Reach
and ArduPilot.
Provided opportunities:
- Detection of the driver
- Parsing of input messages: status of transmitter
and navigation information.
- Inject GPS messages from base
2016-03-02 06:04:39 -08:00
Jonathan Challinger e946e047e6 AC_AttitudeControl: add attitude_controller_run functions, call from input functions 2016-03-02 20:16:18 +09:00
Tom Pittenger c0a6a94936 AP_IntertialNav: ensure we work on valid updated data 2016-03-02 10:53:07 +09:00
Paul Riseborough 38b3625ed8 AP_NavEKF2: Fix bug in initial alignment calculation
The bug caused the initial roll angle to be incorrect if the vehicle was powered up when inverted, causing long alignment times.
2016-03-02 09:10:09 +09:00
Paul Riseborough 2888bdd6d5 AP_NavEKF: Protect against possible div by 0 2016-03-01 10:08:47 -03:00
Paul Riseborough 7d6b926749 AP_NavEKF2: Improved magnetic heading fusion
Use an Euler yaw heading that switches between a 321 and 312 rotation
sequence to avoid areas of singularity.  Using Euler yaw decouples the
observation from the roll and pitch states and prevents magnetic
disturbances from affecting roll and pitch via the magnetometer fusion
process.
2016-03-01 10:08:47 -03:00
Randy Mackay e502e0fc2e SoloGimbal: resolve compiler warning re float comparison 2016-03-01 21:51:43 +09:00
Randy Mackay 438769c8ae SoloGimbal: resolve compiler warning re initialisation order 2016-03-01 21:51:41 +09:00
Paul Riseborough bb74371c58 AP_NavEKF2: Do not use GPS height if GPS accuracy is poor
If we are using GPS height, revert back to using Baro height if the GPS accuracy is poor.
2016-03-01 15:13:13 +09:00
Tom Pittenger b1ea82079e AP_Rangefinder: compiler warning float to double on atof()
- this is horribly inefficient so better to change the parsing
2016-02-29 10:26:31 -08:00
Tom Pittenger 068374658c AP_Mission: utilize radius for loiter commands 2016-02-29 06:43:19 -08:00
Will Sackfield 8b5fa9d23d SITL: Initialise yaw_rate and pitch_rate
* Clang requires these variables to be initialized
2016-02-29 14:14:37 +11:00
Will Sackfield 6f43b7121c DataFlash: Cast msg to uint8
* Clang requires this explicit cast
2016-02-29 14:14:37 +11:00
Will Sackfield 723e166c13 AP RPM: Initialise backend with _instance
* Unsure how this worked in the past
2016-02-29 14:14:37 +11:00
Will Sackfield 0a60d713af AP HAL SITL: Use fully qualified SITL namespace
* using namespace SITL caused ambiguities due to
both SITL and HAL SITL using the same namespace
2016-02-29 14:14:37 +11:00
Will Sackfield 8c98eb2b84 APMControl: Cast type to uint8
* Clang requires that the type be explicitly cast
to uint8
2016-02-29 14:14:37 +11:00
Staroselskii Georgii 5b3627f83e AP_Notify: made DiscreteRGBLed more generic
- made pins and polarity configurable
- got rid of all Navio specific code
2016-02-27 03:06:50 -03:00
Staroselskii Georgii ef4e3aa333 AP_Notify: renamed Navio2Led to DiscreteRGBLed 2016-02-27 03:06:50 -03:00
Staroselskii Georgii 0bd7839b9f AP_Notify: made Navio2LED a little easier to configure
- got rid of a lot of not needed defines
- allocated channels on init instead of accessing them every time
  through the HAL reference
- simpliefied hw_set_rgb()
2016-02-27 03:06:50 -03:00
Staroselskii Georgii da550e5e98 AP_Inertial_Sensor: do not rotate MPU9250 on Navio2 2016-02-27 03:06:50 -03:00
Staroselskii Georgii f93e790717 AP_HAL_Linux: make Ublox work on the higher frequency
The lower speed was only valid for very old Navio's. All new boards ship
with the GPSs that support higher frequencies.
2016-02-27 03:06:50 -03:00
Staroselskii Georgii a327a8779e AP_HAL_Linux: added Navio2 support 2016-02-27 03:06:50 -03:00
Staroselskii Georgii 7187f26220 AP_HAL_Linux: use Raspberry Pi GPIO for Navio2 2016-02-27 03:06:50 -03:00
Staroselskii Georgii 6680baf777 AP_HAL_Linux: use MPU9250 for Navio2 2016-02-27 03:06:50 -03:00
Staroselskii Georgii c9869e768a AP_HAL_Linux: use Util_RPI for Navio2 2016-02-27 03:06:50 -03:00
Staroselskii Georgii 23a2cf45aa AP_HAL_Linux: added RCInput for Navio2 2016-02-27 03:06:50 -03:00
Staroselskii Georgii 2ea69571ef AP_Notify: disabled boardled for Navio 2016-02-27 03:06:50 -03:00
Staroselskii Georgii 3223802431 AP_Notify: enabled leds for Navio2 2016-02-27 03:06:50 -03:00
Alexey Bulatov fc6351b929 AP_Notify: added Navio2LED driver 2016-02-27 03:06:50 -03:00
Staroselskii Georgii a24e9df765 AP_HAL_Linux: added AnalogIn_Navio2
This is a shim driver around the temporarily interface that is exported via
sysfs entries.
2016-02-27 03:06:50 -03:00
Staroselskii Georgii 392165c6a2 AP_HAL: added Navio2 board definitions 2016-02-27 03:06:50 -03:00
Staroselskii Georgii 6172ed078e GCS_Mavlink: send power status from all boards 2016-02-27 03:06:50 -03:00
dgrat 672acdc8ef AP_Math: Created location.h header for location functions
Helps to order AP_Math functions by purpose.
2016-02-27 02:51:33 -03:00
Lucas De Marchi 7f685a12bd AP_Math: remove trailing whitespaces and tabs 2016-02-27 02:51:33 -03:00
dgrat 5148e41c1a AP_Math: Cleaned macro definitions
Moved Definitions into a separate header. Replaced PI with M_PI and
removed the M_PI_*_F macros.
2016-02-27 02:51:33 -03:00
dgrat 7c4c8ea579 AP_Math: Remove ROTATION_COMBINATION_SUPPORT
This function is not used.
2016-02-27 02:51:33 -03:00
Gustavo Jose de Sousa 6144226c51 AP_HAL: always define HAL_OS_SOCKETS
And avoid warnings.
2016-02-26 14:17:33 -03:00
AndersonRayner c9d5c548a6 Corrects a bracket error for the LSM9DS0 IMU
Switches the probe of the accel and gyro so they boot correctly (was
failing the WHOAMI with a switched result)
2016-02-25 20:08:01 -03:00
Michael du Breuil 287a3367ad AP_HAL_SITL: Force the simulated gps time to be on valid intervals for u-blox hardware 2016-02-26 09:57:03 +11:00
Daniel Frenzel ead51a9d19 AP_Math: Removed useless "undef INLINE" 2016-02-25 02:10:39 -03:00
Daniel Frenzel ef7cf7c4aa AP_Math: Removed useless header
"float.h" does not exist. It is useless and wrong to include it.
2016-02-25 02:10:39 -03:00
Andrew Tridgell 04bac8a446 AP_GPS: removed duplicate dataflash write of ublox version 2016-02-24 14:26:57 +11:00
Andrew Tridgell 14bd4ba2c7 AP_GPS: removed console print for GPS type
it is now sent as a STATUSTEXT
2016-02-24 14:22:48 +11:00
Michael du Breuil 1426ff2732 AP_GPS: Broadcast what type of GPS is found and at what baud rate 2016-02-24 14:22:48 +11:00
Andrew Tridgell fe3812c51b GCS_MAVLink: re-worked text send in terms of ObjectArray 2016-02-24 09:18:06 +11:00
Andrew Tridgell 2120913ac2 AP_HAL: added ObjectArray template
this is a ring buffer that supports indexing for efficient handling of
queue peeking and manipulation
2016-02-24 09:18:06 +11:00
Tom Pittenger 9718ee23d1 AP_HAL: fix peekbytes casting 2016-02-24 09:18:06 +11:00
Tom Pittenger 54d2a263fe GCS_MAVLink: create queue scheme for static statustext msgs 2016-02-24 09:18:05 +11:00
Tom Pittenger faa4238370 SITL: fixed warning comparing signed vs unsigned 2016-02-23 10:32:48 -08:00
Andrew Tridgell 7fede90df3 HAL_PX4: work around a bus locking issue on Pixracer
Pixracer has FRAM on the same bus as the ms5611 and the FRAM ramtron
driver does not use the same locking mechanism as other px4 SPI
drivers. We need to disable interrupts during FRAM transfers to ensure
we don't get FRAM corruption
2016-02-23 16:34:06 +11:00
Andrew Tridgell 0a72c2bbd5 AP_Baro: prevent bad ground pressure from making a board unbootable 2016-02-23 16:34:06 +11:00
Andrew Tridgell 1df2512935 AP_HAL: added update() method for object ringbuffer
to support updating objects for GCS work Tom is doing
2016-02-23 16:34:06 +11:00
Tom Pittenger 1d528d552f AP_HAL: rename RingBuffer.force() to RingBuffer.push_force() 2016-02-21 22:13:27 -08:00
Paul Riseborough 7459bfb96b AP_NavEKF2: Eliminate simple compass fusion singularities near +-90 deg pitch
The use of yaw angle fusion during startup and ground operation causes problems with tail-sitter vehicle types.
Instead of observing an Euler yaw angle, we now observe the yaw angle obtained by projecting the measured magnetic field onto the the horizontal plain.
This avoids the singularities associated with the observation of Euler yaw angle.
2016-02-22 16:29:36 +11:00
Andrew Tridgell 4ff396dfa8 AP_HAL: added force() and peek() method for object ringbuffers 2016-02-22 12:34:32 +11:00
Andrew Tridgell 5080201be6 GCS_MAVLINK: added set_dataflash() method 2016-02-22 12:34:32 +11:00
Paul Riseborough 4aefe1caee AP_NavEKF2: Fix sign error in magnetic heading innovation calculation 2016-02-20 08:55:48 +11:00
Tom Pittenger 7e4ae39b8e AP_Arming: fixed GPS_CFG mask bug 2016-02-19 13:53:44 -08:00
Víctor Mayoral Vilches 9bb039accd AP_HAL: PXFmini add HAL_BARO_MS5611_NAME
Peer coded with @LanderU.
2016-02-19 19:17:34 -02:00
Lucas De Marchi 0ccd2de12b AP_AHRS: fix use of undefined macro
../../libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp:63:5: warning: "WITH_GPS" is not defined [-Wundef]
 #if WITH_GPS
     ^

g_gps was not even declared so remove it.
2016-02-19 12:35:20 -02:00
Lucas De Marchi 7d24b4d1ca AP_Notify: add missing include to use board config
<command-line>:0:18: warning: "HAL_BOARD_LINUX" is not defined [-Wundef]
../../libraries/AP_Notify/Buzzer.h:20:5: note: in expansion of macro ‘CONFIG_HAL_BOARD’
 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
     ^
In file included from ../../libraries/AP_Notify/Buzzer.cpp:18:0:
../../libraries/AP_Notify/Buzzer.h:20:25: warning: "HAL_BOARD_VRBRAIN" is not defined [-Wundef]
 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
                         ^
2016-02-19 12:35:20 -02:00
Lucas De Marchi 69f6a73c19 Global: fix missing renames for HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD
Commit b87fd58 (AP_HAL: ERLEBOARD legacy support) renamed the define but
forgot some around.
2016-02-19 12:35:18 -02:00
Peter Barker 475a2040a1 AP_NavEKF2: avoid use of undefined #defines
Ensure EKF_DISABLE_INTERRUPTS is defined

Do not define MATH_CHECK_INDEXES, assume it is defined
2016-02-19 12:34:24 -02:00
Peter Barker 11760c33f6 AP_NavEKF: avoid use of undefined #defines
Ensure EKF_DISABLE_INTERRUPTS is defined

Do not define MATH_CHECK_INDEXES, assume it is defined
2016-02-19 12:34:24 -02:00
Peter Barker 80bc7a50d7 AP_Math: define MATH_CHECK_INDEXES
Wrapped in ifndefs so the top-level Makefile can override

Assume MATH_CHECK_INDEXES is always defined
2016-02-19 12:34:23 -02:00
Lucas De Marchi 3ace8b52de AP_HAL_Linux: use AnalogIn_IIO for minlure 2016-02-19 11:55:31 -02:00
Lucas De Marchi f865e085b1 AP_BattMonitor: add defaults for minlure 2016-02-19 11:55:31 -02:00
Lucas De Marchi 4e034cd2e1 AP_HAL_Linux: AnalogIn_IIO: add scale for minlure 2016-02-19 11:55:31 -02:00
Lucas De Marchi f56a80cd80 AP_HAL_Linux: AnalogIn_IIO: return fixed board voltage
Return board voltage as 5V so we don't fail prearm checks.
2016-02-19 11:55:31 -02:00
Lucas De Marchi d387deb2f5 PID: fix example using wrong type
pid.imax() has type int16_t

../../libraries/PID/examples/pid/pid.cpp:36:53: warning: format ‘%f’ expects argument of type ‘double’, but argument 6 has type ‘int’ [-Wformat=]
             pid.kP(), pid.kI(), pid.kD(), pid.imax());
                                                     ^
2016-02-19 11:51:49 -02:00
Lucas De Marchi edd3e3c34a Filter: silence warning about unused function
../../libraries/Filter/examples/Derivative/Derivative.cpp:16:14: warning: ‘float noise()’ defined but not used [-Wunused-function]
 static float noise(void)
              ^
2016-02-19 11:51:49 -02:00
Lucas De Marchi 1f072c4353 AP_HAL: fix unused variable
../../libraries/AP_HAL/examples/UART_test/UART_test.cpp:13:28: warning: ‘uarts’ defined but not used [-Wunused-variable]
 static AP_HAL::UARTDriver* uarts[] = {
                            ^
2016-02-19 11:51:49 -02:00
Jonathan Challinger c454631be8 AP_InertialSensor: work around gyro and accel errors on startup 2016-02-19 16:40:52 +09:00
Paul Riseborough 047e9fabaf AP_NavEKF2: Fix bug in simple heading fusion
The innovation calculation should have been updated when the heading fusion maths was updated.

We now use a direct heading or yaw angle measurement in the derivation, not the difference between observed and published declination.
2016-02-19 15:35:11 +09:00
Lucas De Marchi bf9cf74c38 StorageManager: replace header guard with pragma once 2016-02-18 14:52:35 -02:00
Lucas De Marchi 98904825cb Filter: replace header guard with pragma once 2016-02-18 14:52:35 -02:00
Lucas De Marchi f5437f30ac AP_Scheduler: replace header guard with pragma once 2016-02-18 14:52:35 -02:00
Lucas De Marchi 008e3c9810 AP_OpticalFlow: replace header guard with pragma once 2016-02-18 14:52:35 -02:00
Lucas De Marchi 09d926fa11 AP_Notify: replace header guard with pragma once 2016-02-18 14:52:35 -02:00
Lucas De Marchi 705393b30c AP_HAL_Linux: replace header guard with pragma once 2016-02-18 14:52:35 -02:00
Lucas De Marchi dbf2aedf1e AP_HAL: replace header guard with pragma once 2016-02-18 14:52:34 -02:00
Lucas De Marchi 2bed317c6c AP_HAL_Empty: replace header guard with pragma once 2016-02-18 14:52:34 -02:00
Lucas De Marchi 1a71c169fe AP_Compass: replace header guard with pragma once 2016-02-18 14:52:34 -02:00
Lucas De Marchi 246f940d01 AP_Buffer: replace header guard with pragma once 2016-02-18 14:52:34 -02:00
Lucas De Marchi 62f50aede7 AP_BattMonitor: replace header guard with pragma once 2016-02-18 14:52:34 -02:00
Lucas De Marchi 6623246cf5 AP_ADC: replace header guard with pragma once 2016-02-18 14:52:34 -02:00
Leonard Hall 49a4bde5d9 AC_AttControl: lower minimum accelerations for large copters 2016-02-18 20:49:13 +09:00
mirkix 8da58226ae AP_HAL_Linux: Fix BBBmini IIO scaling 2016-02-18 00:00:07 -02:00
mirkix d868fe4eff AP_HAL: Remove unused GPIO leds for BBBmini 2016-02-17 23:41:24 -02:00
Paul Riseborough d3c9a0aef1 AP_NavEKF: Limit heading innovations after the consistency check 2016-02-18 08:53:47 +09:00
Paul Riseborough 6a34e4c384 AP_NavEKF2: Fix bug in magnetic heading and declination fusion equations.
The derivation incorrectly used a tan instead of an atan function. This applies the corrected auto-code.
2016-02-18 08:53:45 +09:00
Paul Riseborough 59bf29198d AP_NavEKF2: Remove unnecessary logic preventing constant position
This removes a legacy design concept that is no longer required in this filter implementation. Planes will not be armed without EKF aiding and the proposed copter throw mode also requires EKF aiding to be operating.
The other problem with interrupting fusion during the launch is it doesn't reduce the corrections, it just delays them as wen the launch completes, the EKF inertial position estimate is still moving still moved and the corrections are therefore just delayed by the short launch interval.

Thank you to OXINARF for picking up the inconsistency with the previous logic
2016-02-18 08:53:43 +09:00
Paul Riseborough 7e05646316 AP_NavEKF2: Improvements to non-GPS performance
Change to user adjustable fusion of constant position (as per legacy EKF) instead of constant velocity.
Enable user to specify use of 3-axis magnetometer fusion when operating without aiding.
Don't allow gyro scale factor learning without external aiding data as it can be unreliable
2016-02-18 08:53:41 +09:00
Tom Pittenger a9c985bfb3 AP-Mount: compiler warning
ardupilot/libraries/AP_Mount/SoloGimbal_Parameters.cpp:193:107: warning: comparing floating point with == or != is unsafe [-Wfloat-equal]
2016-02-17 14:54:31 -08:00
Lucas De Marchi 10abec277d AP_HAL: functor: use std::remove_reference 2016-02-16 19:49:09 -02:00
Lucas De Marchi d80a0e47bc AP_Common: missing: move definitions to standard headers
This way we don't create problems regarding which header to include: we
just include the normal/c++11 headers and everything works as it should.
2016-02-16 19:49:09 -02:00
Lucas De Marchi 75d58bcfb6 Global: rename HAVE_NULLPTR_T with HAVE_STD_NULLPTR_T
This makes for a more standard name for these overrides.
2016-02-16 19:49:09 -02:00
Andrew Tridgell 29100937bc AP_Common: allow for nullptr_t but not std::move replacement 2016-02-16 19:49:09 -02:00
Andrew Tridgell 52e36908ff AP_Common: fixed std::move() for qurt build
Thanks Lucas!
2016-02-16 19:49:09 -02:00
Lucas De Marchi cc4504e613 AP_Airspeed: fix coding style
- replace tabs with spaces
  - remove C-style void from function arguments
  - use pragma once
  - fix pointer alignement
  - remove unused header: AP_Airspeed_I2C_PX4 - we actually use
    AP_Airspeed_PX4
2016-02-16 19:49:09 -02:00
Lucas De Marchi 02a7fa5c2b AP_InertialSensor: MPU9250: use AP_HAL::Device abstraction
This makes MPU9250 be almost the same as MPU6000 driver. Work has been
done here to make than similar so it's easier to spot the differences.
2016-02-16 19:49:09 -02:00
Lucas De Marchi d2b267d026 AP_InertialSensor: LSM9DS0: use AP_HAL::SPIDevice abstraction 2016-02-16 19:49:09 -02:00
Lucas De Marchi 58f4624f8c AP_InertialSensor: L3G4200D: use AP_HAL::I2CDevice abstraction 2016-02-16 19:49:09 -02:00
Lucas De Marchi af846636e4 AP_InertialSensor: MPU60x0: use AP_HAL::Device abstraction 2016-02-16 19:49:09 -02:00
Lucas De Marchi f1ade970a3 AP_Baro: MS5611: Use AP_HAL::Device abstraction
This allows to share almost all the I2C/SPI code and remove the
AP_Serial abstraction since that is now handled by AP_HAL itself.
2016-02-16 19:49:09 -02:00
Lucas De Marchi b05954660a AP_Baro: BMP085: use I2CDevice interface 2016-02-16 19:49:09 -02:00
Lucas De Marchi 3060c3da3c AP_HAL_Linux: Add fake device to SPIDriver
This allows us to re-use SPIDevice from SPIDeviceDriver (the
to-become-SPIDeviceProperties) while the drivers are
converted.  We create a fake device by calling the temporary
SPIDeviceManager::get_device() method passing the descriptor. The
transfer and assert logic is still using the old code.

Now we can interoperate SPIDeviceDriver with the ones based in
SPIDevice since they are going to use the same semaphore and bus.
2016-02-16 19:49:09 -02:00
Lucas De Marchi 61ef653181 AP_HAL_Linux: implement SPIDevice
The way this code is structured is a little bit different from the
SPIDriver implementation:

 - We only open the bus once, no matter how many devices we have in it

 - There's a single transfer() method which uses half-duplex mode
   instead of full duplex. The reason is that for all cases in the
   codebase we are using half-duplex transfers using the full-duplex
   API, i.e. a single SPI msg with both tx and rx buffers. This is
   cumbersome because the buffers need to be of the same size and the
   receive buffer using an offset of the same length as the actux data
   being written. This means the high level APIs need to copy buffers
   around.

   If later we have uses for a real full duplex case it's just a matter
   of adding another transfer_fullduplex() method or something like
   this.

 - The methods are implemented in the SPIDevice class instead of having
   proxy methods to SPIDeviceManager as is the case of SPIDriver

Also from now on we refer to the SPIDriver objects as "descriptors"
because they have the parameters of each device in the
SPIDeviceManager::devices[] table. When SPIDeviceDriver is completely
replaced we can rename them to SPIDeviceProperties.
2016-02-16 19:49:09 -02:00
Lucas De Marchi 0d1bb7aa84 AP_HAL_Linux: export number of SPI devices
Save in the manager the number of devices so it can be used in other
places like the SPIDevice implementation. This is a temporary storage
while we migrate to SPIDevice.

While at it use protected rather than private.
2016-02-16 19:49:09 -02:00
Lucas De Marchi cb40444bf8 AP_HAL_Empty: implement SPIDevice 2016-02-16 19:49:09 -02:00
Lucas De Marchi 66f644c50d AP_HAL: add interface for SPIDevice devices
In order to interoperate with SPIDeviceDriver this is re-using the same
SPIDeviceManager interface.
2016-02-16 19:49:09 -02:00
Andrew Tridgell 30ce8ad311 HAL_QURT: fixed for addition of i2c manager 2016-02-16 19:49:09 -02:00
Lucas De Marchi 00249dc8bb AP_HAL_VRBRAIN: use empty I2CDevice 2016-02-16 19:49:09 -02:00
Lucas De Marchi 8de329fc81 AP_HAL_PX4: use empty I2CDevice 2016-02-16 19:49:09 -02:00
Lucas De Marchi c3d8ba3ea5 AP_HAL_SITL: use empty I2CDevice 2016-02-16 19:49:09 -02:00
Lucas De Marchi f22f4928dc AP_HAL_FLYMAPLE: fix constructor after I2CDevice 2016-02-16 19:49:09 -02:00
Lucas De Marchi e40785b002 AP_HAL_Linux: Add fake device to I2CDriver
This allows us to re-use I2CDevice from I2CDriver while the drivers are
converted.  We create a fake device with addr = 0 for each I2CDriver but
we only use the register/unregister logic. The transfer logic still uses
the methods from I2CDriver in order to use the right address.

Now we can interoperate I2CDevice drivers with the ones base in
I2CDriver since they are going to use the same semaphore and bus.

The I2CDriver constructors were changed to re-use the logic in I2CDevice
(it uses a number rather than an string) and the semaphore doesn't live
outside anymore, its embedded in the fake I2CDevice, as well as the
bus's file descritor.
2016-02-16 19:49:09 -02:00
Lucas De Marchi 5194f7e5ce AP_HAL_Linux: I2CDevice: method to read multiple times 2016-02-16 19:49:09 -02:00
Lucas De Marchi c394de31a0 AP_HAL_Linux: register I2CManager instance 2016-02-16 19:49:09 -02:00
Lucas De Marchi bc2f7f2783 AP_HAL_Linux: implement function to transfer data
This is a similar function to what we have in I2CDriver, but it can
receive a nullptr to recv or send.  It will create 2 i2c_msg structs to
send and receive data to/from the I2C slave.
2016-02-16 19:49:08 -02:00
Lucas De Marchi 2fc534d18d AP_HAL_Linux: implement methods to open the bus
These are very similar to their counterparts in I2CDriver. The changes
were:
    - Don't use fixed buffer with PATH_MAX length: allocate the string
    - Change the interface to use std::vector so we can simplify the
      implementation
2016-02-16 19:49:08 -02:00
Lucas De Marchi cd0e1dff82 AP_HAL_Linux: Add skeleton for I2CDevice
This adds the logic to maintain the I2CDevice's managed by I2CManager.
2016-02-16 19:49:08 -02:00
Lucas De Marchi a117c22c34 AP_HAL_Empty: add I2CDevice 2016-02-16 19:49:08 -02:00
Lucas De Marchi 2250d9d768 AP_HAL: initialize I2C manager
Add I2CManager to AP_HAL's contructor.
2016-02-16 19:49:08 -02:00
Lucas De Marchi f8e6c5b379 AP_HAL: add helper method to read registers
This just forwards to the transfer() method, avoiding the need in driver
code to have a similar method.
2016-02-16 19:49:08 -02:00
Lucas De Marchi b4ff2d7595 AP_HAL: add helper method to write register
This just forwards to the transfer() method, avoiding the need in driver
code to have a similar method.
2016-02-16 19:49:08 -02:00
Lucas De Marchi 872b255384 AP_HAL: Add interface for I2CDevice
This is a new interface to replace I2CDriver in future, when all drivers
are converted.
2016-02-16 19:49:08 -02:00
Lucas De Marchi 0eb450d379 AP_HAL: Add interface for I2C/SPI devices
These interfaces are intended to abstract I2C and SPI devices for
drivers.
2016-02-16 19:49:08 -02:00
Lucas De Marchi 2e60e1b1f2 AP_HAL: utility: Add OwnPtr implementation
This is very similar to std::unique_ptr, but doesn't require including
the <memory> header which pulls lots of c++ headers and cause problems
with nuttx headers. It's header-only. It contains an explanation on what
it solves, how to use and unit tests.
2016-02-16 19:49:08 -02:00
Lucas De Marchi e1ae79688d AP_Common: add directory to add missing C/C++ symbols
Add a cstddef header to allow using std::nullptr_t with those toolchains
that don't provide it. The idea is to make these platforms to use our
wrapper header (see https://gcc.gnu.org/onlinedocs/cpp/Wrapper-Headers.html)
and then we add the missing bits to the header.
2016-02-16 19:49:08 -02:00
Julien Beraud c2db6bfb9d AP_Param: Fix warning
Cast to the original type to use get function.
Still a hack but better than casting a pointer to an object which
memory mapping we are not supposed to know
2016-02-15 15:48:35 -02:00
Tom Pittenger 786d14cd3c AP_RangeFinder: For LightWareSerial, write 'd' to support more devices 2016-02-14 16:05:50 -08:00
Andrew Tridgell b76aff2dcb AP_Arming: allow unconfigured GPS in SITL arming checks
the SITL GPS does not implement the needed protocol negotiation
2016-02-15 07:49:19 +11:00
Lucas De Marchi 7debd14683 AP_HAL_Linux: Scheduler: remove unused _in_io_proc 2016-02-12 23:42:34 -02:00
Lucas De Marchi fbb3bb2fd0 AP_HAL_Linux: Scheduler: remove unused _timer_event_missed 2016-02-12 23:42:34 -02:00
Lucas De Marchi f39a6745d1 Global: remove unused _timer_pending from scheduler 2016-02-12 23:42:34 -02:00
Lucas De Marchi 0ad436c337 AP_HAL_Linux: Scheduler: bring back scheduler table
Use a scheduler table to list threads' properties in a single place.
2016-02-12 23:42:34 -02:00
Lucas De Marchi a1b62b4984 AP_HAL_Linux: Scheduler: use PeriodicThread
Some tasks were not accounting for the time to execute the tasks. Now
that we are using the infra from PeriodicThread all of them are.
2016-02-12 23:42:34 -02:00
Lucas De Marchi 48e81c8589 AP_HAL_Linux: Thread: add PeriodicThread helper
This is a helper class to run a single periodic function like the ones
used in the scheduler.
2016-02-12 23:42:34 -02:00
Lucas De Marchi 860d5aaf84 AP_HAL_Linux: Scheduler: move rpcmem initialization to setup phase
This was the only piece remaining in the timer thread that was used only
to setup the thread.
2016-02-12 23:42:34 -02:00
Lucas De Marchi 0282ebb8ff AP_HAL_Linux: add method to check caller same as thread 2016-02-12 23:42:34 -02:00
Lucas De Marchi e3beef0f77 AP_HAL_Linux: Scheduler: remove unused parameter 2016-02-12 23:42:34 -02:00
Lucas De Marchi 2b61eaf9f2 Global: remove {begin,end}_atomic from scheduler
These are never used and largely not implemented.
2016-02-12 23:42:34 -02:00
Lucas De Marchi 9aa49cda93 Global: remove system_initializing() from scheduler
This is not used anymore.
2016-02-12 23:42:34 -02:00