Randy Mackay
b92c4097d2
AC_WPNav: first implementation
2013-04-14 10:34:47 +09:00
Andrew Tridgell
76e20150e9
AP_InertialSensor: ensure parent class is initialised in instance classes
2013-04-12 14:30:35 +10:00
Andrew Tridgell
a5c3051929
AP_GPS: fixed initialisation error in uBlox driver
...
found with valgrind
2013-04-12 14:25:46 +10:00
Andrew Tridgell
dca597cda1
L1_Control: added a comment on speed of the L1 control code
2013-04-12 12:58:20 +10:00
Brandon Jones
a3c2851120
AP_L1_Control: Addition of library for geometry calculations required for L1 Control.
...
1) Explicit control of tracking loop period and damping which removes previous
variation in period with speed and fixed damping ratio
2) Explicit control of track capture angle (now set to 45 degrees by default)
3) Removal of restriction on loiter radius being greater than L1 distance
The circle(loiter) control is a L1 and PD hybrid utilising L1 for waypoint capture and PD control for circle tracking.
Pair-Programmed-With: Paul Riseborough <p_riseborough@live.com.au>
Pair-Programmed-With: Andrew Tridgell <tridge@samba.org>
2013-04-12 12:48:09 +10:00
priseborough
b63d0969b7
AP_AHRS: Addition of a first order complementary filter to AP_AHRS::groundspeed_vector
...
Addition of a complementary filter to estimation of the ground velocity vector for use by the L1-nav
2013-04-12 12:48:09 +10:00
Andrew Tridgell
05ecb8d8fa
AP_AHRS: fixed functions that need to be virtual
...
functions overridden in a child class need to be marked virtual, or
you get the parent class function
2013-04-12 12:48:08 +10:00
Andrew Tridgell
ee81b0f729
AP_AHRS: added wind_correct_bearing() and groundspeed_vector()
...
these are very useful for navigation libraries
2013-04-12 12:48:08 +10:00
Andrew Tridgell
43c3c60de2
AP_Math: moved a lot of vector templates to cpp from .h
...
this reduces the code size quite a lot on AVR
2013-04-12 12:48:08 +10:00
Andrew Tridgell
78eb12a4ac
AP_Math: added RadiansToCentiDegrees and RADIUS_OF_EARTH
2013-04-12 12:48:08 +10:00
Andrew Tridgell
8b119934ea
AP_Math: fixed grammar error
2013-04-12 12:48:08 +10:00
Andrew Tridgell
2d29a6a7be
AP_Math: added Vector2f.angle()
...
useful for calculating the vector in polar coordinates
2013-04-12 12:48:08 +10:00
Andrew Tridgell
f6aacdc768
AP_Navigation: added a navigation controller class
...
the new L1 controller will be a instance of this class. Other
navigation controllers can be added as additional instances
Pair-Programmed-With: Paul Riseborough <p_riseborough@live.com.au>
2013-04-12 12:48:08 +10:00
Randy Mackay
cdb532a594
Copter: bug fix for loiter target
2013-04-11 18:24:20 +09:00
Randy Mackay
86fe79a662
INS: updated MPU6K_FILTER parameter description
2013-04-10 00:14:53 +09:00
tobias
217b8d7a59
cleanup: use const for struct Location pointers and references
...
this allows the compiler to generate more efficient code
2013-04-09 12:10:32 +10:00
Stange Szilard
6516bffbb6
AP_Camera: enable relay off in all builds
2013-04-09 11:38:30 +10:00
Andrew Tridgell
8d992ae615
InertialSensor: added OilPan INS example
2013-04-08 07:07:25 +10:00
Randy Mackay
af13f6795c
INS: switch to global definition of GRAVITY_MSS
...
saves 4 bytes of RAM
2013-04-05 22:57:46 +09:00
Randy Mackay
777c6a308e
AP_InertialNav: use shared GRAVITY_MSS constant
2013-04-05 11:48:41 +09:00
foobarbecue
c07702f46d
Update AP_MotorsOctaQuad.cpp
...
There were two "4"s in the motor test order values. Presumably a typo.
2013-04-05 11:22:56 +09:00
Randy Mackay
739e3c2b9a
Copter: adjust trapezoidal motor mixing
2013-04-04 21:46:11 +09:00
Randy Mackay
e32cbd827b
Copter: replace quad trapezoid frame with V
...
Also update motor mixing
2013-04-03 22:14:29 +09:00
Randy Mackay
5bf55a9523
OpticalFlow: switch order of sin_yaw, cos_yaw
2013-04-02 15:49:31 +09:00
Andrew Tridgell
5667f5d817
AP_ADC: fixed APM1 HIL_SENSORS Ch6() return
2013-04-02 13:20:08 +11:00
Andrew Tridgell
310a5a6be1
DataFlash: don't try to write if no card inserted
2013-04-02 13:08:38 +11:00
Andrew Tridgell
6123ea2dac
PID: added get_pid_4500()
...
this is a version of get_pid() that returns an int16_t constrained to
-4500 to 4500. This will prevent overflow errors for large PID gains
in ArduPlane and Rover
2013-04-01 22:17:04 +11:00
Randy Mackay
6816c45c39
InertialNav: reduce Z-axis time constant to 5
2013-04-01 11:51:12 +09:00
Michael Oborne
541fa13291
cleanup comments
2013-03-31 17:14:54 +08:00
Michael Oborne
2160bf135d
fix sitl segfault in hil
2013-03-31 16:39:15 +08:00
Michael Oborne
87292e0a4a
Init hil accel with gravity
2013-03-31 16:38:48 +08:00
Randy Mackay
39ba406957
Copter: add trapezoid frame type
...
We still need to properly define the motor mixing for the trapezoid
frame in AP_MotorsQuad.cpp
2013-03-31 12:41:02 +09:00
Andrew Tridgell
a093926b04
Revert "RC_Channel: removed pwm_out variable from RC_Channel"
...
This reverts commit 8e4a003d8d
.
It is used by MotorsMatrix
2013-03-29 22:36:29 +11:00
Andrew Tridgell
8e4a003d8d
RC_Channel: removed pwm_out variable from RC_Channel
...
saves 16 bytes
2013-03-29 19:32:52 +11:00
Andrew Tridgell
896fd52aa1
AP_AHRS: fixed functions that need to be virtual
...
functions overridden in a child class need to be marked virtual, or
you get the parent class function
2013-03-29 18:35:10 +11:00
Andrew Tridgell
8459da202c
AP_AHRS: prevents compass flyaways for plane and rover
...
this switches to the GPS for yaw if the compass has dragged us off by
more than 45 degrees from the GPS heading, and the wind speed is less
than 80% of the ground speed.
2013-03-29 13:48:25 +11:00
Andrew Tridgell
091b474a1d
AP_Math: added wrap_360_cd() and wrap_180_cd()
...
moved from per-vehicle code
2013-03-29 13:13:37 +11:00
Andrew Tridgell
0ffc7dab6b
SITL: added GPS speed down to SITL state
2013-03-28 10:29:12 +11:00
Randy Mackay
93f7e61b66
UBLOX GPS: fix MSG_SOL typo
...
"status" was used instead of "solution"
2013-03-27 11:42:05 +09:00
Randy Mackay
27309a553f
GPS: fixes after review
...
Ensure 3D fix before returning velocity_down
UBLOX: restore check of fix_status as part of determining 2D or 3D fix
SIRF: add missing brackets on fix type check
2013-03-27 11:41:54 +09:00
Randy Mackay
24044dc0c4
AHRS: add support for GPS fix type 2D
2013-03-27 11:41:43 +09:00
Randy Mackay
d7454bb09e
GPS: add 2D fix type
2013-03-27 11:41:39 +09:00
Andrew Tridgell
eb6c66af7e
AP_HAL: added gpio->analogPinToDigitalPin() API
2013-03-22 12:31:14 +11:00
Andrew Tridgell
a6b21443c4
HAL_AVR: fixed null termination of vsnprintf()
2013-03-22 11:53:24 +11:00
Andrew Tridgell
91bbf914f7
RangeFinder: added SONAR_ENABLE boolean to analog sonar object
2013-03-22 07:52:51 +11:00
Andrew Tridgell
7e58bde826
GCS_MAVLink: added comm_is_idle() function
...
this will make CLI detection more reliable
2013-03-21 21:55:12 +11:00
Andrew Tridgell
6ddb99a50b
HAL_PX4: create APM/boot.log on SD card
...
useful for debugging
2013-03-21 15:05:21 +11:00
Andrew Tridgell
cc932973d6
HAL_PX4: remove the need for the fmu_only flag file
2013-03-21 15:05:21 +11:00
Andrew Tridgell
3f6eb87f23
AP_GPS: fixed uBlox Debug() macro
2013-03-20 15:42:07 +11:00
Andrew Tridgell
8766e86091
HAL_PX4: fixed blocking bulk writes to UARTs
...
this fixes a problem with uBlox initialisation on PX4
2013-03-20 15:41:52 +11:00
Andrew Tridgell
14911eff6c
HAL_PX4: added a (disabled) trick for handling blocking ttyACM0
...
this doesn't work yet, but is worth having for debugging
2013-03-20 11:20:43 +11:00
Randy Mackay
38e81adae0
InertialNav: remove unnecessary "virtual" from function definitions
...
This saves about 30bytes of RAM
2013-03-19 17:51:16 +09:00
Andrew Tridgell
93fc9c48e5
HAL_PX4: fixed startup bug in fmu_only mode
2013-03-19 07:57:13 +11:00
Christopher Hrabia
744f610409
RangeFinder_I2C: fixed bug with interchanged min max values
...
- add usage of mode-filter and min-max constrain, similar to MaxsonarXL
2013-03-18 14:28:31 +09:00
Christopher Hrabia
9760cdf2d7
Compass: corrected space
2013-03-18 14:27:49 +09:00
Andrew Tridgell
ba8ba36af4
HAL_AVR: fixed build.Examples in autotest
2013-03-18 14:01:21 +11:00
Andrew Tridgell
ac69a531d3
HAL_PX4: workaround problem with APM file on SD card
...
this works around file redirection bug from earlier firmwares
2013-03-18 13:12:17 +11:00
Andrew Tridgell
551950c573
GPS_UBLOX: fixed auto-config of baudrate
...
this fixes the setting of the baudrate on a uBlox that is configured
for 9600. It fixes the NMEA message to have a \r\n, plus sends the
NAV_SOL rate config before the NMEA baudrate config message.
This fixes issue #159
2013-03-17 17:52:48 +11:00
Randy Mackay
c9571ad543
InertialNav: remove 3sec limit on position est after losing GPS
2013-03-16 18:15:59 +09:00
Andrew Tridgell
6a1aad30f1
HAL_PX4: auto-create APM directory on SD card
2013-03-16 19:47:09 +11:00
Andrew Tridgell
7681f3b639
AP_HAL: update AnalogIn example to show voltages not raw values
2013-03-15 08:39:22 +11:00
Andrew Tridgell
c1c967f3bf
DataFlash: fixed test sketch build and run
2013-03-15 07:30:40 +11:00
Andrew Tridgell
a7541e9ad3
DataFlash: report log number when starting a new log
...
helps with test sketch
2013-03-15 07:30:23 +11:00
Andrew Tridgell
ba8d830754
DataFlash: start to fix example build
2013-03-11 13:02:08 +11:00
John Arne Birkeland
9487eb6c1b
Examples: Improved compatibility with Mission Planner serial terminal (CLI)
2013-03-09 15:02:56 +11:00
Andrew Tridgell
26fedc543c
AP_Mount: fixed scaling of the joystick speed to give better control
...
thanks to Chris Miser for reporting this problem
2013-03-08 14:39:32 +11:00
Andrew Tridgell
00e905b025
AP_Airspeed: use new voltage_average() API in Airspeed driver
2013-03-08 10:01:15 +11:00
Andrew Tridgell
bf1944a36d
AP_ADC_AnalogSource: fixed reference scaling for APM1 Ch6 ADC
...
it is not referenced to Vcc
2013-03-08 09:06:40 +11:00
Andrew Tridgell
2fc922a251
AP_Rangefinder: use voltage_average() interface for generic analog rangefinder
2013-03-08 08:27:18 +11:00
Andrew Tridgell
ce46f2f871
AP_ADC: fixed scaling factor for voltage on APM1 Ch6 ADC
2013-03-08 08:26:54 +11:00
Randy Mackay
b8d492b504
Compass: current based compensation added
2013-03-03 23:02:12 +09:00
Andrew Tridgell
16270ccc47
HAL_AVR_SITL: fixed windows build
2013-03-03 22:22:19 +11:00
Andrew Tridgell
3e2cb92c71
AP_ADC_AnalogSource: added voltage_average() interface
2013-03-03 16:16:01 +11:00
Andrew Tridgell
b1c27407a2
AP_HAL: added voltage_average() interface to AnalogIn
...
returns voltage in Volts, using averaged reading over samples.
Where possible this should be auto-scaled against a known reference
voltage
2013-03-03 16:16:01 +11:00
Randy Mackay
e113eb526b
Compass: add get_motor_compensation
...
Remove redundant set_motor_compensation call
2013-03-02 17:53:03 +09:00
Andrew Tridgell
987cdaf3e1
DataFlash: make it safe to do DataFlash logging from timers
...
this uses a non-blocking semaphore take if we are in a timer
process. Useful for logging failsafe events
2013-03-02 17:42:06 +11:00
Randy Mackay
bfb29ce22b
Compass: remove virtual functions to save RAM
2013-03-02 00:07:32 +09:00
Randy Mackay
886725291c
Compass: enable motor compensation for 1280
...
Expand motor compenstion vector's range limit
2013-03-02 00:03:29 +09:00
Randy Mackay
8093c98cd3
Compass: add motor compensation to HIL library
2013-03-02 00:03:24 +09:00
Randy Mackay
d8515ff85e
Compass: basic compensation for motor interference
2013-03-02 00:03:16 +09:00
John Arne Birkeland
fc566096de
AVR HAL: RCJitterTest example
...
Used to test jitter on the PPM R/C input system.
2013-03-01 23:38:30 +09:00
Randy Mackay
318a831b57
INS: set default filter to 20hz for APM2.x and PX4
2013-03-01 19:35:34 +09:00
Andrew Tridgell
cbdeb20dad
MAVLink: rebuilt with new RANGEFINDER message
2013-03-01 12:01:31 +11:00
Andrew Tridgell
44768c911f
MAVLink: added RANGEFINDER message
2013-03-01 11:59:40 +11:00
Andrew Tridgell
8ed2f7d21c
AnalogIn: run the example sketch a bit slower
...
5Hz is plenty
2013-03-01 11:19:26 +11:00
Andrew Tridgell
e4fb54fcc9
RangeFinder: added new AP_RangeFinder_analog
...
this is a generic analog rangefinder, supporting 3 types of functions
between voltage and distance.
2013-03-01 11:19:02 +11:00
Andrew Tridgell
efd2da3eb8
DataFlash: started on file interface
2013-03-01 07:18:26 +11:00
Andrew Tridgell
7b524d15fa
DataFlash: added log_num to dump interface
...
this will be used by the file oriented logging code
2013-03-01 07:18:25 +11:00
Andrew Tridgell
c52ef80f06
DataFlash: added Block layer in classes
...
this will allow the addition of a DataFlash_File implementation of the
DataFlash API which will store logs in a traditional filesystem. That
will align better with the PX4 design, and be more useful for fast
transfer of logs to a host computer
2013-03-01 07:18:25 +11:00
Andrew Tridgell
0ffcffa81c
DataFlash: fixed signed/unsigned errors in API
2013-03-01 07:18:25 +11:00
Andrew Tridgell
9b551f162c
DataFlash: make the public interface much narrower
...
make many variables private, to simplify interface ready for PX4
2013-03-01 07:18:25 +11:00
Andrew Tridgell
5a55fd9a2f
AP_HAL: added HAL_BOARD_NAME define
2013-03-01 07:18:25 +11:00
Andrew Tridgell
20825cc903
DataFlash: removed the byte and word based interfaces
...
simplifing ready for PX4 flash logging
2013-03-01 07:18:25 +11:00
Pat Hickey
e0457f21de
AP_HAL_PX4: fix off-by-one error in RCOutput channel sending
2013-02-23 15:04:17 -08:00
Andrew Tridgell
a3ef58ac92
AP_HAL: moved AnalogIn example to generic examples
...
it is not AVR specific anymore
2013-02-22 12:50:47 +11:00
Andrew Tridgell
5b92c67286
HAL_AVR: fixed analog input with high channel numbers
2013-02-22 12:48:54 +11:00
Andrew Tridgell
fae396e64f
HAL_AVR: expand analog input test to more channels
2013-02-22 12:48:29 +11:00
Andrew Tridgell
c373429a6e
HAL_PX4: fixed a buffer handling bug
...
BUF_SPACE() was badly buggy, which could lead to memory corruption
2013-02-20 18:15:56 +11:00
Andrew Tridgell
160e5fa311
HAL_PX4: show a message if we fail to upgrade PX4IO firmware
2013-02-20 18:15:23 +11:00
Andrew Tridgell
f67480fa50
AP_GPS: ensure constructors zero all key variables
...
this prevents a crash on PX4 if a GPS is attached after startup
2013-02-20 11:33:39 +11:00
Andrew Tridgell
93ef403529
AP_GPS: removed unused AP_GPS_Shim.h
2013-02-20 11:33:39 +11:00
Andrew Tridgell
02c5c3ec4a
HAL_PX4: changed scheduler priorities
...
put sensor priority above main sketch, to prevent occasional blocking
for sensor data
2013-02-20 11:30:54 +11:00
Randy Mackay
963231a19b
AHRS: fix example sketch to use roll/pitch trim
2013-02-19 18:56:09 +09:00
Randy Mackay
3321db8dde
AHRS: limit trim to 10 degrees
2013-02-19 18:50:57 +09:00
Randy Mackay
21de9f5f47
AP_InertialSensor: return roll and pitch trim angles
2013-02-19 12:45:44 +09:00
Andrew Tridgell
54e7bce75e
HAL_PX4: cope with O_NONBLOCK not working in NuttX on ttyACM0
...
writes will block anyway, which clags up APM
2013-02-19 12:02:46 +11:00
Andrew Tridgell
8041768c67
HAL_PX4: perform automatic update of px4io firmware
2013-02-18 13:55:58 +11:00
Andrew Tridgell
8e2a20bea8
HAL_PX4: enable ttyACM0 as main console, ttyS1 as telemetry port
2013-02-18 13:55:33 +11:00
Andrew Tridgell
727f8ff029
AP_GPS: removed the old MTK16 driver
...
the MTK19 driver supports both the 1.6 and 1.9 protocol
2013-02-16 22:03:53 +11:00
Andrew Tridgell
fb4e68f0f0
SITL: added SIM_GPS_BYTELOSS option
...
this allows testing of protocol recovery after losing bytes on the GPS
serial link
2013-02-16 22:00:16 +11:00
Andrew Tridgell
3a582663fb
SITL: improve time field handling in simulated GPS
2013-02-16 21:36:06 +11:00
Andrew Tridgell
428966160a
SITL: added support for MTK16 and MTK19 simulated GPS types
2013-02-16 20:59:48 +11:00
Andrew Tridgell
10cd466035
SITL: added simulation of the original MTK GPS
2013-02-16 20:16:13 +11:00
Andrew Tridgell
2ec2c58f67
SITL: added SIM_GPS_TYPE control
...
for choosing what sort of GPS to simulate
2013-02-16 20:15:57 +11:00
Andrew Tridgell
a63275d284
AP_InertialSensor: expand register range in MPU6000 _dump_registers()
2013-02-13 19:33:40 +11:00
Andrew Tridgell
fe964fcda0
PID: change to float input/output
...
this makes the PID library a bit more flexible for smaller range
numbers. Note that this library is used on ArduPlane and Rover, not
Copter
2013-02-09 20:36:26 +11:00
Andrew Tridgell
e45b137816
HAL_PX4: added run_debug_shell() implementation for PX4
2013-02-07 15:04:33 +11:00
Andrew Tridgell
70f7cde9b8
AP_HAL: added run_debug_shell() hal.util method
2013-02-07 15:04:33 +11:00
zlite
4800c57fb4
Fixed cosmetic typo in user display message
...
Corrected "it's" to "its". Just one of those grammar things that drives me crazy ;-)
2013-02-06 16:34:33 -08:00
Andrew Tridgell
1121254606
AP_InertialSensor: added filter frequency support to PX4 driver
2013-02-07 11:20:45 +11:00
Andrew Tridgell
5643c371b9
AP_InertialSensor: removed unused new_data_available() and temperature() APIs
2013-02-07 10:23:37 +11:00
Andrew Tridgell
7b1245937c
AP_InertialSensor: always sample at 200Hz in MPU6000
...
this changes the sampling to 200Hz regardless of requested rate, and
it is downsampled inside num_samples_available() using a shift. This
gives better noise resistance in ArduPlane.
This patch also makes it possible to update the filter frequency while
running, which is very useful for bench testing with a vibration
source
2013-02-07 10:23:08 +11:00
Jochen Tuchbreiter
c5f19f5df8
Plane: Implement issue 80: counterclockwise loiter
...
- libraries/AP_Common/AP_Common.h: Use bit 2 of Location.options to store
loiter direction
- ArduPlane/defines.h: New bitmask MASK_OPTIONS_LOITER_DIRECTION for struct
Location bit 2
- ArduPlane/ArduPlane.pde: New variable loiter_direction
- ArduPlane/GCS_Mavlink.pde: For mavlink loiter-commands use sign of param3 to
detemine direction. Set Location.option flag accordingly
- ArduPlane/commands.pde: Make sure loiter-directions get saved into EEPROM
correctly
- ArduPlane/commands_logic.pde: Set loiter_direction on all loiter-actions
as well as RTL/instant loiter
- ArduPlane/navigation.pde: Yield loiter_direction in update_loiter
2013-02-05 10:29:31 +11:00
Michael
5d91b06de3
RC_Channel: added secondary elevator support
2013-02-05 08:57:28 +11:00
Andrew Tridgell
db8da71f65
Revert "AP_HAL_AVR: Improved AVRTimer micros() and millis()"
...
This reverts commit 527dcdf3b9
.
This was causing the MPU6000 startup code to fail, due to time running
backwards.
2013-02-03 21:32:22 +11:00
John Arne Birkeland
527dcdf3b9
AP_HAL_AVR: Improved AVRTimer micros() and millis()
...
- More efficient code by using 16-bit timer
- micros() now has proper 1 us resolution and less overhead
- millis() has less overhead
- removed unneeded/unwanted initializatin of timers in AVRTimer::init()
pull request 62, approved and merged by pat
2013-02-01 09:32:40 -08:00
Randy Mackay
7729ec950e
AP_Math: longitude_scale function made public
...
Added LATLON_TO_M and LATLON_TO_CM #defines
2013-01-27 23:21:39 +09:00
Andrew Tridgell
4fd7630ec9
HAL_PX4: IO_SET_FEATURES is not needed any more
2013-01-27 15:05:28 +11:00
Andrew Tridgell
8375abdd99
HAL_PX4: fixed max storage write size
2013-01-27 15:04:47 +11:00
Andrew Tridgell
e4a204d2f6
HAL_PX4: reopen storage file on any IO error
2013-01-27 13:39:11 +11:00
Randy Mackay
6f5050a8b9
Copter: minor casting fixup for wp_distance
2013-01-27 11:27:43 +09:00
Randy Mackay
bad81a5113
AP_InertialSensor_MPU6k: remove unnecessary check of sign when receiving fifo packet from dmp
2013-01-27 11:22:39 +09:00
Andrew Tridgell
90e264d56a
HAL_PX4: disable manual override in PX4 for now
2013-01-27 12:52:14 +11:00
Andrew Tridgell
02b4ecc273
HAL_PX4: get RC input from PX4IO board
...
this allows us to support DSM and SBUS receivers
2013-01-27 12:52:14 +11:00
Randy Mackay
d2767b911c
AP_Math: switch get_distance_cm to return uint32_t
...
Includes changes required on ArduCopter and ArduPlane side as well
2013-01-26 17:04:12 +09:00
Andrew Tridgell
d7409b6a25
HAL_PX4: startup in low priority to fix CLI
...
this ensures that tight sensor loops in setup() can run without
sleeping
2013-01-25 20:44:36 +11:00
Andrew Tridgell
7359348e2c
HAL_PX4: added support for /fs/microsd/APM/nostart
...
prevents APM startup
2013-01-25 20:44:36 +11:00
Andrew Tridgell
8f2f4b1bc5
HAL_PX4: use write() to /dev/pwm_output for servo output
...
this lowest the cost of PWM output a lot, but relies on the new I2C
based IO firmware
2013-01-25 20:44:36 +11:00
Andrew Tridgell
9b4c75c66b
RC_Channel: don't change trim if radio in is zero
2013-01-25 20:44:36 +11:00
Andrew Tridgell
f9d43f4c3e
HAL_PX4: prevent loop() overruns using hrt
...
this ensures if loop() takes more than 1 second, the main task gets
its priority dropped until loop() completes
2013-01-24 15:04:57 +11:00
Andrew Tridgell
70227d5d93
HAL_PX4: added scheduler performance counters
2013-01-24 15:04:57 +11:00
Andrew Tridgell
0e79b93289
HAL_PX4: added storage performance counters
2013-01-24 15:04:57 +11:00
Andrew Tridgell
fc8065b50f
HAL_PX4: added UART performance counters
2013-01-24 15:04:57 +11:00
Andrew Tridgell
6cf1d5e1ff
HAL_PX4: handle IO errors on microsd
...
this should handle EINTR gracefully
2013-01-24 15:04:57 +11:00
Randy Mackay
542e2e1358
AP_PerfMon: fixes to make it work under AP_HAL (almost)
2013-01-23 21:22:17 +09:00
Andrew Tridgell
966b9b9b9c
HAL_PX4: format panic messages with a newline
2013-01-23 16:54:44 +11:00
Andrew Tridgell
c9799fb2b7
HAL_PX4: writing more than 512 bytes at a time can cause IO errors
...
the vfat fs in NuttX is really very picky!
2013-01-23 16:54:44 +11:00
Andrew Tridgell
952df2fced
HAL_PX4: new buffered storeage driver for microsd cards
...
this does all IO in the timer thread, avoids writes that don't change
data, and does all writes in multiples of 128 byte chunks. This should
be about as friendly to SD cards as we can get.
2013-01-23 16:37:40 +11:00
Andrew Tridgell
f72b532405
HAL_PX4: ensure all writes go via buffers
...
this prevents output corruption by direct fd writes
2013-01-23 09:22:51 +11:00
Andrew Tridgell
2a10727902
HAL_PX4: run timer thread as SCHED_FIFO
...
this ensures it never yields to the main thread, which would break our
locking assumptions
2013-01-23 09:21:50 +11:00
Andrew Tridgell
930e79a9e1
HAL_PX4: fixed rcin->valid() for RC override input
2013-01-23 07:57:59 +11:00
Andrew Tridgell
06e63d3167
HAL_PX4: use pthread_yield() in main loop
...
this lowers the latency of the main loop somewhat
2013-01-23 07:36:13 +11:00
Andrew Tridgell
6e8501603c
HAL_PX4: avoid RCOutput ioctl unless values change
...
this lowers latency somewhat
2013-01-23 07:29:59 +11:00
Andrew Tridgell
89cb3fbd61
HAL_PX4: fixed blocking IO in UART driver
2013-01-22 21:52:21 +11:00
Andrew Tridgell
6ffa18fa61
HAL_PX4: rewrite UART driver to be much more efficient
...
this does the IO in the timer thread, and uses buffers in the main
task to avoid system call costs in the flight code.
The cost of PX4 read and write system calls is quite high - about 10
to 15 usec. We can't afford to pay that per byte
2013-01-22 21:22:01 +11:00
Andrew Tridgell
37be83994f
SITL: allow motor multiplier to work on quad simulation
2013-01-22 21:22:01 +11:00
Andrew Tridgell
f0469a21f2
AP_Baro: fixed timestamp on baro for PX4
...
milliseconds not microseconds
2013-01-22 21:22:01 +11:00
Andrew Tridgell
80eaa52ed8
AP_Compass: use report timestamp on PX4 for accurate timing
2013-01-22 21:22:01 +11:00
rmackay9
6f1035debc
InertialNav: added 300ms timeout after which error from gps heading will be set to zero
2013-01-22 18:37:54 +09:00
Jonathan Challinger
6565d83e73
InertialNav: Fixed signs, remove body-frame rotation, apply correction at 100hz.
2013-01-22 18:37:45 +09:00
Andrew Tridgell
546ed19ffc
HAL_PX4: improved efficiency of serial writes
...
use buffer at a time writes when possible, and use O_NONBLOCKING to
avoid txspace()
2013-01-22 10:50:26 +11:00
Andrew Tridgell
18cfd29f2f
HAL_PX4: added a read buffer to the UART driver
...
this lowers the average cost of reading bytes by a large amount, and
prevents the GPS driver from chewing lots of time.
2013-01-22 10:34:04 +11:00
Andrew Tridgell
db0bd86317
HAL_PX4: name the eeprom file after the sketch
...
this makes it easier to switch between ArduPlane and ArduCopter
2013-01-21 22:04:17 +11:00
Andrew Tridgell
f60d657f72
AP_InertialSensor: added timer for accumulating samples for PX4
...
this makes the driver much more tolerant of sketch timing errors
2013-01-21 21:51:32 +11:00
Andrew Tridgell
3d0cb755d2
AP_InertialSensor: user a timer to drive data collection on PX4
...
this reduces the chance of missing a sample if the main sketch is a
bit slow
2013-01-21 19:44:01 +11:00
Andrew Tridgell
b9b3ef91a1
AP_Baro: added timer to PX4 driver
...
this gives us more samples when main sketch is reading slowly
2013-01-21 18:20:05 +11:00
Andrew Tridgell
1188c9e335
HAL_PX4: added Util instance
...
this fixes hal.util->vsnprintf_P()
2013-01-21 17:10:42 +11:00
Andrew Tridgell
52f560a4c2
HAL_PX4: enabled AnalogIn driver
2013-01-21 13:56:57 +11:00
Andrew Tridgell
ed94292c25
HAL_PX4: start adc driver in rc.APM
2013-01-21 13:55:58 +11:00
Andrew Tridgell
e42cf918fd
HAL_PX4: added AnalogIn driver
...
this allows airspeed to work on a PX4
2013-01-21 13:55:06 +11:00
Andrew Tridgell
39e28d48c2
HAL_PX4: switched scheduler to use a pthread
...
this allows the timer tasks to access file descriptors in the main APM
task, which makes writing PX4 device drivers much easier
2013-01-21 13:54:09 +11:00
Andrew Tridgell
ffb2924dd4
HAL_PX4: added APM startup script
2013-01-21 08:27:02 +11:00
Andrew Tridgell
6a5421a361
AP_Baro: ask for maximum poll rate for PX4
2013-01-21 08:27:02 +11:00
Andrew Tridgell
74f7b0f218
AP_Baro: added accumulate method to PX4 driver, and fixed scaling
2013-01-20 22:13:21 +11:00
Andrew Tridgell
0655b1a925
HAL_PX4: fixed thread_running on failed startup
2013-01-20 22:13:20 +11:00
Andrew Tridgell
16d72ca160
AP_InertialSensor: update PX4 driver to use read() method
2013-01-20 22:13:20 +11:00
Andrew Tridgell
6119201307
AP_AHRS: ensure compass is non-NULL for set_board_orientation()
2013-01-17 17:23:34 +11:00
Andrew Tridgell
7294d9ef35
AP_Menu: fixed build with older compilers
...
avoids relocation truncated to fit error
2013-01-17 07:26:26 +11:00
Andrew Tridgell
76092eb590
AP_HAL: remove unused peek() interface from UART drivers
...
this is a bit tricky to implement on some platforms, and is unused
anyway
2013-01-16 14:43:18 +11:00
Andrew Tridgell
e852d6300f
AP_HAL_AVR: fixed multi-channel RC output
2013-01-16 14:21:55 +11:00
James Bielman
4fa7bb1486
Add AVR compatibility header for missing math.h definitions.
...
- Define float versions of math functions to the double versions
on AVR (eg. #define sinf sin).
- These macros appear to be missing in older versions of avr-libs.
- Include AP_Math.h rather than math.h to get these definitions.
2013-01-16 13:52:17 +11:00
James Bielman
5631f865b2
Update floating point calculations to use floats instead of doubles.
...
- Allows use of hardware floating point on the Cortex-M4.
- Added "f" suffix to floating point literals.
- Call floating point versions of stdlib math functions.
2013-01-16 13:52:01 +11:00
Andrew Tridgell
d00b06d449
Filter: added a butter filter to example
2013-01-16 09:15:35 +11:00
Andrew Tridgell
befc6b7b9b
Filter: fixed butter filter build on px4
2013-01-16 09:15:22 +11:00
Andrew Tridgell
2ce18f588b
AP_HAL: added AP_HAL_Macros.h
...
this adds a define for constexpr, allowing code to build either with
or without -std=gnu++0x
2013-01-16 09:12:55 +11:00
Pat Hickey
53ea7c564e
Butter filter: needs header guards
2013-01-15 12:47:43 -08:00
Jonathan Challinger
c66571b87d
Filter: added 2nd-order butterworth filters.
2013-01-14 19:18:47 -08:00
Andrew Tridgell
c6b006cf5f
DataFlash: move log reading logic into common library
2013-01-15 14:03:51 +11:00
Andrew Tridgell
bd9c61562f
HAL_PX4: added -d command line option to app
...
allows control of serial device
2013-01-14 16:21:27 +11:00
Andrew Tridgell
64a8a8e4c9
HAL_PX4: fixed using mavlink on the console
...
this disables the ONLCR termios flag, which was injecting extra
carriage returns in the output
2013-01-14 16:21:27 +11:00
Andrew Tridgell
4c4b6afaff
HAL_AVR_SITL: fixed log dump
...
the sockets need to default blocking, and only be non-blocking per
call
fixes issue #9
2013-01-14 08:26:29 +11:00
Andrew Tridgell
4609114a81
HAL_Empty: fixed example build
2013-01-14 07:03:34 +11:00
Andrew Tridgell
a3556c8cf8
HAL_AVR: fixed example build
2013-01-14 07:03:25 +11:00
Andrew Tridgell
d844a1ba3c
AP_InertialSensor: fixed PX4 example build
2013-01-13 21:10:53 +11:00
Andrew Tridgell
98a55bf2a1
AP_Limits: removed old declaration
2013-01-13 20:46:44 +11:00
Randy Mackay
109b1069d8
AP_InertialNav: added constraint to how large local accelerometer offset corrections can become
2013-01-13 19:55:09 +11:00
Andrew Tridgell
f683cff9e2
DataFlash: speed up SPI transfers in DataFlash_APM1
2013-01-13 19:26:43 +11:00
Andrew Tridgell
6bd361b9cd
OpticalFlow: make surface_quality uint8_t
2013-01-13 17:53:54 +11:00
Andrew Tridgell
f644a356c9
AP_AHRS: document more rotation combinations
2013-01-13 17:32:48 +11:00
Andrew Tridgell
38062bbb6d
AP_Math: support some more rotation combinations
2013-01-13 17:32:48 +11:00
Andrew Tridgell
848fc3e32d
AP_AHRS: added AHRS_ORIENTATION parameter
2013-01-13 17:32:48 +11:00
Andrew Tridgell
d7996acdf7
AP_InertialSensor: added set_board_orientation() method
2013-01-13 17:32:48 +11:00
Andrew Tridgell
60a4447a86
AP_Compass: added set_board_orientation() method
2013-01-13 17:32:48 +11:00
Andrew Tridgell
8015f0f626
DataFlash: update SITL implementaion for new API
2013-01-13 17:31:43 +11:00
Andrew Tridgell
9ef1f8509b
DataFlash: update test code for new macros
2013-01-13 17:31:42 +11:00
Andrew Tridgell
83b074dd87
DataFlash: moved macros into common header
2013-01-13 17:31:42 +11:00
Andrew Tridgell
f3005c4267
DataFlash: use bulk SPI transfer() method
...
this reduces the per-byte overhead of flash logging to about 3.9 usec
2013-01-13 17:31:42 +11:00
Andrew Tridgell
a06202e750
HAL_SMACCM: added bulk SPI transfer() method
2013-01-13 17:31:42 +11:00
Andrew Tridgell
3dc0a990a1
HAL_Empty: added bulk SPI transfer() method
2013-01-13 17:31:42 +11:00
Andrew Tridgell
b5b7fd2f9a
HAL_AVR: added bulk transfer() method
...
this is quite a lot faster than the byte at a time method
2013-01-13 17:31:42 +11:00
Andrew Tridgell
6415f00ce3
AP_HAL: added a bulk transfer() method
...
very useful for dataflash
2013-01-13 17:31:42 +11:00
Pat Hickey
af8f576c67
AP_HAL_SMACCM: add LICENSE file
2013-01-12 11:54:19 -08:00
Pat Hickey
3d0a4394b6
DataFlash Empty: conform to blockread/write virtual if
2013-01-12 10:44:05 -08:00
Andrew Tridgell
7274d847f8
DataFlash: update for new block API
2013-01-12 17:21:21 +11:00
Andrew Tridgell
28a0ba6c4a
DataFlash: added block based dataflash writes
...
these are about 10x faster than the old writes
2013-01-12 17:21:04 +11:00
Andrew Tridgell
252d11ccfa
AP_GPS: initialise _step to zero in all drivers
...
new() does not zero-fill memory
2013-01-12 16:04:23 +11:00
Andrew Tridgell
64734dc51c
AP_Scheduler: show scheduler task slips
...
this is when a task doesn't run at the desired rate
2013-01-12 13:04:52 +11:00
Andrew Tridgell
1cb64dacf9
AP_Scheduler: expose debug variable
2013-01-12 12:06:55 +11:00
Andrew Tridgell
7ddadcf34e
AP_Scheduler: added new scheduler library
...
this will be used for main loop control
2013-01-12 12:02:57 +11:00
Andrew Tridgell
30b50a858d
Filter: fixed a warning on PX4
2013-01-11 21:17:34 +11:00
Andrew Tridgell
6142eac4b4
AP_InertialSensor: simplify get_delta_time() API
...
use a single float return rather than two APIs.
This also changes the MPU6k driver to match the new 2.9 behaviour of
using the MPU6k sample timing instead of micros()
2013-01-11 21:17:21 +11:00
Andrew Tridgell
7c7a215934
HAL_PX4: fixes for new Scheduler API
2013-01-11 12:25:26 +11:00
Andrew Tridgell
2fe4656a50
Merge pull request #4 from GaloisInc/master
...
Thanks Pat!
2013-01-10 17:24:59 -08:00
Andrew Tridgell
6aecdb3d7d
HAL_AVR: tweak the default serial buffer sizes
...
this reduces memory fragmentation a lot, saving memory
2013-01-11 11:16:09 +11:00
Andrew Tridgell
0cb8192861
HAL_AVR: ensure we can handle a 256 size buffer
2013-01-11 10:32:52 +11:00
Andrew Tridgell
cf04935438
HAL_AVR: make Console a direct wrapper of uartA
...
this saves a bunch of memory, and we don't really need separate
console support on AVR
2013-01-11 10:23:51 +11:00
Pat Hickey
7b5153c79b
AP_HAL_AVR_SITL: main calls system_initialized
2013-01-10 14:37:22 -08:00
Pat Hickey
4d5d08ad10
AP_HAL_Empty: main calls system_initialized
2013-01-10 14:37:07 -08:00
Pat Hickey
2b621dc579
AP_HAL_AVR: main calls system_initialized
2013-01-10 14:36:53 -08:00
James Bielman
25d078e2bd
AP_Baro_MS5611: Don't panic if taking semaphore fails during init.
...
- The MPU6000 holds on to the I2C semaphore for quite some time during
init, which caused a panic when the MS5611 is also on I2C.
2013-01-10 14:22:41 -08:00
James Bielman
edfddbab57
AP_HAL_SMACCM: Implement new scheduler methods.
...
- Set the system initialized after call to "setup" in main.
2013-01-10 14:22:15 -08:00
Pat Hickey
910e09fc96
AP_InertialSensor_MPU6000: fix sync/async semaphore usage with new scheduler
2013-01-10 14:12:19 -08:00
Pat Hickey
83adb72f16
AP_HAL_Empty: Stub out new Scheduler methods
2013-01-10 14:07:44 -08:00
Pat Hickey
a228519b18
AP_HAL_AVR_SITL: Implement new Scheduler methods
2013-01-10 14:07:43 -08:00
Pat Hickey
930a789b25
AP_HAL_AVR: Implement new scheduler methods
2013-01-10 14:07:43 -08:00
Pat Hickey
7a0f95c11c
AP_HAL: add Scheduler methods in_timerprocess, system_initialize
2013-01-10 14:07:43 -08:00
Pat Hickey
6d64bf2921
AP_HAL_SMACCM: Semaphores fixup
2013-01-10 13:52:30 -08:00
James Bielman
9abf3d2c0f
AP_HAL_SMACCM: Panic if taking a semaphore held by current thread.
...
- Catches bugs with attempted recursive semaphore taking.
2013-01-10 13:16:43 -08:00
Andrew Tridgell
ea3b405959
MAVLink: moved CRC table into program
...
this saves 256 bytes of memory
2013-01-10 21:28:07 +11:00
Andrew Tridgell
f3783b0306
AP_GPS: put SIRF init_messages in progmem
...
this saves 32 bytes of memory
2013-01-10 21:27:41 +11:00
Andrew Tridgell
dbad61816b
AP_InertialSensor: only build Oilpan driver on APM1
2013-01-10 21:01:55 +11:00
Andrew Tridgell
2c603a0960
AP_Baro: only build BMP085 driver on APM1
2013-01-10 21:01:07 +11:00
Andrew Tridgell
63634c4e8a
HAL_SMACCM: fixed build warning
2013-01-10 16:29:46 +11:00
Andrew Tridgell
130aaae168
HAL_AVR: switched to 8 bit mask
...
max buffer size is now 256. This makes serial faster
2013-01-10 16:29:34 +11:00
Andrew Tridgell
03b26c7d6d
AP_Motors: fixed setup of ESC update speeds
2013-01-10 15:52:46 +11:00
Pat Hickey
ea6147162a
AP_HAL_SMACCM: fix to goofed PPM_MAX_CHANNELS macro
2013-01-09 17:24:23 -08:00
Pat Hickey
8f5da03f93
AP_HAL_SMACCM: guard compilation on CONFIG_HAL_BOARD
2013-01-09 13:32:34 -08:00
Pat Hickey
59365f1b90
AP_HAL_AVR: UARTDriver guard needs AP_HAL_Boards.h
2013-01-09 13:32:13 -08:00
Pat Hickey
ab5522a20a
AP_HAL_SMACCM: remove meaningless example dir
2013-01-09 13:15:10 -08:00
James Bielman
0160a10ba7
AP_HAL_SMACCM: Increase scheduler stack sizes.
2013-01-09 11:19:51 -08:00
James Bielman
46b0742710
AP_HAL_SMACCM: Fix pin conflict between uartC and I2C.
...
- uartC is currently disconnected.
- Set uartB to USART6 for GPS communication.
2013-01-09 11:19:51 -08:00
James Bielman
7827a4a54a
ArduCopter: Add AP_HAL_SMACCM support.
...
- Added default configuration to "config.h".
- Added main function to run under FreeRTOS with HWF4.
2013-01-09 11:19:51 -08:00
James Bielman
4e0806186f
AP_HAL_SMACCM: Implement RCInput driver.
2013-01-09 11:19:51 -08:00
James Bielman
8e38ef6567
MPU6000: Flip Y and Z axes for SMACCM_HAL.
...
- The accelerometer is upside-down on the PX4FMU vs the APM2.
2013-01-09 11:19:51 -08:00
James Bielman
1309b7332a
MPU6000: Use signed addition when accumulating readings.
...
- Fixes very erratic accel readings on the PX4 board.
2013-01-09 11:19:51 -08:00
Andrew Tridgell
8cb0ed364a
AP_Baro: read 4 pressure values for every temperature value on BMP085
2013-01-09 23:44:26 +11:00
Andrew Tridgell
1ce1fa3864
AP_Baro: update example to use accumulate()
2013-01-09 23:06:24 +11:00
Andrew Tridgell
8ceabc97f1
AP_Baro: added accumulate() function
...
this allows us to read the BMP085 much faster
2013-01-09 23:05:17 +11:00
Andrew Tridgell
8f424cdf21
AP_Compass: ensure we check we got the semaphore
2013-01-09 20:42:20 +11:00
Andrew Tridgell
e76c77e86a
AP_HAL: mark semaphore take operations as WARN_IF_UNUSED
...
this prevents common bugs
2013-01-09 20:42:02 +11:00
Andrew Tridgell
90523ae975
AP_HAL: added WARN_IF_UNUSED macro
...
useful for key functions
2013-01-09 20:41:37 +11:00
Andrew Tridgell
8e1bee3a5e
HAL_AVR: make _taken volatile
2013-01-09 20:33:37 +11:00
Andrew Tridgell
f48790a56e
AP_InertialSensor: poll for new data in num_samples_available()
...
this lowers the latency for new data
2013-01-09 20:31:09 +11:00
Andrew Tridgell
4ab1cddd15
AP_InertialSensor: ensure we always have the SPI semaphore for MPU6k
2013-01-09 20:30:20 +11:00
Andrew Tridgell
9b972af307
AP_Baro: skip timer if we don't get the SPI semaphore
2013-01-09 20:27:48 +11:00
Andrew Tridgell
dc66708856
MAVLink: cope with available() returning -1
2013-01-09 13:31:00 +11:00
Andrew Tridgell
7be1335b3a
AP_Param: removed copy_name() and add token to find_by_index()
...
this allows callers to avoid another var_info traverse
2013-01-09 13:30:51 +11:00
Andrew Tridgell
c9fe7fe932
MAVLink: use buffer send and fast CRC if possible
2013-01-08 14:37:40 -08:00
Andrew Tridgell
df91734883
MAVLink: import latest upstream messages and headers
2013-01-08 14:37:40 -08:00
Andrew Tridgell
feeebae03f
GCS_MAVLink: added comm_send_buffer()
...
this reduces the overhead of sending messages
2013-01-08 14:37:39 -08:00
Andrew Tridgell
7f20f720e8
HAL_AVR: started I2C in high speed mode
...
this speeds up the compass a lot
2013-01-08 14:37:39 -08:00
Andrew Tridgell
c8ae665ac3
AP_Param: added copy_name_token()
...
this avoids an expensive var_info traversal on every copy_name call
2013-01-08 14:37:39 -08:00
Andrew Tridgell
44285cfbad
DataFlash: fixed a semaphore bug in APM1 dataflash code
2013-01-08 14:37:39 -08:00
Andrew Tridgell
b39166b71a
MPU6000: fixed minor timing bug
...
if we miss a sample due to SPI contention we shouldn't update last
sample time
2013-01-07 11:07:29 +11:00
Andrew Tridgell
f93a7d50eb
AP_GPS: fixed debug code
2013-01-07 11:06:53 +11:00
Andrew Tridgell
5ac23d358f
HAL_PX4: update for new i2cdriver interface
2013-01-07 11:05:30 +11:00
Andrew Tridgell
319e1a4e84
HAL_PX4: support setting servo rate
2013-01-07 11:05:30 +11:00
Pat Hickey
0660873fa7
AP_HAL_AVR: pull-up UART RX lines to fix GPS spoofing (Tridge)
...
Tridge discovered this bugfix:
https://groups.google.com/d/topic/drones-discuss/aek6LJeYQo8/discussion
2013-01-05 21:03:02 -08:00
Pat Hickey
1b7b096b05
AP_Relay: fix pin used on APM2/SITL per Sando on drones-discuss
...
* My bad, thanks for the fix Sandro
2013-01-05 13:51:59 -08:00
Andrew Tridgell
f7e5f88199
AP_GPS: make UBLOX driver a bit more robust
2013-01-05 20:39:31 +11:00
Andrew Tridgell
3b0398dc14
AP_GPS: fixed UBLOX example for PX4
2013-01-05 20:39:30 +11:00
Pat Hickey
dd27984eac
SITL: instansiate EmptyI2CDriver with EmptySemaphore
2013-01-04 16:20:22 -08:00
Pat Hickey
0db60464f7
AP_HAL_Empty: add semaphore to I2CDriver
2013-01-04 16:19:51 -08:00
Pat Hickey
4c31cc0c2b
AP_HAL_AVR: add semaphore to I2CDriver
2013-01-04 16:19:38 -08:00
Pat Hickey
3da864499d
AP_HAL Semaphore: don't use limits, they don't work on c++
2013-01-04 16:19:15 -08:00
James Bielman
bb4474fa6d
AP_HAL_SMAACM: Add timeout for SPI transfers.
...
- Detects lockup in the lower level SPI driver.
- Add scheduler task tags for FreeRTOS debugging.
2013-01-04 15:44:21 -08:00
James Bielman
eca1417858
AP_HAL: Add semaphores to I2C driver.
...
- Guard I2C transactions with this semaphore in the MS5611 and
HMC5843 drivers.
2013-01-04 15:43:43 -08:00
Andrew Tridgell
30447018d5
HAL_PX4: handle %S in format strings
2013-01-05 08:10:07 +11:00
Andrew Tridgell
c16db01395
HAL_SITL: add pragma pack
...
may be needed on some systems
2013-01-05 08:01:30 +11:00
Andrew Tridgell
08d518e07f
HAL_PX4: switch to libc vdprintf()
...
vdprintf has now been added to NuttX
2013-01-05 08:01:10 +11:00
Andrew Tridgell
c15bf95e19
AP_Baro: fixed example build on AVR
2013-01-04 22:45:02 +11:00
Andrew Tridgell
84bd10d279
HAL_PX4: minor cleanups
2013-01-04 22:27:04 +11:00
Andrew Tridgell
aa64a41512
AP_Baro: removed debug line
2013-01-04 22:26:51 +11:00
Andrew Tridgell
5829d44a22
HAL_PX4: disable failsafe handler
...
this won't work until we can set RC output values in timers
2013-01-04 22:26:16 +11:00
Andrew Tridgell
0fcc6d7389
HAL_PX4: added an RC Output driver
2013-01-04 22:25:36 +11:00
Andrew Tridgell
4fe7ad6267
AP_Baro: added averaging to PX4 baro driver
2013-01-04 21:08:20 +11:00
Andrew Tridgell
26bc278181
AP_Compass: use queue length 10 in PX4 driver
...
and remove unnecessary poll() call
2013-01-04 20:12:03 +11:00
Andrew Tridgell
dbcaa4cf3c
AP_Baro: average over multiple samples in PX4 baro driver
2013-01-04 20:11:30 +11:00
Andrew Tridgell
44837a11f2
HAL_PX4: added baudrate support to UART driver
2013-01-04 19:42:30 +11:00
Andrew Tridgell
965fc8a9d1
HAL_PX4: enable uartB as GPS port
2013-01-04 19:41:50 +11:00
Andrew Tridgell
2f111b857b
AP_GPS: ported test code for PX4
2013-01-04 19:41:36 +11:00
Andrew Tridgell
f701d0cc85
AP_GPS: a couple more places where we should restart
...
this prevents us losing a byte
2013-01-04 19:40:49 +11:00
Andrew Tridgell
3bfff4bd6d
AP_GPS: pragma pack is needed on ARM
...
we rely on GPS data structures having byte alignment. Luckily GCC can
cope with this.
2013-01-04 19:39:15 +11:00
Andrew Tridgell
741174f5d5
AP_Compass: first cut at a PX4 compass driver
2013-01-04 16:21:24 +11:00
Andrew Tridgell
2ac6541526
AP_Baro: added PX4 barometer driver
2013-01-04 14:58:24 +11:00
Andrew Tridgell
cf5d102912
AP_Common: added board ID for PX4
2013-01-04 14:26:28 +11:00
Andrew Tridgell
fd23f6bd33
InertialSensor: added PX4 example sketch
2013-01-04 14:26:14 +11:00
Andrew Tridgell
ae09b31176
AP_InertialSensor: added PX4 gyro/accel driver
2013-01-04 14:25:57 +11:00
Andrew Tridgell
9f423a24ad
HAL_PX4: yield CPU in delay()
...
this allows other apps to run
2013-01-04 12:34:35 +11:00
Pat Hickey
bc3b6fcb9f
AP_HAL_AVR_SITL: remove begin/end atomic, adjust timer procs
2013-01-03 17:33:14 -08:00
Pat Hickey
688ec864dc
AP_HAL_AVR: deprecate begin/end atomic, timer procs run on resume
2013-01-03 17:33:14 -08:00
Pat Hickey
ea2a03344e
AP_HAL Scheduler: remove begin_atomic and end_atomic from api
...
* application-level atomic operations can now only be defined in
terms of suspend/resume_timer_procs
2013-01-03 17:33:14 -08:00
James Bielman
8f4a2e4c0e
AP_HAL_SMACCM: Scheduler timer process implemented correctly.
...
- Use "g_atomic" for suspend/resume timer procs.
2013-01-03 17:33:13 -08:00
James Bielman
d84ba8ef59
Use HAL suspend/resume timer procs rather than atomic.
...
- Preparation for removing begin/end atomic.
2013-01-03 17:33:13 -08:00
James Bielman
578c4859e4
AP_HAL_SMACCM: Update to new semaphore interface.
...
- Renamed files to match AVR HAL.
2013-01-03 17:33:13 -08:00
Andrew Tridgell
155fca8a4b
HAL_PX4: make APM sketches into daemons
...
this also moves uartA onto UART5, allowing ttyS0 for nsh
2013-01-04 11:14:35 +11:00
Pat Hickey
8503f3e2ae
Optflow: uses new Semaphore
2013-01-03 13:48:07 -08:00
Pat Hickey
d808c19c10
AP_InertialSensor_MPU6000: uses new semaphores
...
* some refactoring to fix differences between timerprocess
and non-timerprocess usage
2013-01-03 13:48:07 -08:00
Pat Hickey
5d91f342bb
AP_Baro_MS5611: uses new semaphore lib
2013-01-03 13:48:07 -08:00
Pat Hickey
a556a95565
AP_ADC: uses new semaphore interface
2013-01-03 13:48:07 -08:00
Pat Hickey
390e96311e
DataFlash: change to new style Semaphore library
2013-01-03 13:48:07 -08:00
Pat Hickey
f178d1bd02
AP_HAL_Empty: implement new Semaphore interface
2013-01-03 13:48:07 -08:00
Pat Hickey
2d6b649aa4
AP_HAL_AVR: Semaphore unit test
2013-01-03 13:48:07 -08:00
Pat Hickey
0029148b3a
AP_HAL_AVR: Implements new Semaphore interface
2013-01-03 13:48:07 -08:00
Pat Hickey
74e2ba2168
AP_HAL_AVR Scheduler: _in_timer_proc is volatile protected
...
* and AVRSemaphore is a friend, so it can read _in_timer_proc
to know the current context.
2013-01-03 13:48:07 -08:00
Pat Hickey
81d77d4a70
AP_HAL: New semaphore interface
...
* it now looks like a semaphore!
2013-01-03 13:48:07 -08:00
James Bielman
acf05a29ee
AP_InertialSensor_MPU6000: Poll status register if there is no data ready pin.
2013-01-03 13:48:06 -08:00
James Bielman
264db3670e
AP_Baro: Add CONFIG_MS5611_SERIAL option to choose between SPI and I2C.
...
- Update ArduCopter and ArduPlane modules to pass the correct serial
driver to the MS5611 driver.
- Update barometer examples, assuming SPI.
2013-01-03 13:48:06 -08:00
James Bielman
5753ae5692
AP_Baro: Add I2C support to MS5611 driver.
2013-01-03 13:48:06 -08:00
James Bielman
a4af314b57
Add AP_HAL_SMACCM implementation.
...
- Add a board definition for SMACCMPilot.
- Support the SMACCM HAL in required utility libraries.
2013-01-03 13:48:06 -08:00
Andrew Tridgell
1fc95a2d45
HAL_PX4: support PPM RC Input
...
HIL flying now works properly
2013-01-04 08:31:23 +11:00
Andrew Tridgell
e729a8b277
AP_HAL: rename Semaphores cpp file to match header
2013-01-03 21:36:48 +11:00
Andrew Tridgell
38bccee230
HAL_PX4: initial RCInput driver (overrides only)
2013-01-03 21:30:35 +11:00
Andrew Tridgell
85007cb766
HAL_Empty: fixed throttle in Empty RCInput
2013-01-03 21:14:00 +11:00
Andrew Tridgell
d492b72a2c
HAL_PX4: use /dev/ttyS0 for uartA
...
this also changes txspace and available to use FIONWRITE and FIONREAD
2013-01-03 21:12:10 +11:00
Andrew Tridgell
1e69b88261
HAL_PX4: use write() in panic()
...
this allows panic from the UARTDriver
2013-01-03 21:11:37 +11:00
Andrew Tridgell
ac7117245a
HAL_PX4: added a storage driver
...
stores 'eeprom' to a sdcard file
2013-01-03 19:35:05 +11:00
Andrew Tridgell
b30fa6535b
HAL_PX4: support reboot
2013-01-03 19:34:36 +11:00
Andrew Tridgell
c6c336a6e8
HAL_PX4: implement peek() and available()
...
keep a 1 byte buffer
2013-01-03 17:27:53 +11:00
Andrew Tridgell
cc7f4353b4
HAL_PX4: update simple example
2013-01-03 13:17:32 +11:00
Andrew Tridgell
b0f1ceb76b
HAL_PX4: removed some files not needed any more
2013-01-03 13:17:11 +11:00
Andrew Tridgell
d9d5eb52bf
HAL_PX4: use fd IO instead of stdio
...
this allows for hal console output from within timers, which is very
handy for debugging
2013-01-03 13:16:41 +11:00
Andrew Tridgell
c6305b5876
HAL_PX4: rework Scheduler using hrt calls
...
thanks to Julian Oes for the suggestion
2013-01-03 13:15:57 +11:00
Andrew Tridgell
9373a4e5b3
HAL_PX4: added a uartA driver
...
uses stdin/stdout for IO
2013-01-03 11:03:05 +11:00
Andrew Tridgell
2294acc652
AC_PID: fixed build on ARM
2013-01-02 22:09:02 +11:00
Andrew Tridgell
e7dea077b4
AP_Motors: fixed example sketch
2013-01-02 22:02:46 +11:00
Andrew Tridgell
5053fb8acc
HAL_PX4: implement atomic operations
2013-01-02 21:45:17 +11:00
Andrew Tridgell
5a70f3becf
HAL_PX4: added a scheduler implementation
2013-01-02 21:39:26 +11:00
Andrew Tridgell
e25e500516
AP_HAL: fixed SPI3 Semaphores.h
2013-01-02 21:07:25 +11:00
rmackay9
45b6dbf580
AP_Limit: small fixes to make parameter descriptions appear in mission planner
2013-01-02 18:50:03 +09:00
rmackay9
cf409abc63
AP_Mount: add parameter descriptions
2013-01-02 16:47:39 +09:00
rmackay9
e594f18b75
AP_InertialSensor: added parameter descriptions
2013-01-02 16:32:43 +09:00
Andrew Tridgell
a3c26d44e4
AP_HAL: rename Sempahore.h to Semaphores.h
...
this is needed to allow build on MacOS, as its case-insensitive
filesystem picks up the NuttX semaphore.h
2013-01-02 18:22:13 +11:00
rmackay9
55e6544e64
AP_InertialNav: added parameter descriptions
2013-01-02 16:17:00 +09:00
rmackay9
bf77a0f2e4
AP_Compass: added parameter descriptions
2013-01-02 16:08:44 +09:00
rmackay9
9e5861ccaf
AP_AHRS: small fix to parameter comments
2013-01-02 16:08:38 +09:00
rmackay9
77331f6538
AP_AHRS: another attempt at updating the TRIM parameter descriptions
2013-01-02 15:47:59 +09:00
rmackay9
e6c10f4f0b
AP_ARHS: add description to AHRS_TRIM parameters
2013-01-02 15:44:42 +09:00
Andrew Tridgell
374af1cd14
build: change from Arduino.mk to apm.mk
2013-01-02 17:29:37 +11:00
Andrew Tridgell
2ba2e1c279
Derivative: removed reference to DESKTOP_BUILD
2013-01-02 15:40:01 +11:00
Andrew Tridgell
3f6f0b6d79
Oilpan: removed reference to DESKTOP_BUILD
2013-01-02 15:39:41 +11:00
Andrew Tridgell
f91ddf5df9
AP_Motors: removed board type define
2013-01-02 15:27:58 +11:00
Andrew Tridgell
ba1a6eb073
AP_HAL: fixed SITL build
2013-01-02 14:48:15 +11:00
Andrew Tridgell
d0ae51e92a
memcheck: fixed for PX4 build
2013-01-02 14:45:09 +11:00
Andrew Tridgell
f9ab781d57
APM_Control: include AP_Common.h
2013-01-02 14:45:09 +11:00
Andrew Tridgell
456e8bfb6e
AP_Common: include stdlib.h for abs()
2013-01-02 14:45:09 +11:00
Andrew Tridgell
609ef220a6
AP_GPS: more state machine fixes for MTK19 GPS
2013-01-02 14:45:09 +11:00
Andrew Tridgell
ac8fcd5b23
AP_Common: include stdbool.h for ARM
2013-01-02 14:45:09 +11:00
Andrew Tridgell
d6b00bd848
AP_ADC: fixed bool problem on ARM
2013-01-02 14:45:09 +11:00
Andrew Tridgell
d3f154bbae
AP_HAL: include stdbool.h for ARM build
2013-01-02 14:45:09 +11:00
Andrew Tridgell
4764a03aaa
AP_Param: fixed ARM PX4 build
2013-01-02 14:45:09 +11:00
Andrew Tridgell
3ac3aeb1b1
AHRS: fixed build on ARM
2013-01-02 14:45:09 +11:00
Andrew Tridgell
5277dd4b0f
APM_Control: fixed build on ARM
2013-01-02 14:45:09 +11:00
Andrew Tridgell
eb74fddd9f
AP_Math: added global GRAVITY_MSS define
2013-01-02 14:45:08 +11:00
Andrew Tridgell
6901c56a2e
yaw fixup
2013-01-02 14:45:08 +11:00
Andrew Tridgell
583845cc17
ahrs fixup
2013-01-02 14:45:08 +11:00
Andrew Tridgell
5923808526
AP_Relay: allow for no relay pin
2013-01-02 14:45:08 +11:00
Andrew Tridgell
3a762f891e
AP_Param: fixup for ARM compiler
2013-01-02 14:45:08 +11:00
Andrew Tridgell
1b0670e67c
AHRS: fixup for ARM compiler
2013-01-02 14:45:08 +11:00
Andrew Tridgell
d55acbc00a
AP_YawController: fixup for ARM compiler
2013-01-02 14:45:08 +11:00
Andrew Tridgell
f7939ad179
AP_Relay: allow relay object in SITL
2013-01-02 10:19:43 +11:00
Andrew Tridgell
8d901b3f5a
HAL_AVR: fixed a warning
2013-01-02 10:19:28 +11:00
Andrew Tridgell
c980b32319
GPS: fixed state machine logic errors in MTK19 driver
2013-01-02 10:12:55 +11:00
Andrew Tridgell
8c0d1d7084
GPS: fixed MTK19 driver for AP_HAL merge
2013-01-02 09:55:37 +11:00
rmackay9
92e271e517
AP_InertialNav: increase baro delay to 0.5 sec (was 0.2sec) to allow slower baro updates on APM1
2013-01-02 09:55:37 +11:00
rmackay9
af4d998697
AP_InertialNav: correct lat/lon to cm
2013-01-02 09:55:37 +11:00
Sandro Benigno
6abe1fe94f
AP Camera changes required to work with modified AP_Relay lib.
2013-01-02 09:55:37 +11:00
Andrew Tridgell
0b2960e504
fixup relay merge
2013-01-02 09:55:37 +11:00
Sandro Benigno
cc7f26a99b
New Relay class and the subclasses for APM1 and APM2.
...
Updated AP_Camera class.
2013-01-02 09:31:32 +11:00
Craig@3DR
2de676306e
Improved parsing in auto detect
2013-01-02 09:24:31 +11:00
Craig@3DR
8cfefbc275
Updated rev number in driver
2013-01-02 09:22:21 +11:00
rmackay9
b8b17a4a70
ArduCopter: added AP_PerfMon library
2013-01-02 09:20:08 +11:00
rmackay9
bd0e018ca0
ArduCopter: restore auto-trim method but now use AHRS.add_trim
2013-01-02 09:20:08 +11:00
rmackay9
37b56662bd
AP_InertialNav: Jason's bug fix to inertial nav velocity and position calculations
2013-01-02 09:19:39 +11:00
rmackay9
120b494d83
Filter: #include AP_Buffer.h no longer needed now that completementary filter has been moved to InertialNav library
2013-01-02 09:19:39 +11:00
rmackay9
3aca61cefb
AP_Motors: remove unnecessary opposite_motor array (no longer needed with new stability patch)
2013-01-02 09:19:17 +11:00
rmackay9
41cc1c74d8
AP_InertialNav: increase time constant for Z axis to 7 seconds
2013-01-02 09:19:17 +11:00
rmackay9
a76aec675a
AP_InertialSensor: resolved compile warning re uninitialised variable
2013-01-02 09:18:03 +11:00
rmackay9
90d7f00965
AP_GPS_MTK16: saved 22 bytes of ram by moving error message into program space.
...
Perhaps there's no point in writing an error message to a console that likely nobody will be viewing anyway.
2013-01-02 09:18:03 +11:00
rmackay9
811550cca6
AP_GPS_MTK19: small bug fix re "==" vs "="
...
Also saved 22 bytes of RAM by moving error message into program space.
2013-01-02 09:16:48 +11:00
Craig@3DR
f778961acf
Added support for Mediatek firmware Rev 1.9
2013-01-02 09:16:47 +11:00
rmackay9
557f4e65de
AP_InertialNav: small performance improvement by replacing mul_transpose with direct multiplication of Z axis accel correction to specific elements of dcm
2013-01-02 09:12:40 +11:00
rmackay9
1f7614929f
AP_AHRS: save trim to eeprom when set_trim is called
2013-01-02 09:12:17 +11:00
rmackay9
e9fa5dec0f
AP_InertialNav: make use of ahrs library's get_accel_ef method to save some cpu cycles
2013-01-02 09:11:25 +11:00
rmackay9
1c08f176ea
AP_AHRS: add get_accel_ef method to return earth frame accelerometer values for use in ArduCopter's inertial nav and accel based throttle
2013-01-02 09:11:25 +11:00
Andrew Tridgell
18581d0220
HAL_AVR: change order of CS pin init - fixes APM2 boot problem
...
We now init the MPU6k CS pin before the MS5611 CS pin. This should not
matter at all, but it turns out that it solves the APM2 boot
problem. We should investigate why, as this may indicate an electrical
problem.
Pair-Programmed-With: Pat Hickey
2013-01-02 08:55:47 +11:00
Andrew Tridgell
57bf6531b4
Progmem: use right CONFIG_HAL_BOARD #ifdefs
2013-01-01 18:26:12 +11:00
Andrew Tridgell
da10e68e87
HAL_PX4: added basic console driver (output only)
2013-01-01 18:19:18 +11:00
Andrew Tridgell
0ef003a45f
AP_HAL: added PX4 board support
2012-12-30 20:02:45 +11:00
Andrew Tridgell
24a291cf66
HAL_AVR: only build on APM boards
2012-12-30 20:02:45 +11:00
Andrew Tridgell
b41440175f
HAL_PX4: started on new PX4 HAL structures
2012-12-30 20:02:45 +11:00
Andrew Tridgell
0adc4afcb5
InertialSensor: add reboot option in MPU6000 test
2012-12-27 21:29:00 +11:00
Andrew Tridgell
212728be34
InertialSensor: ensure MPU6000 is out of sleep mode before configuring
...
the MPU6000 starts in sleep mode, and can take a while to wakeup
2012-12-27 21:28:41 +11:00
Andrew Tridgell
091c14a33e
SITL: disabled buffering on stdout
...
this fixes the ArduPlane log dump
2012-12-24 08:00:57 +11:00
Andrew Tridgell
0186fabb3b
build: allow building with the "Empty" HAL
...
useful for porting
2012-12-24 07:30:50 +11:00
Andrew Tridgell
122b8716a7
InertialSensor: added auto reset of MPU6000 on startup failure
...
this works around the problem of the MPU6000 failing to come up on DTR
reset or warm reboot
2012-12-24 07:17:03 +11:00
Andrew Tridgell
44ad850542
InertialSensor: latch the data ready pin high on new data
...
this ensures we don't miss a sample due to another source of delay
2012-12-23 17:46:36 +11:00
Andrew Tridgell
fcb09c3993
InertialSensor: fixed example app for new syntax
2012-12-23 12:49:34 +11:00
Andrew Tridgell
e2edad8a3f
InertialSensor: fixed last sample time in MPU6000
...
we lost this in the final work on the DTR bug
2012-12-23 08:59:35 +11:00
Andrew Tridgell
feb11f0bc9
PX4: mark example as nobuild for now
2012-12-22 14:40:10 +11:00
Andrew Tridgell
e7b915b0f4
AP_Math: fixed error comment
2012-12-22 12:52:42 +11:00
Andrew Tridgell
463a089e5c
InertialNav: fixed example build
2012-12-22 12:50:31 +11:00
Andrew Tridgell
c3dc23d295
AP_HAL: fixed warning in progmem
2012-12-22 09:49:19 +11:00
Andrew Tridgell
1a53bc783c
InertialSensor: poll data ready pin instead of an interrupt for MPU6k
2012-12-22 09:16:31 +11:00
Pat Hickey
563ca3f79b
AP_HAL_AVR: expose gpio pin 70 for mpu6000 interrupt input
2012-12-22 09:11:14 +11:00
Pat Hickey
1678dcc6f0
AP_HAL: GPIO INTERRUPT defines
2012-12-22 09:11:11 +11:00
Andrew Tridgell
93040e5725
AP_HAL: removed the defer_timer_process() function
...
this is now unused
2012-12-21 20:01:42 +11:00
Andrew Tridgell
9548e7e79e
InertialSensor: simplify the data_ready interrupt handling
...
this avoids using the defer process code, and fixes a nasty bug that
caused the APM to lockup on reset
2012-12-21 20:01:19 +11:00
Andrew Tridgell
c5ba33d39a
AP_Baro: fixed MS5611 semaphore handling
2012-12-21 19:33:57 +11:00
Andrew Tridgell
47358929e2
HAL_AVR: fixed attach_interrupt race condition
2012-12-21 19:33:57 +11:00
Andrew Tridgell
8d47a739a1
SITL: fixed a return value in snprintf functions
2012-12-20 22:46:22 +11:00
Andrew Tridgell
cd430cb6a8
RC_Channel: added no_deadzone version of set_pwm()
2012-12-20 22:41:58 +11:00
Andrew Tridgell
f504e2ec67
InertialSensor: removed sample rate in example
...
not needed any more
2012-12-20 15:16:43 +11:00
Andrew Tridgell
9931009db2
Math: use pythagorous2() in some more places
2012-12-20 15:16:18 +11:00
Andrew Tridgell
13ea0bb5d8
AP_Camera: disable relay on APM2
2012-12-20 14:53:24 +11:00
Andrew Tridgell
4a6b46c661
AP_GPS: fixed multiple GPS detection bug
2012-12-20 14:53:24 +11:00
Andrew Tridgell
fb4540a349
DataFlash: disable some debug code
2012-12-20 14:53:24 +11:00
Andrew Tridgell
f549950a9c
AP_GPS: remove some debug code
2012-12-20 14:53:23 +11:00
Andrew Tridgell
3aa39da6cd
AP_Baro: removed some debug code
2012-12-20 14:53:23 +11:00
Andrew Tridgell
e282554035
AHRS: removed some debug code
2012-12-20 14:53:23 +11:00
Andrew Tridgell
a180437028
AP_Compass: disable auto-declination on 1280
...
this saves a few k of flash space
2012-12-20 14:53:23 +11:00
Andrew Tridgell
60d3df50ae
AP_HAL: changed delay() to take a uint16_t
...
this allows for up to 32 second delays, and saves a bit of flash space
2012-12-20 14:53:23 +11:00
Andrew Tridgell
d8bed0c2aa
AP_Math: fixed get_distance() function
2012-12-20 14:53:23 +11:00
Pat Hickey
6437bd3a08
AP_InertialSenor MPU6000 test: fixed for user interact changes
2012-12-20 14:53:23 +11:00
Pat Hickey
9055681b3a
AP_InertialSensor: use AP_InertialSensor_UserInteract
...
* permits polymorphic user interaction, so we can plug in a
pure mavlink interface
2012-12-20 14:53:23 +11:00
Pat Hickey
a2cf47e769
AP_InertialSensor: start implementing UserInteract
...
* untested implementation in terms of BetterStream
2012-12-20 14:53:23 +11:00
Pat Hickey
b2d69e6a8c
AP_HAL_Empty: betterstreams get vprintfs
2012-12-20 14:53:23 +11:00
Pat Hickey
823efc4734
AP_HAL_AVR_SITL: implement BetterStream's vprintf methods
2012-12-20 14:53:22 +11:00
Pat Hickey
1ed6a49a7a
AP_HAL_AVR: implementation for each BetterStream vprintf
...
* had to rename the utility vprintf function calls to print_vprintf
to make the naming work.
2012-12-20 14:53:22 +11:00
Pat Hickey
7681fef988
AP_HAL: BetterStream gets vprintf and vprintf_P methods
2012-12-20 14:53:22 +11:00
Pat Hickey
ec8f08d743
AP_HAL_AVR_SITL: rename vprintf utility to print_vprintf
2012-12-20 14:53:22 +11:00
Pat Hickey
5ab4e57673
AP_HAL_AVR: rename vprintf function to print_vprintf
...
* because it takes an AP_HAL::Print
2012-12-20 14:53:22 +11:00
Pat Hickey
1b0bde2779
AP_HAL_AVR: rename vprintf files to print_vprintf
2012-12-20 14:53:22 +11:00
Andrew Tridgell
bada70d871
InertialSensor: fixed example build on 1280
2012-12-20 14:53:22 +11:00
Andrew Tridgell
8a70e173a7
AP_HAL: restrict build to right board type
2012-12-20 14:53:22 +11:00
Andrew Tridgell
3c0440b0b4
Math: use common degrees() and radians() functions
2012-12-20 14:53:22 +11:00
Andrew Tridgell
7277d4934d
AP_InertialSensor: move constructor into cpp
2012-12-20 14:53:22 +11:00
Andrew Tridgell
ceb3f577d8
libraries: use new math functions
2012-12-20 14:53:22 +11:00
Andrew Tridgell
a072afa223
AP_Math: expand some macros into functions
...
this saves some flash
2012-12-20 14:52:38 +11:00
Andrew Tridgell
a1187519a8
AP_HAL: use AP_HAL_BOARD_DRIVER in remaining test sketches
2012-12-20 14:52:37 +11:00
Pat Hickey
4c715bfd04
AP_HAL_AVR_SITL: add Util driver, fix deprecated deps on HAL_AVR.h
2012-12-20 14:52:37 +11:00
Pat Hickey
771f2a3acf
AP_HAL_Empty: add Util driver
2012-12-20 14:52:37 +11:00
Pat Hickey
f9eff068f9
AP_HAL_AVR: UtilityStringTest added
2012-12-20 14:52:37 +11:00
Pat Hickey
defc539e57
AP_HAL_AVR: implement string Utils in terms of existing vprintf
2012-12-20 14:52:37 +11:00
Pat Hickey
b3abe89989
AP_HAL_AVR: add Util stubs
2012-12-20 14:52:37 +11:00
Pat Hickey
0d702045b8
AP_HAL: Add Util member for string utilities
2012-12-20 14:52:37 +11:00
Pat Hickey
372c0074b1
AP_HAL_AVR: remove old style HAL_AVR classes (deprecated)
2012-12-20 14:52:37 +11:00
Andrew Tridgell
2679eabdef
Cleanup: removed unused AP_GPS_IMU
2012-12-20 14:52:37 +11:00
Andrew Tridgell
678c281f78
Cleanup: removed unused AP_Navigation
2012-12-20 14:52:37 +11:00
Andrew Tridgell
32afc3f9ae
Filter: fixed example warnings
2012-12-20 14:52:36 +11:00
Andrew Tridgell
29f5e346c2
Menu: fixed example warnings
2012-12-20 14:52:36 +11:00
Andrew Tridgell
a76688e630
Math: fixed example warnings
2012-12-20 14:52:36 +11:00
Andrew Tridgell
b8843489be
HAL_AVR: fixed example warnings
2012-12-20 14:52:36 +11:00
Andrew Tridgell
b673320f72
ADC: fixed example warnings
2012-12-20 14:52:36 +11:00
Andrew Tridgell
22ada8b9c3
RC_Channel: fixed example build
2012-12-20 14:52:36 +11:00
Andrew Tridgell
62bfded26c
PID: fixed example build
2012-12-20 14:52:36 +11:00
Andrew Tridgell
393455cdbb
RangeFinder: fixed example build
2012-12-20 14:52:36 +11:00
Andrew Tridgell
b06e072c87
AP_InertialSensor: fixed example build
2012-12-20 14:52:36 +11:00
Andrew Tridgell
c15eb97c8d
AP_Baro: fixed example build
2012-12-20 14:52:36 +11:00
Andrew Tridgell
bd2a733a6b
HAL_Empty: allow example build for other backends
2012-12-20 14:52:36 +11:00
Andrew Tridgell
8beaec61a8
AP_GPS: fixed build for new syntax
2012-12-20 14:52:36 +11:00
Pat Hickey
eb530b86e8
move Arduino.mk to /mk/Arduino.mk
2012-12-20 14:52:35 +11:00
Andrew Tridgell
44f860e102
InertialSensor: fixed some compiler warnings
2012-12-20 14:52:35 +11:00
Andrew Tridgell
fc66f5594f
AHRS: allow AHRS test to build with SITL
2012-12-20 14:52:34 +11:00
Andrew Tridgell
7ecf8981b9
SITL: added dummy SPI and make RCInput 50Hz
2012-12-20 14:52:34 +11:00
Andrew Tridgell
e020694c03
SITL: fixed build of apm1/apm2 target
2012-12-20 14:52:34 +11:00
Andrew Tridgell
4cff98dcae
AP_HAL: added AP_HAL_BOARD_DRIVER define
...
this makes example sketches easier to read
2012-12-20 14:52:33 +11:00
Andrew Tridgell
abbe37be37
SITL: added emulated airspeed sensor on a pin
2012-12-20 14:52:33 +11:00
Andrew Tridgell
46f7c9e92b
SITL: added basic analogin implementation
2012-12-20 14:52:33 +11:00
Andrew Tridgell
472b45bc2a
SITL: fixed use of local printf() method in UART driver
2012-12-20 14:52:33 +11:00
Andrew Tridgell
7be507948f
SITL: added SITL_State::loop_hook()
...
this prevents us using so much CPU time, and ensures stdout is flushed
2012-12-20 14:52:33 +11:00
Andrew Tridgell
69bebbcaf8
SITL: removed old SITL code
2012-12-20 14:52:33 +11:00
Andrew Tridgell
0c9d37e2ee
SITL: added RCInput and RCOutput
2012-12-20 14:52:33 +11:00
Andrew Tridgell
28f0ce6185
Build: use -O0 for SITL
2012-12-20 14:52:33 +11:00
Andrew Tridgell
dcc17dad94
SITL: added panic() method in scheduler
2012-12-20 14:52:33 +11:00
Andrew Tridgell
475496cee2
Revert "Arduino.mk: use target variables rather than recursive make for apm1, apm2.."
...
This reverts commit fcd58cc1d7892bb8b45db75c35e1bdccaa2d47bb.
still doesn't work ...
2012-12-20 14:52:33 +11:00
Andrew Tridgell
975506c840
Build: add debugging in SITL build
2012-12-20 14:52:33 +11:00
Andrew Tridgell
448fc6719f
HAL_Empty: fixed return in dataflash
2012-12-20 14:52:33 +11:00
Andrew Tridgell
6627e7ea0e
HAL_Empty: fixed I2CDriver declaration
2012-12-20 14:52:33 +11:00
Andrew Tridgell
5f7f6966af
SITL: fixed GPS and UART startup
2012-12-20 14:52:32 +11:00
Andrew Tridgell
334b96b375
SITL: switched to empty driver for unimplemented backends
2012-12-20 14:52:32 +11:00
Andrew Tridgell
18db7b2efd
GPS: move _port setting to init()
...
this is needed to avoid constructor ordering dependencies
2012-12-20 14:52:32 +11:00
Pat Hickey
107ab1a694
AP_Baro: translated to SPI transactions
2012-12-20 14:52:32 +11:00
Pat Hickey
b502732249
AP_InertialSensor: rewrite basic code for spi device transactions
...
* I'm not touching that DMP stuff because I'm pretty convinced it should
instead be deprecated
2012-12-20 14:52:32 +11:00
Pat Hickey
3153105682
AP_HAL_AVR: spi transaction handle null RX properly
2012-12-20 14:52:32 +11:00
Pat Hickey
992de8c2b9
AP_ADC_ADS7844: changed to use spidevicedriver transaction
2012-12-20 14:52:32 +11:00
Pat Hickey
b43b003777
AP_ADC: fix typo in test
2012-12-20 14:52:32 +11:00
Pat Hickey
5c1e7abf0e
AP_HAL_Empty: add spi driver transaction
2012-12-20 14:52:32 +11:00
Pat Hickey
4fe889c9c5
AP_HAL_AVR: Implement bulk SPI transaction
2012-12-20 14:52:32 +11:00
Pat Hickey
d2f7402243
AP_HAL: add bulk transaction to SPIDeviceDriver
2012-12-20 14:52:32 +11:00
Pat Hickey
087b1fa196
AP_HAL_AVR: AnalogIn returns new ADCSource each time a channel is requested
...
* fixes a bug where multiple sources created as pin -1, then change to
appropriate pin on mavlink messages. Make treat each creation as distinct
object.
2012-12-20 14:52:32 +11:00
Pat Hickey
d5a46ca1e3
AP_ADC: uses scheduler panic
2012-12-20 14:52:32 +11:00
Pat Hickey
d92e8045c1
AP_Baro: uses scheduler panic
2012-12-20 14:52:31 +11:00
Pat Hickey
2c2279722b
AP_Baro_MS5611: use scheduler panic
2012-12-20 14:52:31 +11:00
Pat Hickey
a4f41c1d29
AP_InertialSensor: MPU6000 uses scheduler panic
2012-12-20 14:52:31 +11:00
Pat Hickey
90670cb499
AP_HAL_AVR: panic in spidevice0
2012-12-20 14:52:31 +11:00
Pat Hickey
885fc79af5
AP_HAL_Empty: add panic method to scheduler
2012-12-20 14:52:31 +11:00
Pat Hickey
9656b0ad0e
AP_HAL_AVR: add panic method to scheduler
2012-12-20 14:52:31 +11:00
Pat Hickey
c86004d676
AP_HAL: Add panic method to scheduler
2012-12-20 14:52:31 +11:00
Pat Hickey
8fe3c5e5d6
Arduino.mk: use target variables rather than recursive make for apm1, apm2..
2012-12-20 14:52:31 +11:00
Pat Hickey
76dabef7d6
AP_HAL_Empty: fix public declaration for i2cdriver
2012-12-20 14:52:31 +11:00
Pat Hickey
eda450a166
AP_HAL: I2CDriver bug fixed for pure virtual base class
2012-12-20 14:52:31 +11:00
Pat Hickey
de6f9e52b2
AP_HAL_Empty: finished up scaffolding
2012-12-20 14:52:31 +11:00
Pat Hickey
4c930b77a4
DataFlash_Empty defined
2012-12-20 14:52:31 +11:00
Pat Hickey
b7cd4312f3
AP_HAL_Empty: more scaffolding complete
2012-12-20 14:52:31 +11:00
Andrew Tridgell
7d27e420ae
AP_HAL: remove unnecessary Arduino.h includes
2012-12-20 14:52:30 +11:00
Andrew Tridgell
6a56f72918
Build: added empty Arduino.h
2012-12-20 14:52:30 +11:00
Andrew Tridgell
98ead51801
SITL: fill in a lot more of the AP_HAL SITL backend
2012-12-20 14:52:30 +11:00
Andrew Tridgell
4a54ffb523
Baro: use local include to reduce boilerplate
2012-12-20 14:52:30 +11:00
Andrew Tridgell
d473203737
Build: added global board targets
2012-12-20 14:52:30 +11:00
Pat Hickey
3cc204321c
AP_Motors_Class: add Progmem typedef
2012-12-20 14:52:30 +11:00
Pat Hickey
8d0c56a19a
AP_Curve: put template in cpp file
...
* required for the new funny way avr-gcc 4.7 does PSTR.
2012-12-20 14:52:30 +11:00
Pat Hickey
6ea38432b9
AP_Progmem_AVR: prog_char typedef was deprecated in avr-gcc 4.7, add compat def
2012-12-20 14:52:30 +11:00
Pat Hickey
3e3c0f57ae
AP_HAL_Empty: started building out the scaffolding
2012-12-20 14:52:30 +11:00
Pat Hickey
b79bd01761
SPIDriver: namespace explicit to better permit copypasta
2012-12-20 14:52:30 +11:00
Pat Hickey
527dfb5af4
AP_HAL: remove EmptyUARTDriver
2012-12-20 14:52:30 +11:00
Pat Hickey
63eb1dc85d
AP_HAL_AVR_SITL: separate header for AP_HAL_MAIN and Private
2012-12-20 14:52:30 +11:00
Pat Hickey
07be511f5e
AP_HAL_AVR: move AP_HAL_MAIN into separate header
2012-12-20 14:52:30 +11:00
Pat Hickey
d18b9feaa1
AP_HAL: add HAL_BOARD_EMPTY to AP_HAL_BOARDS
2012-12-20 14:52:30 +11:00
Pat Hickey
104ad8f6c8
AP_Menu: save a little ram by reducing MENU_ARGS_MAX to 3
...
* we only ever use 3 in arducopter's gyro gain setup
2012-12-20 14:52:29 +11:00
Andrew Tridgell
af12c18dea
AP_Param: setup var_info and num_vars earlier
...
needed for AP_HAL startup
2012-12-20 14:52:29 +11:00
Andrew Tridgell
8916b280fd
SITL: filled in more of the HAL SITL backend
2012-12-20 14:52:29 +11:00
Andrew Tridgell
e10e3ee3be
AP_HAL: fixed argv declaration to match getopt()
2012-12-20 14:52:29 +11:00
Andrew Tridgell
964bc56aa2
DataFlash: reinstate SITL dataflash code
2012-12-20 14:52:29 +11:00
Andrew Tridgell
18824c7ef5
AP_HAL: expose argc/argv in hal.init()
...
used for SITL port
2012-12-20 14:52:29 +11:00
Pat Hickey
ddafd4ffbb
memcheck: need AP_HAL_Boards import for CONFIG_HAL_BOARD configs to make sense
...
* with great programming in c preprocessor comes great responsibility
2012-12-20 14:52:29 +11:00
Pat Hickey
d93d932831
ArduCopter: defines fixes
...
Conflicts:
libraries/AP_Common/Arduino.mk
2012-12-20 14:52:28 +11:00
Pat Hickey
f060df9747
AP_HAL_AVR: now that we can detect the APM revision, use wdt reboot on apm2
2012-12-20 14:52:28 +11:00
Pat Hickey
7622b725c9
AP_Limits: fixes to use hal.storage for eeprom access
2012-12-20 14:52:28 +11:00
Pat Hickey
b0b3fa33b4
AP_Limits: fix for AP_Param var_info registration in AP_Limit_Module
...
* AP_Limit_Module class does not have its own var_info table.
2012-12-20 14:52:28 +11:00