Reduced scope of many variables since they were being
exposed unnecessarily.
Renamed pios_usb_hid_prop code to pios_usbhook to reflect
the fact that it implements all of the callout functions
that are hooked into the stm32 usb library.
No code changes, just file, variable and define names are changed.
First, it better describes the serial protocol used by DSMx satellite
receivers. Second, many people using Spektrum radio, assume Spektrum
protocol. This is the attempt to address those inaccuracies.
- 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).
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.
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.
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.
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.
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.
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.
- 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)
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.
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.
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
- 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
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
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
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
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
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
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
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
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
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
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