AP_HAL_FLYMAPLE: I2CDriver now uses low level hardware i2c librray from

libmaple

CAUTION: requires a patched version of libmaple, to be provided by mikem.
This commit is contained in:
Mike McCauley 2013-10-03 17:34:32 +10:00 committed by Andrew Tridgell
parent 68a7cac9a2
commit 2d3c86ee80
3 changed files with 104 additions and 31 deletions

View File

@ -86,14 +86,15 @@ SysTick 1000Hz normal timers
3 CH1-4, 4 CH1-2 RCOut
8 not used by AP
AP I2CDriver on Flymaple uses the libmaple Wire library, configured to clock
at about 200kHz. The maximum possible Flymaple could support speed is limited
by the BMP085 barometer to 400kHz.
Current version of the Wire library is unfortunately
bit-banged. This may change in the future.
The I2CDriver on Flymaple uses the libmaple i2c low level hardware I2C
library, configuredfor high speed (400kHz).
At 200kHz I2C speed, it takes 500us to read the 6 byte accelerometer
buffer, and 500us to read the 6 byte gyro buffer.
As at 2013-10-03, there is a bug in the libmaple git master code, that causes
a crash in the I2C interrupt handler. Therfore it is necessary to use the
patched version of libmaple referred to below.
At 400kHz I2C speed, it takes 500us to read both the 6 byte accelerometer
buffer and the the 6 byte gyro buffer.
The SerialUSB (USB connection) to Flymaple is not used by AP. It can be used for
debugging inside AP_HAL_FLYMAPLE, using SerialUSB.println().
@ -109,10 +110,14 @@ per sec
ITG3205 Gyro
2000 degrees/sec, 256Hz LPF, 8kHz internal sample rate, read at 1kHz sample rate
The gyro and accelerometers are sampled at about 800Hz in
AP_InertialSensor_Flymaple.cpp, with the samples passed through a software
2-pole low pass filter, to produce filtered data for the main loop.
Installation on Linux
Tested with:
libmaple https://github.com/leaflabs/libmaple http://leaflabs.com/docs/unix-toolchain.html
libmaple patched library based on https://github.com/leaflabs/libmaple http://leaflabs.com/docs/unix-toolchain.html
arm-none-eabi-g++ toolchain, version 4.4.1
on OpenSuSE 12.3
Mission Planner 1.2.78
@ -122,7 +127,8 @@ have assumed that you will install them in your home directory, but they can rea
go anywhere provided you make the appropriate changes
cd ~
git clone https://github.com/leaflabs/libmaple.git
git clone https://github.com/leaflabs/libmaple.git NO THIS IS WRONG: need
mikems patched version
cd libmaple
wget http://static.leaflabs.com/pub/codesourcery/gcc-arm-none-eabi-latest-linux32.tar.gz
tar xvzf gcc-arm-none-eabi-latest-linux32.tar.gz

View File

@ -23,28 +23,45 @@
#include "I2CDriver.h"
#include "FlymapleWirish.h"
#include <Wire.h>
using namespace AP_HAL_FLYMAPLE_NS;
// We use a 0 delay to go as fast as we can with bitbanging
static TwoWire twowire(5, 9, 0); // Flymaple has non-standard SCL, SDA, speed ~285kHz
//static TwoWire twowire(5, 9, 0); // Flymaple has non-standard SCL, SDA, speed ~285kHz
extern const AP_HAL::HAL& hal;
// This is the instancxe of the libmaple I2C device to use
#define FLYMAPLE_I2C_DEVICE I2C1
FLYMAPLEI2CDriver::FLYMAPLEI2CDriver(AP_HAL::Semaphore* semaphore)
: _semaphore(semaphore),
_timeout_ms(0)
{
}
void FLYMAPLEI2CDriver::begin()
{
twowire.begin();
_reset();
}
void FLYMAPLEI2CDriver::end() {}
void FLYMAPLEI2CDriver::setTimeout(uint16_t ms) {}
void FLYMAPLEI2CDriver::setTimeout(uint16_t ms)
{
_timeout_ms = ms;
}
void FLYMAPLEI2CDriver::setHighSpeed(bool active) {}
uint8_t FLYMAPLEI2CDriver::write(uint8_t addr, uint8_t len, uint8_t* data)
{
twowire.beginTransmission(addr);
twowire.send(data, len);
uint8_t result = twowire.endTransmission();
return result;
i2c_msg msgs[1];
msgs[0].addr = addr;
msgs[0].flags = 0; // Write
msgs[0].length = len;
msgs[0].data = data;
return _transfer(msgs, 1);
}
uint8_t FLYMAPLEI2CDriver::writeRegister(uint8_t addr, uint8_t reg, uint8_t val)
@ -55,20 +72,28 @@ uint8_t FLYMAPLEI2CDriver::writeRegister(uint8_t addr, uint8_t reg, uint8_t val)
uint8_t FLYMAPLEI2CDriver::writeRegisters(uint8_t addr, uint8_t reg,
uint8_t len, uint8_t* data)
{
twowire.beginTransmission(addr);
twowire.send(reg);
if (len)
twowire.send(data, len);
uint8_t result = twowire.endTransmission();
return result;
uint8_t buffer[100];
buffer[0] = reg;
memcpy(buffer+1, data, len);
i2c_msg msgs[1];
msgs[0].addr = addr;
msgs[0].flags = 0; // Write
msgs[0].length = len + 1;
msgs[0].data = buffer;
return _transfer(msgs, 1);
}
uint8_t FLYMAPLEI2CDriver::read(uint8_t addr, uint8_t len, uint8_t* data)
{
uint8_t actual_len = twowire.requestFrom(addr, len);
for (uint8_t i = 0; i < actual_len; i++)
*data++ = twowire.receive();
return actual_len != len;
// For devices that do not honour normal register conventions (not on flymaple?)
// Now read it
i2c_msg msgs[1];
msgs[0].addr = addr;
msgs[0].flags = I2C_MSG_READ;
msgs[0].length = len;
msgs[0].data = data;
return _transfer(msgs, 1);
}
uint8_t FLYMAPLEI2CDriver::readRegister(uint8_t addr, uint8_t reg, uint8_t* data)
@ -79,10 +104,46 @@ uint8_t FLYMAPLEI2CDriver::readRegister(uint8_t addr, uint8_t reg, uint8_t* data
uint8_t FLYMAPLEI2CDriver::readRegisters(uint8_t addr, uint8_t reg,
uint8_t len, uint8_t* data)
{
writeRegisters(addr, reg, 0, NULL); // Tell device which register we want
return read(addr, len, data);
// Write the desired register we wish to read
data[0] = reg; // Temp steal this
i2c_msg msgs[1];
msgs[0].addr = addr;
msgs[0].flags = 0; // Write
msgs[0].length = 1;
msgs[0].data = data;
if (_transfer(msgs, 1))
return 1; // Fail
// Now read it
msgs[0].addr = addr;
msgs[0].flags = I2C_MSG_READ;
msgs[0].length = len;
msgs[0].data = data;
return _transfer(msgs, 1);
}
uint8_t FLYMAPLEI2CDriver::lockup_count() {return 0;}
uint8_t FLYMAPLEI2CDriver::lockup_count() {
return _lockup_count;
}
uint8_t FLYMAPLEI2CDriver::_transfer(i2c_msg *msgs, uint16 num)
{
// ALERT: patch to libmaple required for this to work else
// crashes next line due to a bug in latest git libmaple see http://forums.leaflabs.com/topic.php?id=13458
int32 result = i2c_master_xfer(I2C1, msgs, 1, _timeout_ms);
if (result != 0)
{
// Some sort of I2C bus fault, or absent device, reinitialise the bus
_reset();
_lockup_count++;
}
return result != 0;
}
void FLYMAPLEI2CDriver::_reset()
{
i2c_disable(FLYMAPLE_I2C_DEVICE);
i2c_master_enable(FLYMAPLE_I2C_DEVICE, I2C_FAST_MODE | I2C_BUS_RESET);
}
#endif

View File

@ -21,9 +21,11 @@
#include <AP_HAL_FLYMAPLE.h>
#include <i2c.h>
class AP_HAL_FLYMAPLE_NS::FLYMAPLEI2CDriver : public AP_HAL::I2CDriver {
public:
FLYMAPLEI2CDriver(AP_HAL::Semaphore* semaphore) : _semaphore(semaphore) {}
FLYMAPLEI2CDriver(AP_HAL::Semaphore* semaphore);
void begin();
void end();
void setTimeout(uint16_t ms);
@ -52,7 +54,11 @@ public:
AP_HAL::Semaphore* get_semaphore() { return _semaphore; }
private:
uint8_t _lockup_count; // Bus error count
uint8_t _transfer(i2c_msg *msgs, uint16 num);
void _reset(); // Bus and device reset
AP_HAL::Semaphore* _semaphore;
uint16_t _timeout_ms;
};
#endif // __AP_HAL_FLYMAPLE_I2CDRIVER_H__