- both CC serial ports are now disabled by default (no telemetry);
- serial ports now have DSM2, DSMX (10bit) and DSMX (11bit) options;
- ReceiverGroups now have DSM (MainPort) and DSM (FlexiPort) options.
For DSM2 protocol there is an explicit resolution bit in the stream, so
the DSM2 should be selected. For DSMX there is no such bit, and user
should choose the resolution from the list configuring the spektrum port.
ReceiverGroups have single DSM option which is handled by the same driver.
Downside: this implementation saves received frame first, unrolls by the
end of frame. This should be ok, but may be improved by unrolling channels
on the fly in the rx callback.
Another minor difference is that a ChannelGroup is now bound to port:
DSM (MainPort) or DSM (FlexiPort). This was considered as acceptable
solution in order to not have 6 DSM options for each ChannelGroup and
even more in case of new DSM protocol variations.
Known problem: it is not possible to choose same protocols like
DSM2/DSM2 for two ports. It can be enabled by adding an exception to
common rule, though.
The DSMX throttle channel misbehavior (zero value) is not treated
specially yet. It should trigger the failsafe being out of bounds.
More info and data dumps are required to handle this properly.
In the previous version the decoder could in rare cases get synced from
the middle of data stream in case of data byte equal to the S.Bus start
of frame (SOF) byte (wrong data will be rejected but it was not perfect).
Now it waits for the real start of frame and then checks the SOF byte.
- does not glitch when used in 2-frame mode (DM9, 9503, etc)
- does NOT provides yet DSMX stream decoding - do NOT merge
- uses a bit more time in the interrupt, but frees 16 bytes of RAM.
This is done to help decoding the weird DSMX stream which does not
contain explicit resolution/frame/lost frames info and needs special
processing (to be done yet).
TIM5-8. Also TIM1 was not handled probably (for CC either) as the name of the
IRQ is TIM1_CC and TIM1_UP for the capture compare versus update. I haven't
checked the downstream code that the registers it uses to map from a context to
event is invariant under timer channel.
TIM5-8. Also TIM1 was not handled probably (for CC either) as the name of the
IRQ is TIM1_CC and TIM1_UP for the capture compare versus update. I haven't
checked the downstream code that the registers it uses to map from a context to
event is invariant under timer channel.
them symbolic constants.
- A timeout is 0
- A missing driver is 65534
- An invalid channel is 65535
ManualControl: Make it deal with the values explicitly. A timed out value
should not be treated like a minimum duration signal. Instead it does not
updated the scaled value but marks the data window as invalid to trigger the
failsafe.
Move the configuration files for INS from AHRS* to INS*. Strip out unused
fields in settings and merge calibration and settings since settings has
basically no information.
Allocate per-instance data for drivers from the heap
rather than as static variables from the .data segment.
This converts > 800 bytes of RAM from being always consumed
as static data into being allocated from the heap only when
a particular feature is enabled in the hwsettings object.
A minimal config (no receivers, flexi port disabled, main port
disabled) leaves 2448 bytes of free heap. That's our new baseline.
Approximate RAM (heap) costs of enabling various features:
+ 632 Serial Telemetry (includes 400 bytes of Rx/Tx buffers)
+ 108 PWM Rcvr
+ 152 PPM Rcvr
+ 112 Spektrum Rcvr
+ 24 S.Bus (Should be closer to 68 since driver is still using
static memory)
There are still some drivers that pre-allocate all of their memory
as static data. It'll take some work to convert those over to
dynamically allocating their instance data.
PWM and PPM can now coexist in the same load and be
selected at boot time via the hwsettings UAVObject.
This is basically a complete restructuring of the
way the drivers interact with the TIM peripheral in
the STM32.
As a side effect, the PWM and PPM drivers are now
ready to support multiple instances of each.
This also provides the first step toward being able
to reassign some of the PWM input pins to be servo
output pins. Still more work required, but this is
a good start.
transfers from IRQ. Also catch the double 0x70084 event which was locking up
the FSM with -Os enabled. I did this in a cheating way (filtering the event
based on state) but it's the cleanest I can see. Hopefully a DMA version of
I2C will fix this.
CRC. This wasn't the case on F1. With CRC the last byte of the buffer passed
to PIOS_SPI_TransferBlock is NOT USED. This is the case on both F1 and F2.
Also need to DeInit DMA before enabling or it doesn't enable successfully.
Finally added a timeout which sets a fail on the pios spi transfer in the case
that either of the dma channels fails to enable.
needed by users because if too much changes I change the FS magic and trigger a
wipe.
Possibly the erase should require a particular "magic" object id value to
execute? This would make it harder to do manually through UAVOs though.
This allows the GCS to emulate a receiver device via the
telemetry link.
Select "GCS" as your input type in the manualcontrol config
screen and calibrate it as normal.
Note: The expected values for the channels are in microseconds
just like a PWM or PPM input device. The channel values
are validated against minimum/maximum pulse lengths just
like normal receivers.
The small bootloaders (CC and PipX) are out of flash space
so their stopwatch implementation has been swapped out for
one based on the DELAY clock that takes about 500 bytes less
of code space.
Identical functionality is preserved.
This allows the spektrum and sbus receiver drivers to bind
directly to the usart layer using a properly exported API
rather than overriding the interrupt handler.
Bytes are now pushed directly from the usart layer into the
com layer without any buffering. The com layer performs all
of the buffering.
A further benefit from this approach is that we can put all
blocking/non-blocking behaviour into the COM layer and not
in the underlying drivers.
Misc related changes:
- Remove obsolete .handler field from irq configs
- Adapt all users of PIOS_COM_* functions to new API
- Fixup callers of PIOS_USB_HID_Init()
Update to use 32-bit microsecond values.
Remove PIOS_DELAY_DiffuS per consensus (caller can do it easily themselves).
Update the core delay logic per Stac's suggestion to a version that is
resistant to various overflows.
Address the following review feedback items:
- use stdint types
- avoid the use of magic numbers (define CYCCNTENA)
- remove expository comment about sneakiness and corresponding code, replace with something simpler based on the API
- remove commented/#if 0 code
Each channel was previously tracking a separate driver.
Now, channels are grouped within a channel group to save
RAM used for tracking and to better reflect how channels
are actually mapped.
Working spektrum bind routine, depending your TX try BIND_PULSES 3,5,7,9 (5 works with DX7)
Boot process takes too long on MB so bind command misses the window (20-140ms).
Also reduce heap has it does not fit in SRAM anymore (not with current compiler).
(that's ok since if there is more space available, it will be reclaimed).
Merge branch 'master' into OP-423_Mathieu_Change_Init_To_Reduce_Memory_Footprint
Conflicts:
flight/CopterControl/System/inc/pios_config.h
flight/Modules/ManualControl/manualcontrol.c
This is a port of a work-in-progress by Sambas onto
the new driver infrastructure needed for boot-time
configuration.
PPM and PWM still don't coexist in a build but this
is closer.
The initial baud rates of each interface are now forced in the
board init code.
Any modules using USARTs should have fields added to
their settings object to allow the user to change the
baud rate from the default by using the COM layer APIs.
Developers requiring custom baud rates before the settings
objects are in place should locally edit the cfg structs
to specify the desired baud rates.
Tested this heap2 at runtime with CC and new compiler since old one (current) triggers strict alliasing error.
That's ok since strict aliasing is disabled on OP, and CC only use heap1.
This should mark an end to the compile-time selection of HW
configurations.
Minor changes in board initialization for all platforms:
- Most config structs are marked static to prevent badly written
drivers from directly referring to config data.
- Adapt to changes in .irq fields in config data.
- Adapt to changes in USART IRQ handling.
Major changes in board initialization for CC:
- Use HwSettings UAVObj to decide which drivers to attach to
the "main" port and the flexi port, and select the appropriate
device configuration data.
- HwSettings allows choosing between Disabled, Telemetry, SBUS,
Spektrum,GPS, and I2C for each of the two ports.
- Use ManualControlSettings.InputMode to init/configure the
appropriate receiver module, and register its available rx channels
with the PIOS_RCVR layer. Can choose between PWM, Spektrum and PPM
at board init time. PPM driver is broken, and SBUS will work once
it is added to this UAVObj as an option.
- CC build now includes code for SBUS, Spektrum and PWM receivers in
every firmware image.
PIOS_USART driver:
- Now handles its own low-level IRQs internally
- If NULL upper-level IRQ handler is bound in at board init time
then rx/tx is satisfied by internal PIOS_USART buffered IO routines
which are (typically) attached to the COM layer.
- If an alternate upper-level IRQ handler is bound in at board init
then that handler is called and expected to clear down the USART
IRQ sources. This is used by Spektrum and SBUS drivers.
PIOS_SBUS and PIOS_SPEKTRUM drivers:
- Improved data/API hiding
- No longer assume they know where their config data is stored which
allows for boot-time alternate configurations for the driver.
- Now registers an upper-level IRQ handlerwith the USART layer to
decouple the driver from which USART it is actually attached to.
This separates the RTC device and interrupt handling
from the devices that rely on the tick notifications.
Drivers can now register tick notification functions
that will be called on each RTC tick event.
All receivers now fall under the same driver API provided
by pios_rcvr.c.
This is part of a larger sequence of commits that will
switch the receiver selection over to boot time dynamic
configuration via UAVObjects.
Also implement some ordering (quite ugly still) in the module init and task creation order so we can decide which module to start/init first
and which module to start/init last.
This will be replaced/adapter with the uavobject list later (once it's implemented).
reserving some space for module init and task create parameters to customize module/task creation (this will be usefull once we get the list and customization from customer).
Changes have been made for OP and CC. Tested comped with CC,OP, sim_posix.
Only ran on bench with CC for couple of minutes (code increase expected but no dropping of stack which is good).
This gives task creation at the time wherethe all heap is available.
heap reamining is low (about 500) but stacks can be ajusted (specially the 200 bytes from system) to give the level close to 1Ko if needed.
Merge branch 'master' into OP-423_Mathieu_Change_Init_To_Reduce_Memory_Footprint
Conflicts:
flight/CopterControl/System/inc/FreeRTOSConfig.h
flight/CopterControl/System/inc/pios_config.h
- create linker section for those <module>Initialize()
- later this list will incorporate parameters as well. (this probably will be more a OP feature to swap/remove/delete module on the fly.
- this is not done at compile time anymore by Makefile.
- this will allow us to have control on the module start at run-time (not implemented but build the ground for it).
- this simplify the startup (Part of code re-org).
- this change does not affect sim_posix and win32 (since they don't need that)
- ensure it's compiling for PiOS.posix
- port to PiOS.win32 but not tested (not compiled)
- tested on CC
- compile on OP.
- this free ~200 bytes.
- current avalable bytes (is we keep the same remaining bytes on the stack than before) is easily passed the 1.2Ko mark on CC with new gcc (4.5.2)
- this does not include init-reorg for each module (I still think more can be freed)
It was tested being merged with OP-472_CorvusCorax_CopterControl-Guidance_v3
branch, Spektrum on USART3 and GPS on USART1 and seems to work.
Currently defaults mimic original behavior, that is, if USE_SPEKTRUM
is not defined - define USE_PWM and USE_GPS. Thsi should be refactored
later to make it configurable from the Makefile.
Also it was not ported to the OP MB: it currently does not support the
S.Bus hardware and still has original behavior with the patch. But this
is one more step to dynamic configuration of ports.
CAREFULL: the heap section need to be the last section in RAM to avoid overwritting data...
Tested with GCC 4.5.2 this gives 1K of free bytes usable in heap right away (including the 200 bytes saved just by using the new gcc).
This does not include any code re-org yet!
I managed to test CC with heap2 changes and the init stack claimed back to heap once scheduler starts.
the changes of this commit are OP related (just cleanup on CC side):
Arch specific stuff (in reset vector) to hide this from portable code:
- switch back to MSP stack before starting the scheduler so that the sheduler can use the IRQ stack (when/if needed).
- call the C portable function in heap2 to claim some stack back (the number to claim is taken from linker file).
- start the scheduler from reset vector (I move this here from main because it make sense to not go back to C (so that I don't need to copy the rolled stack in case the sheduler returns). This make it more clean.
- Also I have added the call to the mem manager if sheduler return. that way, we don't reset indefinitely if memory runs out. We will go to this handler and figure things out (right now, it's just looping but at least not rebooting. Probably trap NMI would be better (later improvement).
- switch back to MSP stack before starting the scheduler so that the sheduler can use the IRQ stack (when/if needed).
- call the C portable function in heap1 to claim some stack back (the number to claim is taken from linker file).
- start the scheduler from reset vector (I move this here from main because it make sense to not go back to C (so that I don't need to copy the rolled stack in case the sheduler returns). This make it more clean.
- Also I have added the call to the mem manager if sheduler return. that way, we don't reset indefinitely if memory runs out. We will go to this handler and figure things out (right now, it's just looping but at least not rebooting. Probably trap NMI would be better (later improvement).
The part missing for this part is the weak attribute for the function in heap1.c so that we don't have to update everything with empty stub.
I think the weak atrribute for C function called in assembly is arch dependent so I am not sure if this is possible (will look into it, maybe somebody outthere nows).
Right now, it's heap1 dependent and won't work with heap2. I will clean that up the next couple of days.
I did some test and it looks good.
this is without init code re-organization so we don't free as much as we will be it's good starts.
This compile with sim_posix (since it does not affect portable code) so this is really clean.
I only tested this with CC. I will port it for OP when I will work on heap2.
- use IRQStack for ISRs (at begening of SRAM) (let's call it the irq stack)
- use end of heap for stack needed during initialization (let's call it the init stack).
- the systemStats in GCS indicate the remaining bytes in the IRQ stack (this is realy usefull to monitor our (nested) IRQs.
This is the base ground to provide as much memory as possible available at task creation time.
Next step is to re-organize the initialization in order to move all the init out of the thread's stacks onto the init stack.
This will provide as much memory as possible available at task creation time.
Basically the stack during initialization will be destroyed once the scheduler starts and dynamic alloc are made (since the init stack is at the end of the heap). We will need to make sure we don't clobber the heap during initialization otherwise this will lead to stack corruption.
matches. Read the flash first bytewise to compute CRC instead of buffering
which is more RAM efficient but very inefficient as it sets up many one byte
SPI transfers.
Also incremented the filesystem magic flag to trigger an automatic flash wipe
on this upgrade.
- only affect flight/PiOS (no change for posix and win32)
- tested on recent master (some runtime on CC with GCS)
- the new timer feature is not compiled-in since we don't use it yet.
- NO TEST FLIGHT
The pipxtreme boards use a sector of the on-board flash
for configuration storage. Adjust the memory maps to
reflect this.
The board_info_blob is also extended to include the EE
bank definitions. This should be used by the pipxtreme
firmware rather than determining it based on chip size.
Now that every bootloader build has a board info blob,
make all fw and bl images use it.
The following MACROS are removed:
BOARD_TYPE, BOARD_REVISION, BOOTLOADER_VERSION,
START_OF_USER_CODE, HW_TYPE
These values are now ONLY available from the bootloader
flash via the pios_board_info_blob symbol. These values
must not be #defined or otherwise hard-coded into the
firmware in any way. The bootloader flash is the only
valid source for this information.
NOTE: To ensure that we have an upgrade path from an
old bootloader (without board_info_blob) to a
new bootloader (with board_info_blob), it is
essential that the bu_* targets do not depend
on (or validate) the board_info_blob being present
in the bootloader flash.
The USE_BOOTLOADER compile flag was only being used
to determine where the ISR vector table was located.
Provide this explicitly from the linker since it knows
exactly where it is putting the ISR vector table.
- New macros for fw, bl and bu rules in top-level make
- Per-board info factored into make/board/*/board-info.mk
- Per-board info now shared btw. fw, bl and blupd for each board
- BOARD_TYPE, BOARD_REVISION, BOOTLOADER_VERSION, HW_TYPE
- MCU, CHIP, BOARD, MODEL, MODEL_SUFFIX
- START_OF_BL_CODE, START_OF_FW_CODE
- blupd_* goals renamed to bu_*
- all_blupd goal renamed to all_bu
- firmware goals renamed to fw_*, board name goals are preserved
- bu_*_program now writes updater to correct address for all boards
- BL updater firmware builds now produce .opf format including
version info blob.
- BL updater firmware name now includes board name.
- INS makefile brought up to date w.r.t. linker scripts
The board info blob is stored in the last 128 bytes of the
bootloader's flash bank. You can access this data from the
application firmware like this:
#include <pios_board_info.h>
if (pios_board_info_blob.magic == PIOS_BOARD_INFO_BLOB_MAGIC) {
/* Check some other fields */
}
DO NOT link pios_board_info.c into your application firmware.
Only bootloaders should provide the content for the board info
structure. The application firmware is only a user of the data.
This change is made up of a number of tightly coupled
changes:
- Deprecate the use of the USE_BOOTLOADER command-line
option. It is now hard-coded in each Makefile.
Overriding it on the command line is not allowed.
- Split apart the memory declaration and the section
declaration in all linker files (*_memory.ld and
*_sections.ld).
- Describe the split between bootloader and app sections
of flash in each board's _memory.ld file.
- Change program target to selectively erase flash so
that the installed bootloader is preserved across even
JTAG programming operations.
- All elf files are built with debug symbols and are not
stripped. This should help debugging with gdb. The
images programmed on the boards are all .bin files now
which do not include symbols.
New targets:
- make blupd_all_clean
- make blupd_all
- make blupd_openpilot
- make blupd_ahrs
- make blupd_coptercontrol
- make blupd_pipxtreme
These targets are also included in the 'all_flight' target.
AHRS_comms still needs to be implemented. INS/GPS functionality still needs to be implemented. Double-check of the new drivers still needs to be done.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@3162 ebee16cc-31ac-478f-84a7-5cbb03baadba
We where hammered on the head with interrupts that the driver does not need, not allowing the ISRs of other drivers to run
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@3018 ebee16cc-31ac-478f-84a7-5cbb03baadba
Needed to clear the NACK flag in the ISR, or the next transfers seem to get a nack too because the IRQ comes back
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@3017 ebee16cc-31ac-478f-84a7-5cbb03baadba
will need to be forward ported (and ideally pushed up stream) for FreeRTOS
updates
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2939 ebee16cc-31ac-478f-84a7-5cbb03baadba
- Removed all unnecessary device instances and their cfg's.
- SPI to SD card
- I2C
- Aux USART
- Moved SPI baudrate setting into cfg rather than init func.
- Abstracted forcing slave select under OPAHRS API.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2786 ebee16cc-31ac-478f-84a7-5cbb03baadba
order to free a timer. Mode PIOS_DELAY (not working cleanly) to TIM3 because
Spektrum resets TIM2 count.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2758 ebee16cc-31ac-478f-84a7-5cbb03baadba
because this is what is determines when the Stabilization code executes.
Because we aren't oversampling gyros relative to the PID in CC we should set
the attitude first (computational time to do so is negligible).
Also change update rate to 500 Hz.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2750 ebee16cc-31ac-478f-84a7-5cbb03baadba
also increase the telem queue to decrease event errors (can be reverted later if
we need the memory back)
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2730 ebee16cc-31ac-478f-84a7-5cbb03baadba
functions to use it easily
Conflicts:
flight/Modules/Attitude/attitude.c
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2707 ebee16cc-31ac-478f-84a7-5cbb03baadba
The UAVObject initcall list is now automatically
generated at link time based on the exact set of
UAVObjects linked into the firmware image.
This will allow any subset of UAVObjects to be
used in any firmware image.
The uavobj_initcall() macro automatically adds the
marked function's address into the .initcalluavobj.init
ELF section.
The UAVObjectsInitializeAll() function now simply
iterates over the functions listed in the
.initcalluavobj.init section and calls them.
You can see the contents of this section in the ELF file
like this:
./tools/arm-2009q3/bin/arm-none-eabi-objdump \
--syms -j .initcalluavobj.init \
./build/openpilot/OpenPilot.elf
This is fundamentally the same mechanism that the Linux
kernel uses to initialize the specific set of components
that the user has selected in their kernel configuration.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2630 ebee16cc-31ac-478f-84a7-5cbb03baadba
only one CS line is asserted. No checks are enforced on this by the SPI code
as I cant see a clean way of it being aware of the CS lines. We could add
another CS mode those which is driver managed per transfer and has a GPIO i
line for each device.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2579 ebee16cc-31ac-478f-84a7-5cbb03baadba
Beginning of unifying the input types into PIOS_RECEIVER.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2568 ebee16cc-31ac-478f-84a7-5cbb03baadba
accounting for the fact they are transferred in pairs when using ADC2
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2510 ebee16cc-31ac-478f-84a7-5cbb03baadba
gyro data into attitude raw. Hardcoded calibration for now.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2474 ebee16cc-31ac-478f-84a7-5cbb03baadba
semaphores for sharing the bus between the flash chip and this though.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2473 ebee16cc-31ac-478f-84a7-5cbb03baadba
1) Added nack counter monitoring
2) Made timeout for getting semaphore in I2C user space code use the one from
driver and record timeouts. This does not influence timeouts in the non
FreeRTOS case
3) Remove case block from the error handler so that all bus errors reset the
i2c interface
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2469 ebee16cc-31ac-478f-84a7-5cbb03baadba
projects which messed up a timer on OP and serial on PipX. Now this is only
changed for AHRS. Ideally wouldn't even change for that but then ADC runs too
fast and we get a lot more CRC errors for dealing with all that data.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2459 ebee16cc-31ac-478f-84a7-5cbb03baadba
size (may eventually need to be per revision if we get bigger ram). Typo in a
the ifdefs to get allow disabling SDCARD
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2423 ebee16cc-31ac-478f-84a7-5cbb03baadba
New naming convention for the linker files:
link_(board_name)_(density)_(bl usage).ld
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2401 ebee16cc-31ac-478f-84a7-5cbb03baadba
are logged, and separately the erirq and evirq logs are exported
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2368 ebee16cc-31ac-478f-84a7-5cbb03baadba
ActuatorSettings although for PWM aircrafts it should be done exactly as before
Actuator: Store the update times and maximum update time
OP-14 I2C: Start tracking short history of events and states in driver for
logging
OP-237 Flight/Actuator: Support for I2C based ESCs
OP-237 MK_ESC: Send all four motors as one atomic transfer
OP-237 Flight/Actuator: Allow channels to be mapped to MK I2C interface. Currently
mixer channels are either PWM or MK but in the future this will change to
support more than 8 channels.
OP-16 PiOS/I2C: Further work to try and make I2C more stable, mstly special case
handline in IRQ
OP-237 I2C ESC: Support for Astect 4 channel ESCs
OP-237: When the I2C Actuator write update fails track this
OP-237 Actuator Settings: Change the way motor types are selected to keep that
information more appropriately within ActuatorSettings instead of MixerSettings
Also make motors stay at or above neutral when armed and throttle > 0
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2366 ebee16cc-31ac-478f-84a7-5cbb03baadba
tasks directly update a flag for each module (which they register) and when all
flags set clear the watchdog then.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2365 ebee16cc-31ac-478f-84a7-5cbb03baadba
priority preempts) and adjusting the priorities around to be more sensible.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2355 ebee16cc-31ac-478f-84a7-5cbb03baadba
but not having telemetry causes a reset. If the buffer got full enough it
would never start to transmit again.
Note: also making Telemetry non-blocking
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2346 ebee16cc-31ac-478f-84a7-5cbb03baadba
before because if transmission got NAK then sending would stop. Now the next
time data is added to the buffer a new send will be attempted.
fifoBuf: in clearData just set the read pointer to the write pointer. This is
safer for multiple people accessing it assuming the reader will be clearing it.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2279 ebee16cc-31ac-478f-84a7-5cbb03baadba
required for longer sequences, Need to deal with when it happens
inappropriately better.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2245 ebee16cc-31ac-478f-84a7-5cbb03baadba
sometimes thrown, and made errors not lock it up by default. It works for me,
but since this has historically been associated with lots of lock ups please
check your systems carefully.
PiOS/I2C: Make the bus by default try to recover from errors instead of locking
up
PiOS/I2C: After a bus error and clocking all previous data create a STOP
condition to make sure bus is released (note, this also requires creating a
START condition first)
PiOS/I2C: If the same event hits the I2C bus twice in a row then disregard
second one, there is no situation where we should get the same event multiple
times that matters and this gets us out really quickly to catch the real
events. I was seeing this with repeated 0x70084 which means byte transmitted.
This is related to STM32 bugs in the IRQ timings I believe.
PiOS/I2C: 1) Mask out some bits we don't care about in the event flags
2) Don't lock up if the give semaphore fails, although why it does is strange
3) Recover from bus failure through the "auto" state path instead of just
coding state
PiOS/I2C: Change the reset bus code to follow
http://www.analog.com/static/imported-files/application_notes/54305147357414AN686_0.pdf
(thanks for the reference Neontangerine). Although this may actually NOT clear
the bus the first time through, subsequent bus errors should eventually clock
it out. The up side is it is less likely to clock a bunch of 1s into an ESC
and make it run up.
PiOS/I2C: Some cleaned up code for getting a snippet of the history when
something strange happens
PiOS/I2C: Export logging information from I2C through a UAV object
PiOS/I2C: Improve the diagnostic information
PiOS/I2C: Need to handle the event 0x30084. This seems to happen between a
byte transmitted and new byte started
PiOS/I2C: Handle the NACK condition by simply going to the stopping state.
PiOS/I2C: Add a new NACK state to handle sending the STOP signal after a NACK
following the STM documentation. Other error conditions still are not dealt
with.
PiOS/I2C: Should handle the NACK condition from all the write cases. Need to
think about read cases
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2239 ebee16cc-31ac-478f-84a7-5cbb03baadba
and starting transmission again. This should address the bootloader locking up
on verify.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2235 ebee16cc-31ac-478f-84a7-5cbb03baadba
configuration structures are const which keeps them in flash instead of ram.
However the library needs to declare them const for the compiler to work.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2231 ebee16cc-31ac-478f-84a7-5cbb03baadba
from the AHRS code (which will facilitate code integration with new INS) and
also will help set up a fifo queue for the downsampled data to allow gyro data
output from AHRS faster than EKF output. Also decreased ADC interrupt priority
so the SPI comms don't drop out.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2190 ebee16cc-31ac-478f-84a7-5cbb03baadba
only one receive task. This is less generally safe but decreases the
frequency of resets in our current configuration
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2144 ebee16cc-31ac-478f-84a7-5cbb03baadba
similar driver format to the PIOS_USART system. (p.s. are you happy now, PT?)
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2029 ebee16cc-31ac-478f-84a7-5cbb03baadba
running and block the interrupts while modifying the buffers
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2003 ebee16cc-31ac-478f-84a7-5cbb03baadba
Flight: Create PositionDesired (the active waypoint) UAVObject and make the FlightSituationActual no update since it not used.
Flight: New velocity desired object that passes information between the look computing the desired velocity and the PID loop to get it (updated at different rates)
UAVObjects/PositionActual: Remove unused GPS fields
UAVObjects/PositionActual VelocityActual: Split the velocity into a separate object. ALso make sure all the information telemetered around is in cm to avoid using floats.
UAVObject/GuidanceSettings: New guidance settings object for the guidance module
Flight/Posix: Add the new objects to the Posix sim
Flight/Guidance: Computes a desired velocity based on position error than runs a PID loop to control roll and pitch to achieve that velocity. All distances are in cm, and updated the PositionActual fields to reflect this and use int32.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1760 ebee16cc-31ac-478f-84a7-5cbb03baadba
determine retransmitting calibration, home location and such.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1755 ebee16cc-31ac-478f-84a7-5cbb03baadba
Calibration should take less time now too (using second moments to estimate
variance in one pass). Now need to change to multiple messages to get the
calibration in to keep the request message size minimal. Also currently
running sensor calibrate doesn't store the gyro bias so if you want to use this
you'll have to tweak it manually. I'll fix that step tomorrow.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1741 ebee16cc-31ac-478f-84a7-5cbb03baadba
Way too much was being exposed in the API for the
HMC5843. This commit properly hides internal
details of the driver.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1629 ebee16cc-31ac-478f-84a7-5cbb03baadba
The DRDY signal from the magnetometer is connected to PB8
on the STM32. This pin is now configured as an external
interrupt and is now used to signal when new data is
available from the magnetometer.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1628 ebee16cc-31ac-478f-84a7-5cbb03baadba
I2C bus errors are now recoverable. The bus is properly reset
and an error indication is now provided to the caller whenever
a bus error occurs during processing of the transaction list.
For now, the users of the I2C layer just retry infinitely on
failure. The BMP085 and HMC5843 code should be changed to
report errors to its callers to allow a more sensible retry
strategy.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1625 ebee16cc-31ac-478f-84a7-5cbb03baadba
AUTO transitions in the FSM are now handled immediately
after processing each newly injected event rather than only
at the end of the EV ISR.
This consolidation allows the upcoming addition of event
injection from both the EV and ER ISR contexts.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1624 ebee16cc-31ac-478f-84a7-5cbb03baadba
Occasionally, the I2C driver races with the STM32 I2C peripheral
at the end of a bus cycle. This leaves the bus in an errored
state and the stop condition is not properly asserted on the bus.
The polling for the stopped condition was previously implemented
in ISR context since it was expected to be nearly instananeous.
In the error condition, however, the stop condition will never
happen. The polling for this case is now done by the initiating
task (or mainloop on the AHRS) to prevent the timeout condition
from triggering the watchdog.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1623 ebee16cc-31ac-478f-84a7-5cbb03baadba
The info field in the pios_i2c_txn list can now be used
to provide a const string which describes the context
for this transaction.
This is very helpful when diagnosing an error that occurs
somewhere in the middle of the I2C FSM since the FSM runs
primarily in the ISR where the original context for the
transactions is no longer available in the traceback.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1622 ebee16cc-31ac-478f-84a7-5cbb03baadba
Differentiate the _FSM_ faulted from the (soon to
exist _BUS_ faulted state.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1621 ebee16cc-31ac-478f-84a7-5cbb03baadba
Implement low-level utility functions for sending/receiving
the opahrs proto v0 (bootloader) messages. These are used
by the OP firmware loader and the AHRS bootloader.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1586 ebee16cc-31ac-478f-84a7-5cbb03baadba
Some functions were returning -1 instead of one of the
valud enum values.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1585 ebee16cc-31ac-478f-84a7-5cbb03baadba
This cleans up some of the boiler plate code that is
repeasted for simple (empty) requests that expect a
response.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1584 ebee16cc-31ac-478f-84a7-5cbb03baadba
The number of retries and delay between retries was
increased in a previous commit. This doesn't appear
to be necessary so I'm reverting the increases.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1432 ebee16cc-31ac-478f-84a7-5cbb03baadba
No functional changes. Whitespace/tab fixups only.
Use TRUE/FALSE instead of 1/0.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1430 ebee16cc-31ac-478f-84a7-5cbb03baadba
No need to have boolean flags being floats.
Some of the attitude message was being populated twice.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1428 ebee16cc-31ac-478f-84a7-5cbb03baadba
1. Added reenumeration function and call it on USB init (device will appear after reprogramming now)
2. Moved buffer.c to general flight/Libraries location
3. Removed the 62 byte transmission limitation by adding a transmission buffer
4. Sped up USB communication by increasing endpoint polling frequency
Note, that the nonblocking and blocking USB send functions are not blocking entirely correcting. The blocking calls the nonblocking, and the nonblocking blocks until the last chunk has started tranmission if it's a big transmission. The buffering I added would generalize to non-blocking nicely, but would require using the EP1(IN) callback to handle most of the tranmission. This creates a lot of issues if one function is pushing data onto the buffer and the interrupt is sending.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1403 ebee16cc-31ac-478f-84a7-5cbb03baadba
Issues have been reported with CRC errors
on the SPI link between the OP and AHRS
boards. Slowing the link down eliminates
the errors in my testing.
If we speed this link back up in the future,
further investigation will be required to
diagnose the source of the CRC errors.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1356 ebee16cc-31ac-478f-84a7-5cbb03baadba
This file had mixed line endings. Now they're all the same.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1353 ebee16cc-31ac-478f-84a7-5cbb03baadba
This is to align the object names to matches the UAVObject
architecture doc. No functional changes.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1351 ebee16cc-31ac-478f-84a7-5cbb03baadba
The transition from the ADDR state to the read state
was broken for non-final reads. The FSM diagram was
also wrong for this transition.
Since reads are always the last transaction in a sequence
in our current usage, this doesn't actually fix any known
bugs.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1350 ebee16cc-31ac-478f-84a7-5cbb03baadba
Since the i2c bus is bidirectional, there are certain
states (eg. part way through a read) where the slave
device is in control of driving the SDA line.
On a cold start (power on), the slave devices are all
quiescent and will not drive the bus. However, on a warm
start (eg. watchdog or jtag restart), it is possible that as
the CPU boots, the slave device may be holding the SDA line
low. This is a bus busy condition and will prevent the I2C
bus master in the CPU from being able to seize the bus during
init.
The fix for this is to clock the i2c bus sufficiently to ensure
that the the slave device finishes its transaction and releases
the bus.
Once the slave has released the bus, the bus master can properly
initialize and assert a STOP condition on the bus.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1349 ebee16cc-31ac-478f-84a7-5cbb03baadba
into NED reference frame and used in the INSGPS algorithm, although currently this
information isn't propagated back to OP. Data structures related to the GPS position
into the algorithm and the position estimate out will likely be in flux.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1334 ebee16cc-31ac-478f-84a7-5cbb03baadba
Altitude/pressure sensor data is sent to the AHRS whenever
the AltitudeActual object is updated.
Altitude, Pressure and Temperature are sent as floats.
Same as in the UAVObject that goes to the GCS.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1291 ebee16cc-31ac-478f-84a7-5cbb03baadba
The STM32 I2C block has a number of errata associated with it.
These errata are primarily related to timing sensitivities between
the peripheral and the interrupt handler. In particular, the
correct generation of the stop bit relies on the I2C IRQ running
immediately and not being held off for any reason.
NOTE: The I2C interrupts must be the highest priority IRQs in the
system to ensure correct operation.
I2C protocol is now implemented as a formal state machine.
See: stm32_i2c_fsm.{dot,jpg} for FSM description.
I2C init is now expressed by const initializers in pios_board.c
for both OP and AHRS boards.
I2C device drivers (ie. bmp085/hmc5843) now pass in const arrays
of an unlimited number of bus transfers to be done atomically.
The I2C adapter driver now handles all bus-level locking across the
list of transactions. Generation of start/restart/stop conditions
are handled automatically over the list of transactions.
Timeouts have been removed from the API for now. May be added
back later.
This driver has run error free on both the OP and AHRS boards for
up to 48hrs but it still sometimes fails earlier than that on the OP
board. There is another possible set of improvements to the driver
that could employ the DMA engine for transfers of >= 2bytes. This
change would reduce the timing sensitivities between the peripheral
and the driver but unfortunately, both the SPI and I2C interfaces
share the DMA1 engine. That means only one of these two peripherals
can use the DMA engine and right now, SPI between OP and AHRS is
already using it.
Failures are currently fatal and will lock up the CPU. This allows
useful information to be obtained in the failure cases.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1241 ebee16cc-31ac-478f-84a7-5cbb03baadba
Mark the I2C_InitStruct parameter as const so that we can pass
const data as the initializer.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1240 ebee16cc-31ac-478f-84a7-5cbb03baadba