NOT FINISHED YET!!! My first try to get a self built fully working Quadrocopter based on an mbed, a self built frame and some other more or less cheap parts.
Revision 2:93f703d2c4d7, committed 2012-10-02
- Comitter:
- maetugr
- Date:
- Tue Oct 02 17:53:40 2012 +0000
- Parent:
- 1:5a64632b1eb9
- Child:
- 3:a97f1d874f4e
- Commit message:
- erstes experiment mit funktionierendem filter (nur eine Achse und noch nicht optimal)
Changed in this revision
--- a/LCD/LCD.h Fri Sep 28 13:24:03 2012 +0000 +++ b/LCD/LCD.h Tue Oct 02 17:53:40 2012 +0000 @@ -2,8 +2,8 @@ * Copyright (c) 2007-2010, hb9gaa */ -#ifndef __LCD_H -#define __LCD_H +#ifndef LCD_H +#define LCD_H #include "mbed.h"
--- a/LED/LED.h Fri Sep 28 13:24:03 2012 +0000 +++ b/LED/LED.h Tue Oct 02 17:53:40 2012 +0000 @@ -1,7 +1,7 @@ // by MaEtUgR -#ifndef __LED_H -#define __LED_H +#ifndef LED_H +#define LED_H #include "mbed.h"
--- a/Sensors/Acc/ADXL345.cpp Fri Sep 28 13:24:03 2012 +0000 +++ b/Sensors/Acc/ADXL345.cpp Tue Oct 02 17:53:40 2012 +0000 @@ -1,379 +1,86 @@ -#include "ADXL345.h" -#include "mbed.h" - -ADXL345::ADXL345(PinName sda, PinName scl) : i2c_(sda, scl) { - - //400kHz, allowing us to use the fastest data rates. - //there are other chips on board, sorry - i2c_.frequency(400000); -// initialize the BW data rate - char tx[2]; - tx[0] = ADXL345_BW_RATE_REG; - tx[1] = ADXL345_1600HZ; //value greater than or equal to 0x0A is written into the rate bits (Bit D3 through Bit D0) in the BW_RATE register - i2c_.write( ADXL345_WRITE , tx, 2); - -//Data format (for +-16g) - This is done by setting Bit D3 of the DATA_FORMAT register (Address 0x31) and writing a value of 0x03 to the range bits (Bit D1 and Bit D0) of the DATA_FORMAT register (Address 0x31). - - char rx[2]; - rx[0] = ADXL345_DATA_FORMAT_REG; - rx[1] = 0x0B; - // full res and +_16g - i2c_.write( ADXL345_WRITE , rx, 2); - - // Set Offset - programmed into the OFSX, OFSY, and OFXZ registers, respectively, as 0xFD, 0x03 and 0xFE. - char x[2]; - x[0] = ADXL345_OFSX_REG ; - x[1] = 0xFD; - i2c_.write( ADXL345_WRITE , x, 2); - char y[2]; - y[0] = ADXL345_OFSY_REG ; - y[1] = 0x03; - i2c_.write( ADXL345_WRITE , y, 2); - char z[2]; - z[0] = ADXL345_OFSZ_REG ; - z[1] = 0xFE; - i2c_.write( ADXL345_WRITE , z, 2); - - // MY INITIALISATION ------------------------------------------------------- - - setPowerControl(0x00); - setDataFormatControl(0x0B); - setDataRate(ADXL345_3200HZ); - setPowerControl(MeasurementMode); -} - - -char ADXL345::SingleByteRead(char address){ - char tx = address; - char output; - i2c_.write( ADXL345_WRITE , &tx, 1); //tell it what you want to read - i2c_.read( ADXL345_READ , &output, 1); //tell it where to store the data - return output; - -} - - -/* -***info on the i2c_.write*** -address 8-bit I2C slave address [ addr | 0 ] -data Pointer to the byte-array data to send -length Number of bytes to send -repeated Repeated start, true - do not send stop at end -returns 0 on success (ack), or non-0 on failure (nack) -*/ - -int ADXL345::SingleByteWrite(char address, char data){ - int ack = 0; - char tx[2]; - tx[0] = address; - tx[1] = data; - return ack | i2c_.write( ADXL345_WRITE , tx, 2); -} - - - -void ADXL345::multiByteRead(char address, char* output, int size) { - i2c_.write( ADXL345_WRITE, &address, 1); //tell it where to read from - i2c_.read( ADXL345_READ , output, size); //tell it where to store the data read -} - - -int ADXL345::multiByteWrite(char address, char* ptr_data, int size) { - int ack; - - ack = i2c_.write( ADXL345_WRITE, &address, 1); //tell it where to write to - return ack | i2c_.write( ADXL345_READ, ptr_data, size); //tell it what data to write - -} - - -void ADXL345::getOutput(int* readings){ - char buffer[6]; - multiByteRead(ADXL345_DATAX0_REG, buffer, 6); - - readings[0] = (int)buffer[1] << 8 | (int)buffer[0]; - readings[1] = (int)buffer[3] << 8 | (int)buffer[2]; - readings[2] = (int)buffer[5] << 8 | (int)buffer[4]; - -} - - - -char ADXL345::getDeviceID() { - return SingleByteRead(ADXL345_DEVID_REG); - } -// -int ADXL345::setPowerMode(char mode) { - - //Get the current register contents, so we don't clobber the rate value. - char registerContents = (mode << 4) | SingleByteRead(ADXL345_BW_RATE_REG); - - return SingleByteWrite(ADXL345_BW_RATE_REG, registerContents); - -} - -char ADXL345::getPowerControl() { - return SingleByteRead(ADXL345_POWER_CTL_REG); -} - -int ADXL345::setPowerControl(char settings) { - return SingleByteWrite(ADXL345_POWER_CTL_REG, settings); - -} - - - -char ADXL345::getDataFormatControl(void){ - - return SingleByteRead(ADXL345_DATA_FORMAT_REG); -} - -int ADXL345::setDataFormatControl(char settings){ - - return SingleByteWrite(ADXL345_DATA_FORMAT_REG, settings); - -} - -int ADXL345::setDataRate(char rate) { - - //Get the current register contents, so we don't clobber the power bit. - char registerContents = SingleByteRead(ADXL345_BW_RATE_REG); - - registerContents &= 0x10; - registerContents |= rate; - - return SingleByteWrite(ADXL345_BW_RATE_REG, registerContents); - -} - - -char ADXL345::getOffset(char axis) { - - char address = 0; - - if (axis == ADXL345_X) { - address = ADXL345_OFSX_REG; - } else if (axis == ADXL345_Y) { - address = ADXL345_OFSY_REG; - } else if (axis == ADXL345_Z) { - address = ADXL345_OFSZ_REG; - } - - return SingleByteRead(address); -} - -int ADXL345::setOffset(char axis, char offset) { - - char address = 0; - - if (axis == ADXL345_X) { - address = ADXL345_OFSX_REG; - } else if (axis == ADXL345_Y) { - address = ADXL345_OFSY_REG; - } else if (axis == ADXL345_Z) { - address = ADXL345_OFSZ_REG; - } - - return SingleByteWrite(address, offset); - -} - - -char ADXL345::getFifoControl(void){ - - return SingleByteRead(ADXL345_FIFO_CTL); - -} - -int ADXL345::setFifoControl(char settings){ - return SingleByteWrite(ADXL345_FIFO_STATUS, settings); - -} - -char ADXL345::getFifoStatus(void){ - - return SingleByteRead(ADXL345_FIFO_STATUS); - -} - - - -char ADXL345::getTapThreshold(void) { - - return SingleByteRead(ADXL345_THRESH_TAP_REG); -} - -int ADXL345::setTapThreshold(char threshold) { - - return SingleByteWrite(ADXL345_THRESH_TAP_REG, threshold); - -} - - -float ADXL345::getTapDuration(void) { - - return (float)SingleByteRead(ADXL345_DUR_REG)*625; -} - -int ADXL345::setTapDuration(short int duration_us) { - - short int tapDuration = duration_us / 625; - char tapChar[2]; - tapChar[0] = (tapDuration & 0x00FF); - tapChar[1] = (tapDuration >> 8) & 0x00FF; - return multiByteWrite(ADXL345_DUR_REG, tapChar, 2); - -} - -float ADXL345::getTapLatency(void) { - - return (float)SingleByteRead(ADXL345_LATENT_REG)*1.25; -} - -int ADXL345::setTapLatency(short int latency_ms) { - - latency_ms = latency_ms / 1.25; - char latChar[2]; - latChar[0] = (latency_ms & 0x00FF); - latChar[1] = (latency_ms << 8) & 0xFF00; - return multiByteWrite(ADXL345_LATENT_REG, latChar, 2); - -} - -float ADXL345::getWindowTime(void) { - - return (float)SingleByteRead(ADXL345_WINDOW_REG)*1.25; -} - -int ADXL345::setWindowTime(short int window_ms) { - - window_ms = window_ms / 1.25; - char windowChar[2]; - windowChar[0] = (window_ms & 0x00FF); - windowChar[1] = ((window_ms << 8) & 0xFF00); - return multiByteWrite(ADXL345_WINDOW_REG, windowChar, 2); - -} - -char ADXL345::getActivityThreshold(void) { - - return SingleByteRead(ADXL345_THRESH_ACT_REG); -} - -int ADXL345::setActivityThreshold(char threshold) { - return SingleByteWrite(ADXL345_THRESH_ACT_REG, threshold); - -} - -char ADXL345::getInactivityThreshold(void) { - return SingleByteRead(ADXL345_THRESH_INACT_REG); - -} - -//int FUNCTION(short int * ptr_Output) -//short int FUNCTION () - -int ADXL345::setInactivityThreshold(char threshold) { - return SingleByteWrite(ADXL345_THRESH_INACT_REG, threshold); - -} - -char ADXL345::getTimeInactivity(void) { - - return SingleByteRead(ADXL345_TIME_INACT_REG); - -} - -int ADXL345::setTimeInactivity(char timeInactivity) { - return SingleByteWrite(ADXL345_TIME_INACT_REG, timeInactivity); - -} - -char ADXL345::getActivityInactivityControl(void) { - - return SingleByteRead(ADXL345_ACT_INACT_CTL_REG); - -} - -int ADXL345::setActivityInactivityControl(char settings) { - return SingleByteWrite(ADXL345_ACT_INACT_CTL_REG, settings); - -} - -char ADXL345::getFreefallThreshold(void) { - - return SingleByteRead(ADXL345_THRESH_FF_REG); - -} - -int ADXL345::setFreefallThreshold(char threshold) { - return SingleByteWrite(ADXL345_THRESH_FF_REG, threshold); - -} - -char ADXL345::getFreefallTime(void) { - - return SingleByteRead(ADXL345_TIME_FF_REG)*5; - -} - -int ADXL345::setFreefallTime(short int freefallTime_ms) { - freefallTime_ms = freefallTime_ms / 5; - char fallChar[2]; - fallChar[0] = (freefallTime_ms & 0x00FF); - fallChar[1] = (freefallTime_ms << 8) & 0xFF00; - - return multiByteWrite(ADXL345_TIME_FF_REG, fallChar, 2); - -} - -char ADXL345::getTapAxisControl(void) { - - return SingleByteRead(ADXL345_TAP_AXES_REG); - -} - -int ADXL345::setTapAxisControl(char settings) { - return SingleByteWrite(ADXL345_TAP_AXES_REG, settings); - -} - -char ADXL345::getTapSource(void) { - - return SingleByteRead(ADXL345_ACT_TAP_STATUS_REG); - -} - - - -char ADXL345::getInterruptEnableControl(void) { - - return SingleByteRead(ADXL345_INT_ENABLE_REG); - -} - -int ADXL345::setInterruptEnableControl(char settings) { - return SingleByteWrite(ADXL345_INT_ENABLE_REG, settings); - -} - -char ADXL345::getInterruptMappingControl(void) { - - return SingleByteRead(ADXL345_INT_MAP_REG); - -} - -int ADXL345::setInterruptMappingControl(char settings) { - return SingleByteWrite(ADXL345_INT_MAP_REG, settings); - -} - -char ADXL345::getInterruptSource(void){ - - return SingleByteRead(ADXL345_INT_SOURCE_REG); - -} - - - - +#include "ADXL345.h" +#include "mbed.h" + +ADXL345::ADXL345(PinName sda, PinName scl) : i2c(sda, scl) { + + //400kHz, allowing us to use the fastest data rates. + //there are other chips on board, sorry + i2c.frequency(400000); + // initialize the BW data rate + char tx[2]; + tx[0] = ADXL345_BW_RATE_REG; + tx[1] = ADXL345_1600HZ; //value greater than or equal to 0x0A is written into the rate bits (Bit D3 through Bit D0) in the BW_RATE register + i2c.write( ADXL345_WRITE , tx, 2); + + //Data format (for +-16g) - This is done by setting Bit D3 of the DATA_FORMAT register (Address 0x31) and writing a value of 0x03 to the range bits (Bit D1 and Bit D0) of the DATA_FORMAT register (Address 0x31). + + char rx[2]; + rx[0] = ADXL345_DATA_FORMAT_REG; + rx[1] = 0x0B; + // full res and +_16g + i2c.write( ADXL345_WRITE , rx, 2); + + // Set Offset - programmed into the OFSX, OFSY, and OFXZ registers, respectively, as 0xFD, 0x03 and 0xFE. + char x[2]; + x[0] = ADXL345_OFSX_REG ; + //x[1] = 0xFD; + x[1] = 0x00; + i2c.write( ADXL345_WRITE , x, 2); + char y[2]; + y[0] = ADXL345_OFSY_REG ; + //y[1] = 0x03; + y[1] = 0x00; + i2c.write( ADXL345_WRITE , y, 2); + char z[2]; + z[0] = ADXL345_OFSZ_REG ; + //z[1] = 0xFE; + z[1] = 0x00; + i2c.write( ADXL345_WRITE , z, 2); + + // MY INITIALISATION ------------------------------------------------------- + + writeReg(ADXL345_POWER_CTL_REG, 0x00); // set power control + writeReg(ADXL345_DATA_FORMAT_REG, 0x0B); // set data format + setDataRate(ADXL345_3200HZ); // set data rate + writeReg(ADXL345_POWER_CTL_REG, 0x08); // set mode +} + +void ADXL345::read(int a[3]){ + char buffer[6]; + readMultiReg(ADXL345_DATAX0_REG, buffer, 6); + + a[0] = (short) ((int)buffer[1] << 8 | (int)buffer[0]); + a[1] = (short) ((int)buffer[3] << 8 | (int)buffer[2]); + a[2] = (short) ((int)buffer[5] << 8 | (int)buffer[4]); +} + +int ADXL345::writeReg(char address, char data){ + int ack = 0; + char tx[2]; + tx[0] = address; + tx[1] = data; + return ack | i2c.write(ADXL345_WRITE, tx, 2); +} + +char ADXL345::readReg(char address){ + char tx = address; + char output; + i2c.write( ADXL345_WRITE , &tx, 1); //tell it what you want to read + i2c.read( ADXL345_READ , &output, 1); //tell it where to store the data + return output; +} + +void ADXL345::readMultiReg(char address, char* output, int size) { + i2c.write(ADXL345_WRITE, &address, 1); //tell it where to read from + i2c.read(ADXL345_READ , output, size); //tell it where to store the data read +} + +int ADXL345::setDataRate(char rate) { + //Get the current register contents, so we don't clobber the power bit. + char registerContents = readReg(ADXL345_BW_RATE_REG); + + registerContents &= 0x10; + registerContents |= rate; + + return writeReg(ADXL345_BW_RATE_REG, registerContents); +} \ No newline at end of file
--- a/Sensors/Acc/ADXL345.h Fri Sep 28 13:24:03 2012 +0000 +++ b/Sensors/Acc/ADXL345.h Tue Oct 02 17:53:40 2012 +0000 @@ -1,530 +1,84 @@ -// based on http://mbed.org/users/Digixx/code/ADXL345/ - -/* - * ADXL345, triple axis, I2C interface, accelerometer. - * - * Datasheet: - * - * http://www.analog.com/static/imported-files/data_sheets/ADXL345.pdf - */ - - - -#ifndef __ADXL345_H -#define __ADXL345_H - -#include "mbed.h" - -// register addresses -#define ADXL345_DEVID_REG 0x00 -#define ADXL345_THRESH_TAP_REG 0x1D -#define ADXL345_OFSX_REG 0x1E -#define ADXL345_OFSY_REG 0x1F -#define ADXL345_OFSZ_REG 0x20 -#define ADXL345_DUR_REG 0x21 -#define ADXL345_LATENT_REG 0x22 -#define ADXL345_WINDOW_REG 0x23 -#define ADXL345_THRESH_ACT_REG 0x24 -#define ADXL345_THRESH_INACT_REG 0x25 -#define ADXL345_TIME_INACT_REG 0x26 -#define ADXL345_ACT_INACT_CTL_REG 0x27 -#define ADXL345_THRESH_FF_REG 0x28 -#define ADXL345_TIME_FF_REG 0x29 -#define ADXL345_TAP_AXES_REG 0x2A -#define ADXL345_ACT_TAP_STATUS_REG 0x2B -#define ADXL345_BW_RATE_REG 0x2C -#define ADXL345_POWER_CTL_REG 0x2D -#define ADXL345_INT_ENABLE_REG 0x2E -#define ADXL345_INT_MAP_REG 0x2F -#define ADXL345_INT_SOURCE_REG 0x30 -#define ADXL345_DATA_FORMAT_REG 0x31 -#define ADXL345_DATAX0_REG 0x32 -#define ADXL345_DATAX1_REG 0x33 -#define ADXL345_DATAY0_REG 0x34 -#define ADXL345_DATAY1_REG 0x35 -#define ADXL345_DATAZ0_REG 0x36 -#define ADXL345_DATAZ1_REG 0x37 - -#define ADXL345_FIFO_CTL 0x38 -#define ADXL345_FIFO_STATUS 0x39 - -// data rate codes -#define ADXL345_3200HZ 0x0F -#define ADXL345_1600HZ 0x0E -#define ADXL345_800HZ 0x0D -#define ADXL345_400HZ 0x0C -#define ADXL345_200HZ 0x0B -#define ADXL345_100HZ 0x0A -#define ADXL345_50HZ 0x09 -#define ADXL345_25HZ 0x08 -#define ADXL345_12HZ5 0x07 -#define ADXL345_6HZ25 0x06 - -// read or write bytes -#define ADXL345_READ 0xA7 -#define ADXL345_WRITE 0xA6 -#define ADXL345_ADDRESS 0x53 - -//the ADXL345 7-bit address is 0x53 when ALT ADDRESS is low as it is on the sparkfun chip: when ALT ADDRESS is high the address is 0x1D - -//when ALT ADDRESS pin is high: -//#define ADXL345_READ 0x3B -//#define ADXL345_WRITE 0x3A -//#define ADXL345_ADDRESS 0x1D - -#define ADXL345_X 0x00 -#define ADXL345_Y 0x01 -#define ADXL345_Z 0x02 - -// modes -#define MeasurementMode 0x08 - - - - - - - -class ADXL345 { - -public: - - /** - * Constructor. - * - * @param mosi mbed pin to use for SDA line of I2C interface. - * @param sck mbed pin to use for SCL line of I2C interface. - */ - ADXL345(PinName sda, PinName scl); - - /** - * Get the output of all three axes. - * - * @param Pointer to a buffer to hold the accelerometer value for the - * x-axis, y-axis and z-axis [in that order]. - */ - void getOutput(int* readings); - - /** - * Read the device ID register on the device. - * - * @return The device ID code [0xE5] - */ - char getDeviceID(void); - - /** - * Set the power mode. - * - * @param mode 0 -> Normal operation. - * 1 -> Reduced power operation. - */ - int setPowerMode(char mode); - - /** - * Set the power control settings. - * - * See datasheet for details. - * - * @param The control byte to write to the POWER_CTL register. - */ - int setPowerControl(char settings); - /** - * Get the power control settings. - * - * See datasheet for details. - * - * @return The contents of the POWER_CTL register. - */ - char getPowerControl(void); - - - /** - * Get the data format settings. - * - * @return The contents of the DATA_FORMAT register. - */ - - char getDataFormatControl(void); - - /** - * Set the data format settings. - * - * @param settings The control byte to write to the DATA_FORMAT register. - */ - int setDataFormatControl(char settings); - - /** - * Set the data rate. - * - * @param rate The rate code (see #defines or datasheet). - */ - int setDataRate(char rate); - - - /** - * Get the current offset for a particular axis. - * - * @param axis 0x00 -> X-axis - * 0x01 -> Y-axis - * 0x02 -> Z-axis - * @return The current offset as an 8-bit 2's complement number with scale - * factor 15.6mg/LSB. - */ - - char getOffset(char axis); - - /** - * Set the offset for a particular axis. - * - * @param axis 0x00 -> X-axis - * 0x01 -> Y-axis - * 0x02 -> Z-axis - * @param offset The offset as an 8-bit 2's complement number with scale - * factor 15.6mg/LSB. - */ - int setOffset(char axis, char offset); - - /** - * Get the FIFO control settings. - * - * @return The contents of the FIFO_CTL register. - */ - char getFifoControl(void); - - /** - * Set the FIFO control settings. - * - * @param The control byte to write to the FIFO_CTL register. - */ - int setFifoControl(char settings); - - /** - * Get FIFO status. - * - * @return The contents of the FIFO_STATUS register. - */ - char getFifoStatus(void); - - /** - * Read the tap threshold on the device. - * - * @return The tap threshold as an 8-bit number with a scale factor of - * 62.5mg/LSB. - */ - char getTapThreshold(void); - - /** - * Set the tap threshold. - * - * @param The tap threshold as an 8-bit number with a scale factor of - * 62.5mg/LSB. - */ - int setTapThreshold(char threshold); - - /** - * Get the tap duration required to trigger an event. - * - * @return The max time that an event must be above the tap threshold to - * qualify as a tap event, in microseconds. - */ - float getTapDuration(void); - - /** - * Set the tap duration required to trigger an event. - * - * @param duration_us The max time that an event must be above the tap - * threshold to qualify as a tap event, in microseconds. - * Time will be normalized by the scale factor which is - * 625us/LSB. A value of 0 disables the single/double - * tap functions. - */ - int setTapDuration(short int duration_us); - - /** - * Get the tap latency between the detection of a tap and the time window. - * - * @return The wait time from the detection of a tap event to the start of - * the time window during which a possible second tap event can be - * detected in milliseconds. - */ - float getTapLatency(void); - - /** - * Set the tap latency between the detection of a tap and the time window. - * - * @param latency_ms The wait time from the detection of a tap event to the - * start of the time window during which a possible - * second tap event can be detected in milliseconds. - * A value of 0 disables the double tap function. - */ - int setTapLatency(short int latency_ms); - - /** - * Get the time of window between tap latency and a double tap. - * - * @return The amount of time after the expiration of the latency time - * during which a second valid tap can begin, in milliseconds. - */ - float getWindowTime(void); - - /** - * Set the time of the window between tap latency and a double tap. - * - * @param window_ms The amount of time after the expiration of the latency - * time during which a second valid tap can begin, - * in milliseconds. - */ - int setWindowTime(short int window_ms); - - /** - * Get the threshold value for detecting activity. - * - * @return The threshold value for detecting activity as an 8-bit number. - * Scale factor is 62.5mg/LSB. - */ - char getActivityThreshold(void); - - /** - * Set the threshold value for detecting activity. - * - * @param threshold The threshold value for detecting activity as an 8-bit - * number. Scale factor is 62.5mg/LSB. A value of 0 may - * result in undesirable behavior if the activity - * interrupt is enabled. - */ - int setActivityThreshold(char threshold); - - /** - * Get the threshold value for detecting inactivity. - * - * @return The threshold value for detecting inactivity as an 8-bit number. - * Scale factor is 62.5mg/LSB. - */ - char getInactivityThreshold(void); - - /** - * Set the threshold value for detecting inactivity. - * - * @param threshold The threshold value for detecting inactivity as an - * 8-bit number. Scale factor is 62.5mg/LSB. - */ - int setInactivityThreshold(char threshold); - - /** - * Get the time required for inactivity to be declared. - * - * @return The amount of time that acceleration must be less than the - * inactivity threshold for inactivity to be declared, in - * seconds. - */ - char getTimeInactivity(void); - - /** - * Set the time required for inactivity to be declared. - * - * @param inactivity The amount of time that acceleration must be less than - * the inactivity threshold for inactivity to be - * declared, in seconds. A value of 0 results in an - * interrupt when the output data is less than the - * threshold inactivity. - */ - int setTimeInactivity(char timeInactivity); - - /** - * Get the activity/inactivity control settings. - * - * D7 D6 D5 D4 - * +-----------+--------------+--------------+--------------+ - * | ACT ac/dc | ACT_X enable | ACT_Y enable | ACT_Z enable | - * +-----------+--------------+--------------+--------------+ - * - * D3 D2 D1 D0 - * +-------------+----------------+----------------+----------------+ - * | INACT ac/dc | INACT_X enable | INACT_Y enable | INACT_Z enable | - * +-------------+----------------+----------------+----------------+ - * - * See datasheet for details. - * - * @return The contents of the ACT_INACT_CTL register. - */ - char getActivityInactivityControl(void); - - /** - * Set the activity/inactivity control settings. - * - * D7 D6 D5 D4 - * +-----------+--------------+--------------+--------------+ - * | ACT ac/dc | ACT_X enable | ACT_Y enable | ACT_Z enable | - * +-----------+--------------+--------------+--------------+ - * - * D3 D2 D1 D0 - * +-------------+----------------+----------------+----------------+ - * | INACT ac/dc | INACT_X enable | INACT_Y enable | INACT_Z enable | - * +-------------+----------------+----------------+----------------+ - * - * See datasheet for details. - * - * @param settings The control byte to write to the ACT_INACT_CTL register. - */ - int setActivityInactivityControl(char settings); - - /** - * Get the threshold for free fall detection. - * - * @return The threshold value for free-fall detection, as an 8-bit number, - * with scale factor 62.5mg/LSB. - */ - char getFreefallThreshold(void); - - /** - * Set the threshold for free fall detection. - * - * @return The threshold value for free-fall detection, as an 8-bit number, - * with scale factor 62.5mg/LSB. A value of 0 may result in - * undesirable behavior if the free-fall interrupt is enabled. - * Values between 300 mg and 600 mg (0x05 to 0x09) are recommended. - */ - int setFreefallThreshold(char threshold); - - /** - * Get the time required to generate a free fall interrupt. - * - * @return The minimum time that the value of all axes must be less than - * the freefall threshold to generate a free-fall interrupt, in - * milliseconds. - */ - char getFreefallTime(void); - - /** - * Set the time required to generate a free fall interrupt. - * - * @return The minimum time that the value of all axes must be less than - * the freefall threshold to generate a free-fall interrupt, in - * milliseconds. A value of 0 may result in undesirable behavior - * if the free-fall interrupt is enabled. Values between 100 ms - * and 350 ms (0x14 to 0x46) are recommended. - */ - int setFreefallTime(short int freefallTime_ms); - - /** - * Get the axis tap settings. - * - * D3 D2 D1 D0 - * +----------+--------------+--------------+--------------+ - * | Suppress | TAP_X enable | TAP_Y enable | TAP_Z enable | - * +----------+--------------+--------------+--------------+ - * - * (D7-D4 are 0s). - * - * See datasheet for more details. - * - * @return The contents of the TAP_AXES register. - */ - char getTapAxisControl(void); - - /** - * Set the axis tap settings. - * - * D3 D2 D1 D0 - * +----------+--------------+--------------+--------------+ - * | Suppress | TAP_X enable | TAP_Y enable | TAP_Z enable | - * +----------+--------------+--------------+--------------+ - * - * (D7-D4 are 0s). - * - * See datasheet for more details. - * - * @param The control byte to write to the TAP_AXES register. - */ - int setTapAxisControl(char settings); - - /** - * Get the source of a tap. - * - * @return The contents of the ACT_TAP_STATUS register. - */ - char getTapSource(void); - - /** - * Get the interrupt enable settings. - * - * @return The contents of the INT_ENABLE register. - */ - - char getInterruptEnableControl(void); - - /** - * Set the interrupt enable settings. - * - * @param settings The control byte to write to the INT_ENABLE register. - */ - int setInterruptEnableControl(char settings); - - /** - * Get the interrupt mapping settings. - * - * @return The contents of the INT_MAP register. - */ - char getInterruptMappingControl(void); - - /** - * Set the interrupt mapping settings. - * - * @param settings The control byte to write to the INT_MAP register. - */ - int setInterruptMappingControl(char settings); - - /** - * Get the interrupt source. - * - * @return The contents of the INT_SOURCE register. - */ - char getInterruptSource(void); - - -private: - - I2C i2c_; - - - /** - * Read one byte from a register on the device. - * - * @param: - the address to be read from - * - * @return: the value of the data read - */ - char SingleByteRead(char address); - - /** - * Write one byte to a register on the device. - * - * @param: - - address of the register to write to. - - the value of the data to store - */ - - - int SingleByteWrite(char address, char data); - - /** - * Read several consecutive bytes on the device and store them in a given location. - * - * @param startAddress: The address of the first register to read from. - * @param ptr_output: a pointer to the location to store the data being read - * @param size: The number of bytes to read. - */ - void multiByteRead(char startAddress, char* ptr_output, int size); - - /** - * Write several consecutive bytes on the device. - * - * @param startAddress: The address of the first register to write to. - * @param ptr_data: Pointer to a location which contains the data to write. - * @param size: The number of bytes to write. - */ - int multiByteWrite(char startAddress, char* ptr_data, int size); - -}; - -#endif +// based on http://mbed.org/users/Digixx/code/ADXL345/ + +#ifndef ADXL345_H +#define ADXL345_H + +#include "mbed.h" + +// register addresses +#define ADXL345_DEVID_REG 0x00 +#define ADXL345_THRESH_TAP_REG 0x1D +#define ADXL345_OFSX_REG 0x1E +#define ADXL345_OFSY_REG 0x1F +#define ADXL345_OFSZ_REG 0x20 +#define ADXL345_DUR_REG 0x21 +#define ADXL345_LATENT_REG 0x22 +#define ADXL345_WINDOW_REG 0x23 +#define ADXL345_THRESH_ACT_REG 0x24 +#define ADXL345_THRESH_INACT_REG 0x25 +#define ADXL345_TIME_INACT_REG 0x26 +#define ADXL345_ACT_INACT_CTL_REG 0x27 +#define ADXL345_THRESH_FF_REG 0x28 +#define ADXL345_TIME_FF_REG 0x29 +#define ADXL345_TAP_AXES_REG 0x2A +#define ADXL345_ACT_TAP_STATUS_REG 0x2B +#define ADXL345_BW_RATE_REG 0x2C +#define ADXL345_POWER_CTL_REG 0x2D +#define ADXL345_INT_ENABLE_REG 0x2E +#define ADXL345_INT_MAP_REG 0x2F +#define ADXL345_INT_SOURCE_REG 0x30 +#define ADXL345_DATA_FORMAT_REG 0x31 +#define ADXL345_DATAX0_REG 0x32 +#define ADXL345_DATAX1_REG 0x33 +#define ADXL345_DATAY0_REG 0x34 +#define ADXL345_DATAY1_REG 0x35 +#define ADXL345_DATAZ0_REG 0x36 +#define ADXL345_DATAZ1_REG 0x37 +#define ADXL345_FIFO_CTL 0x38 +#define ADXL345_FIFO_STATUS 0x39 + +// data rate codes +#define ADXL345_3200HZ 0x0F +#define ADXL345_1600HZ 0x0E +#define ADXL345_800HZ 0x0D +#define ADXL345_400HZ 0x0C +#define ADXL345_200HZ 0x0B +#define ADXL345_100HZ 0x0A +#define ADXL345_50HZ 0x09 +#define ADXL345_25HZ 0x08 +#define ADXL345_12HZ5 0x07 +#define ADXL345_6HZ25 0x06 + +// read or write bytes +#define ADXL345_READ 0xA7 +#define ADXL345_WRITE 0xA6 +#define ADXL345_ADDRESS 0x53 + +//the ADXL345 7-bit address is 0x53 when ALT ADDRESS is low as it is on the sparkfun chip: when ALT ADDRESS is high the address is 0x1D +//when ALT ADDRESS pin is high: +//#define ADXL345_READ 0x3B +//#define ADXL345_WRITE 0x3A +//#define ADXL345_ADDRESS 0x1D + +#define ADXL345_X 0x00 +#define ADXL345_Y 0x01 +#define ADXL345_Z 0x02 + +typedef char byte; + +class ADXL345 +{ + public: + ADXL345(PinName sda, PinName scl); // constructor, uses i2c + void read(int a[3]); // read all axis to array + + + private: + I2C i2c; // i2c object to communicate + int writeReg(byte reg, byte value); // write one single register to sensor + byte readReg(byte reg); // read one single register from sensor + void readMultiReg(char startAddress, char* ptr_output, int size); // read multiple regs + int setDataRate(char rate); // data rate configuration (not only a reg to write) +}; + +#endif
--- a/Sensors/Gyro/L3G4200D.cpp Fri Sep 28 13:24:03 2012 +0000 +++ b/Sensors/Gyro/L3G4200D.cpp Tue Oct 02 17:53:40 2012 +0000 @@ -5,17 +5,17 @@ #define L3G4200D_I2C_ADDRESS 0xD0 -L3G4200D::L3G4200D(PinName sda, PinName scl): - i2c(sda, scl) +L3G4200D::L3G4200D(PinName sda, PinName scl) : i2c(sda, scl) { i2c.frequency(400000); // Turns on the L3G4200D's gyro and places it in normal mode. // 0x0F = 0b00001111 // Normal power mode, all axes enabled - writeReg(L3G4200D_CTRL_REG2, 0x05); // Filter steuern + //writeReg(L3G4200D_CTRL_REG2, 0x05); // control filter + writeReg(L3G4200D_CTRL_REG2, 0x00); // highpass filter disabled writeReg(L3G4200D_CTRL_REG3, 0x00); - writeReg(L3G4200D_CTRL_REG4, 0x20); // Genauigkeit 2000 dps + writeReg(L3G4200D_CTRL_REG4, 0x20); // acuracy 2000 dps writeReg(L3G4200D_REFERENCE, 0x00); //writeReg(L3G4200D_STATUS_REG, 0x0F); @@ -26,18 +26,39 @@ writeReg(L3G4200D_INT1_THS_ZH, 0x2C); writeReg(L3G4200D_INT1_THS_ZL, 0xA4); //writeReg(L3G4200D_INT1_DURATION, 0x00); - writeReg(L3G4200D_CTRL_REG5, 0x12); // Filter einschalten + //writeReg(L3G4200D_CTRL_REG5, 0x12); // Filter einschalten + //writeReg(L3G4200D_CTRL_REG5, 0x01); // hochpass Filter einschalten + writeReg(L3G4200D_CTRL_REG5, 0x00); // Filter ausschalten writeReg(L3G4200D_CTRL_REG1, 0x0F); // Gogo + + // calibrate gyro with an average of count samples (result to offset) + #define count 50 + for (int j = 0; j < 3; j++) + offset[j] = 0; + + float Gyro_calib[3] = {0,0,0}; // temporary to sum up + float Gyro_data[3]; + + for (int i = 0; i < count; i++) { + read(Gyro_data); + for (int j = 0; j < 3; j++) + Gyro_calib[j] += Gyro_data[j]; + wait(0.001); // maybe less or no wait !! + } + + for (int j = 0; j < 3; j++) + offset[j] = Gyro_calib[j]/count; } // Writes a gyro register void L3G4200D::writeReg(byte reg, byte value) { - data[0] = reg; - data[1] = value; + byte buffer[2]; + buffer[0] = reg; + buffer[1] = value; - i2c.write(L3G4200D_I2C_ADDRESS, data, 2); + i2c.write(L3G4200D_I2C_ADDRESS, buffer, 2); } // Reads a gyro register @@ -52,28 +73,33 @@ } // Reads the 3 gyro channels and stores them in vector g -void L3G4200D::read(int g[3]) +void L3G4200D::read(float g[3]) { + byte buffer[6]; // 8-Bit pieces of axis data // assert the MSB of the address to get the gyro // to do slave-transmit subaddress updating. - data[0] = L3G4200D_OUT_X_L | (1 << 7); - i2c.write(L3G4200D_I2C_ADDRESS, data, 1); + buffer[0] = L3G4200D_OUT_X_L | (1 << 7); + i2c.write(L3G4200D_I2C_ADDRESS, buffer, 1); // Wire.requestFrom(GYR_ADDRESS, 6); // while (Wire.available() < 6); - i2c.read(L3G4200D_I2C_ADDRESS, data, 6); + i2c.read(L3G4200D_I2C_ADDRESS, buffer, 6); - uint8_t xla = data[0]; - uint8_t xha = data[1]; - uint8_t yla = data[2]; - uint8_t yha = data[3]; - uint8_t zla = data[4]; - uint8_t zha = data[5]; + uint8_t xla = buffer[0]; + uint8_t xha = buffer[1]; + uint8_t yla = buffer[2]; + uint8_t yha = buffer[3]; + uint8_t zla = buffer[4]; + uint8_t zha = buffer[5]; g[0] = (short) (xha << 8 | xla); g[1] = (short) (yha << 8 | yla); g[2] = (short) (zha << 8 | zla); + + //with offset of calibration + for (int j = 0; j < 3; j++) + g[j] -= offset[j]; } // Reads the gyros Temperature
--- a/Sensors/Gyro/L3G4200D.h Fri Sep 28 13:24:03 2012 +0000 +++ b/Sensors/Gyro/L3G4200D.h Tue Oct 02 17:53:40 2012 +0000 @@ -1,7 +1,7 @@ // based on http://mbed.org/users/shimniok/code/L3G4200D/ -#ifndef __L3G4200D_H -#define __L3G4200D_H +#ifndef L3G4200D_H +#define L3G4200D_H #include "mbed.h" @@ -43,11 +43,11 @@ { public: L3G4200D(PinName sda, PinName scl); // constructor, uses i2c - void read(int g[3]); // read all axis to array + void read(float g[3]); // read all axis to array int readTemp(); // read temperature from sensor private: - byte data[6]; // 8-Bit pieces of axis data + float offset[3]; // offset that's subtracted from every measurement I2C i2c; // i2c object to communicate void writeReg(byte reg, byte value); // write one single register to sensor byte readReg(byte reg); // read one single register from sensor
--- a/main.cpp Fri Sep 28 13:24:03 2012 +0000 +++ b/main.cpp Tue Oct 02 17:53:40 2012 +0000 @@ -12,33 +12,84 @@ ADXL345 Acc(p28, p27); Servo Motor(p12); +Timer GlobalTimer; + +#define PI 3.1415926535897932384626433832795 +#define Rad2Deg 57.295779513082320876798154814105 + int main() { // LCD/LED init LCD.cls(); // Display löschen - LCD.printf("FlyBed v0.1"); + LCD.printf("FlyBed v0.2"); LEDs.roll(2); //LEDs = 15; - int Gyro_data[3]; + float Gyro_data[3]; int Acc_data[3]; + int Gyro_angle[3] = {0,0,0}; + unsigned long dt = 0; + unsigned long time_loop = 0; + Motor.initialize(); + + float angle = 0;//TEMP + int j = 0; + //float drift = 0; + GlobalTimer.start(); while(1) { + j++; Gyro.read(Gyro_data); - Acc.getOutput(Acc_data); + Acc.read(Acc_data); + + // Acc data angle + float Acc_abs = sqrt(pow((float)Acc_data[0],2) + pow((float)Acc_data[1],2) + pow((float)Acc_data[2],2)); + //float Acc_angle = Rad2Deg * acos((float)Acc_data[2]/Acc_abs); + float Acc_angle = 0.9 * Rad2Deg * atan((float)Acc_data[1]/(float)Acc_data[2]); + + //angle = (0.98)*(angle + Gyro_data[0] * 0.1) + (0.02)*(Acc_angle); + + /*float messfrequenz = 10; + float geschwindigkeit = Gyro_data[0] - drift; + drift += (geschwindigkeit * messfrequenz * 0.3); + angle += (geschwindigkeit * messfrequenz); + angle += ((Acc_angle - angle) * messfrequenz * 0.1);*/ + + //for (int i= 0; i < 3;i++) + //drift[i] += (Gyro_data[i]-drift[i])* 0.1; + + //for (int i= 0; i < 3;i++) + //Gyro_angle[i] += (Gyro_data[i]/*-drift[i]*/); + + //dt berechnen + dt = GlobalTimer.read_us() - time_loop; + time_loop = GlobalTimer.read_us(); + + angle += (Acc_angle - angle)/30 + Gyro_data[0] * 0.01; + //Gyro_angle[0] += (Gyro_data[0]) * 0.01; LCD.locate(0,0); - LCD.printf("%d %d %d |%d ", Gyro_data[0],Gyro_data[1],Gyro_data[2],Gyro.readTemp()); //roll(x) pitch(y) yaw(z) + LCD.printf(" |%2.1f ",Acc_angle); //roll(x) pitch(y) yaw(z) LCD.locate(1,0); - LCD.printf("%d %d %d %d ", (int16_t)Acc_data[0],(int16_t)Acc_data[1],(int16_t)Acc_data[2], 1000 + abs((int16_t)Acc_data[1])); + //LCD.printf("%d %d %d %2.1f ", Acc_data[0],Acc_data[1],Acc_data[2], Acc_angle); + LCD.printf("%d %d %2.4f %2.1f ", Gyro_angle[0],Gyro_angle[1],dt/10000000.0, angle); + + Motor = 1000 + abs(Acc_data[1]); // Motorwert anpassen - if(abs((int16_t)Acc_data[0]) > 200) - Motor.initialize(); + //LED hin und her + int ledset = 0; + if (Acc_angle < 0) + ledset += 1; + else + ledset += 8; + if (angle < 0) + ledset += 2; + else + ledset += 4; + + LEDs = ledset; - Motor = 1000 + abs((int16_t)Acc_data[1]); // Motorwert anpassen - - LEDs.rollnext(); + //LEDs.rollnext(); wait(0.1); - } }