Removed outdated sensors bringup app

This commit is contained in:
Lorenz Meier 2012-08-18 09:34:49 +02:00
parent 8a8b6b7165
commit c6eff9eb8b
6 changed files with 0 additions and 932 deletions

View File

@ -1,42 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Makefile to build the sensor bringup tests
#
APPNAME = sensors_bringup
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk

View File

@ -1,209 +0,0 @@
/*
* Operations for the Bosch BMA180 3D Accelerometer
*/
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <arch/board/board.h>
#include <nuttx/spi.h>
#include "sensors.h"
#define DIR_READ (1<<7)
#define DIR_WRITE (0<<7)
#define ADDR_INCREMENT (1<<6)
#define ADDR_CHIP_ID 0x00
#define CHIP_ID 0x03
#define ADDR_VERSION 0x01
#define ADDR_CTRL_REG0 0x0D
#define ADDR_CTRL_REG1 0x0E
#define ADDR_CTRL_REG2 0x0F
#define ADDR_BWTCS 0x20
#define ADDR_CTRL_REG3 0x21
#define ADDR_CTRL_REG4 0x22
#define ADDR_OLSB1 0x35
#define ADDR_ACC_X_LSB 0x02
#define ADDR_ACC_Z_MSB 0x07
#define ADDR_TEMPERATURE 0x08
#define ADDR_STATUS_REG1 0x09
#define ADDR_STATUS_REG2 0x0A
#define ADDR_STATUS_REG3 0x0B
#define ADDR_STATUS_REG4 0x0C
#define ADDR_RESET 0x10
#define SOFT_RESET 0xB6
#define ADDR_DIS_I2C 0x27
#define REG0_WRITE_ENABLE 0x10
#define BWTCS_LP_10HZ (0<<4)
#define BWTCS_LP_20HZ (1<<4)
#define BWTCS_LP_40HZ (2<<4)
#define BWTCS_LP_75HZ (3<<4)
#define BWTCS_LP_150HZ (4<<4)
#define BWTCS_LP_300HZ (5<<4)
#define BWTCS_LP_600HZ (6<<4)
#define BWTCS_LP_1200HZ (7<<4)
#define RANGE_1G (0<<1)
#define RANGE_1_5G (1<<1)
#define RANGE_2G (2<<1)
#define RANGE_3G (3<<1)
#define RANGE_4G (4<<1)
#define RANGE_8G (5<<1)
#define RANGE_16G (6<<1)
#define RANGEMASK 0x0E
#define BWMASK 0xF0
static void
write_reg(struct spi_dev_s *spi, uint8_t address, uint8_t data)
{
uint8_t cmd[2] = { address | DIR_WRITE, data };
SPI_SELECT(spi, PX4_SPIDEV_ACCEL, true);
SPI_SNDBLOCK(spi, &cmd, sizeof(cmd));
SPI_SELECT(spi, PX4_SPIDEV_ACCEL, false);
}
static uint8_t
read_reg(struct spi_dev_s *spi, uint8_t address)
{
uint8_t cmd[2] = {address | DIR_READ, 0};
uint8_t data[2];
SPI_SELECT(spi, PX4_SPIDEV_ACCEL, true);
SPI_EXCHANGE(spi, cmd, data, sizeof(cmd));
SPI_SELECT(spi, PX4_SPIDEV_ACCEL, false);
return data[1];
}
int
bma180_test_configure(struct spi_dev_s *spi)
{
uint8_t id;
id = read_reg(spi, ADDR_CHIP_ID);
uint8_t version = read_reg(spi, 0x01);
if (id == CHIP_ID)
{
message("BMA180 SUCCESS: 0x%02x, version: %d\n", id, version);
}
else
{
message("BMA180 FAIL: 0x%02x\n", id);
}
//message("got id 0x%02x, expected ID 0x03\n", id);
write_reg(spi, ADDR_RESET, SOFT_RESET); // page 48
usleep(12000); // wait 10 ms, see page 49
// Configuring the BMA180
/* enable writing to chip config */
uint8_t ctrl0 = read_reg(spi, ADDR_CTRL_REG0);
ctrl0 |= REG0_WRITE_ENABLE;
write_reg(spi, ADDR_CTRL_REG0, ctrl0);
uint8_t disi2c = read_reg(spi, ADDR_DIS_I2C); // read
disi2c |= 0x01; // set bit0 to 1, SPI only
write_reg(spi, ADDR_DIS_I2C, disi2c); // Set spi, disable i2c, page 31
/* set bandwidth */
uint8_t bwtcs = read_reg(spi, ADDR_BWTCS);
printf("bwtcs: %d\n", bwtcs);
bwtcs &= (~BWMASK);
bwtcs |= (BWTCS_LP_600HZ);// & BWMASK);
write_reg(spi, ADDR_BWTCS, bwtcs);
/* set range */
uint8_t olsb1 = read_reg(spi, ADDR_OLSB1);
printf("olsb1: %d\n", olsb1);
olsb1 &= (~RANGEMASK);
olsb1 |= (RANGE_4G);// & RANGEMASK);
write_reg(spi, ADDR_OLSB1, olsb1);
// uint8_t reg3 = read_reg(spi, ADDR_CTRL_REG3);
// //reg3 &= 0xFD; // REset bit 1 enable interrupt
// //reg3 |= 0x02; // enable
// write_reg(spi, ADDR_CTRL_REG3, reg3); //
/* block writing to chip config */
ctrl0 = read_reg(spi, ADDR_CTRL_REG0);
ctrl0 &= (~REG0_WRITE_ENABLE);
printf("ctrl0: %d\n", ctrl0);
write_reg(spi, ADDR_CTRL_REG0, ctrl0);
return 0;
}
int
bma180_test_read(struct spi_dev_s *spi)
{
struct { /* status register and data as read back from the device */
uint8_t cmd;
int16_t x;
int16_t y;
int16_t z;
uint8_t temp;
} __attribute__((packed)) report;
report.x = 0;
report.y = 0;
report.z = 0;
// uint8_t temp;
// uint8_t status1;
// uint8_t status2;
// uint8_t status3;
// uint8_t status4;
report.cmd = ADDR_ACC_X_LSB | DIR_READ | ADDR_INCREMENT;
//SPI_LOCK(spi, true);
//SPI_SELECT(spi, PX4_SPIDEV_ACCEL, true);
//SPI_EXCHANGE(spi, &report, &report, sizeof(report));
//SPI_SELECT(spi, PX4_SPIDEV_ACCEL, false);
//SPI_LOCK(spi, false);
report.x = read_reg(spi, ADDR_ACC_X_LSB);
report.x |= (read_reg(spi, ADDR_ACC_X_LSB+1) << 8);
report.y = read_reg(spi, ADDR_ACC_X_LSB+2);
report.y |= (read_reg(spi, ADDR_ACC_X_LSB+3) << 8);
report.z = read_reg(spi, ADDR_ACC_X_LSB+4);
report.z |= (read_reg(spi, ADDR_ACC_X_LSB+5) << 8);
report.temp = read_reg(spi, ADDR_ACC_X_LSB+6);
// Collect status and remove two top bits
uint8_t new_data = (report.x & 0x01) + (report.x & 0x01) + (report.x & 0x01);
report.x = (report.x >> 2);
report.y = (report.y >> 2);
report.z = (report.z >> 2);
message("ACC: x: %d\ty: %d\tz: %d\ttemp: %d new: %d\n", report.x, report.y, report.z, report.temp, new_data);
usleep(2000);
return 0;
}

View File

@ -1,184 +0,0 @@
/*
* Operations for the l3g4200
*/
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <arch/board/board.h>
#include <nuttx/spi.h>
#include "sensors.h"
#define DIR_READ (1<<7)
#define DIR_WRITE (0<<7)
#define ADDR_INCREMENT (1<<6)
#define ADDR_WHO_AM_I 0x0f
#define WHO_I_AM 0xd4
#define ADDR_CTRL_REG1 0x20 /* sample rate constants are in the public header */
#define REG1_POWER_NORMAL (1<<3)
#define REG1_Z_ENABLE (1<<2)
#define REG1_Y_ENABLE (1<<1)
#define REG1_X_ENABLE (1<<0)
#define ADDR_CTRL_REG2 0x21
/* high-pass filter - usefulness TBD */
#define ADDR_CTRL_REG3 0x22
#define ADDR_CTRL_REG4 0x23
#define REG4_BDU (1<<7)
#define REG4_BIG_ENDIAN (1<<6)
#define REG4_SPI_3WIRE (1<<0)
#define ADDR_CTRL_REG5 0x24
#define REG5_BOOT (1<<7)
#define REG5_FIFO_EN (1<<6)
#define REG5_HIGHPASS_ENABLE (1<<4)
#define ADDR_REFERENCE 0x25
#define ADDR_TEMPERATURE 0x26
#define ADDR_STATUS_REG 0x27
#define STATUS_ZYXOR (1<<7)
#define SATAUS_ZOR (1<<6)
#define STATUS_YOR (1<<5)
#define STATUS_XOR (1<<4)
#define STATUS_ZYXDA (1<<3)
#define STATUS_ZDA (1<<2)
#define STATUS_YDA (1<<1)
#define STATUS_XDA (1<<0)
#define ADDR_OUT_X 0x28 /* 16 bits */
#define ADDR_OUT_Y 0x2A /* 16 bits */
#define ADDR_OUT_Z 0x2C /* 16 bits */
#define ADDR_FIFO_CTRL 0x2e
#define FIFO_MODE_BYPASS (0<<5)
#define FIFO_MODE_FIFO (1<<5)
#define FIFO_MODE_STREAM (2<<5)
#define FIFO_MODE_STREAM_TO_FIFO (3<<5)
#define FIFO_MODE_BYPASS_TO_STREAM (4<<5)
#define FIFO_THRESHOLD_MASK 0x1f
#define ADDR_FIFO_SRC 0x2f
#define FIFO_THREHSHOLD_OVER (1<<7)
#define FIFO_OVERRUN (1<<6)
#define FIFO_EMPTY (1<<5)
#define L3G4200_RATE_100Hz ((0<<6) | (0<<4))
#define L3G4200_RATE_200Hz ((1<<6) | (0<<4))
#define L3G4200_RATE_400Hz ((2<<6) | (1<<4))
#define L3G4200_RATE_800Hz ((3<<6) | (2<<4))
#define L3G4200_RANGE_250dps (0<<4)
#define L3G4200_RANGE_500dps (1<<4)
#define L3G4200_RANGE_2000dps (3<<4)
static void
write_reg(struct spi_dev_s *spi, uint8_t address, uint8_t data)
{
uint8_t cmd[2] = { address | DIR_WRITE, data };
SPI_SELECT(spi, PX4_SPIDEV_GYRO, true);
SPI_SNDBLOCK(spi, &cmd, sizeof(cmd));
SPI_SELECT(spi, PX4_SPIDEV_GYRO, false);
}
static uint8_t
read_reg(struct spi_dev_s *spi, uint8_t address)
{
uint8_t cmd[2] = {address | DIR_READ, 0};
uint8_t data[2];
SPI_SELECT(spi, PX4_SPIDEV_GYRO, true);
SPI_EXCHANGE(spi, cmd, data, sizeof(cmd));
SPI_SELECT(spi, PX4_SPIDEV_GYRO, false);
return data[1];
}
int
l3gd20_test_configure(struct spi_dev_s *spi)
{
uint8_t id;
id = read_reg(spi, ADDR_WHO_AM_I);
if (id == WHO_I_AM)
{
message("L3GD20 SUCCESS: 0x%02x\n", id);
}
else
{
message("L3GD20 FAIL: 0x%02x\n", id);
}
struct { /* status register and data as read back from the device */
uint8_t cmd;
uint8_t temp;
uint8_t status;
int16_t x;
int16_t y;
int16_t z;
} __attribute__((packed)) report;
report.cmd = 0x26 | DIR_READ | ADDR_INCREMENT;
write_reg(spi, ADDR_CTRL_REG2, 0); /* disable high-pass filters */
write_reg(spi, ADDR_CTRL_REG3, 0); /* no interrupts - we don't use them */
write_reg(spi, ADDR_CTRL_REG5, 0); /* turn off FIFO mode */
write_reg(spi, ADDR_CTRL_REG4, ((3<<4) & 0x30) | REG4_BDU);
write_reg(spi, ADDR_CTRL_REG1,
(((2<<6) | (1<<4)) & 0xf0) | REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE);
SPI_SELECT(spi, PX4_SPIDEV_GYRO, true);
SPI_EXCHANGE(spi, &report, &report, sizeof(report));
SPI_SELECT(spi, PX4_SPIDEV_GYRO, false);
message("Init-read: gyro: x: %d\ty: %d\tz: %d\n", report.x, report.y, report.z);
usleep(1000);
//message("got id 0x%02x, expected ID 0xd4\n", id);
return 0;
}
int
l3gd20_test_read(struct spi_dev_s *spi)
{
struct { /* status register and data as read back from the device */
uint8_t cmd;
uint8_t temp;
uint8_t status;
int16_t x;
int16_t y;
int16_t z;
} __attribute__((packed)) report;
report.cmd = 0x26 | DIR_READ | ADDR_INCREMENT;
SPI_LOCK(spi, true);
SPI_SELECT(spi, PX4_SPIDEV_GYRO, true);
SPI_EXCHANGE(spi, &report, &report, sizeof(report));
SPI_SELECT(spi, PX4_SPIDEV_GYRO, false);
SPI_LOCK(spi, false);
message("gyro: x: %d\ty: %d\tz: %d\n", report.x, report.y, report.z);
usleep(1000);
return 0;
}

View File

@ -1,88 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __APPS_PX4_SENSORS_H
#define __APPS_PX4_SENSORS_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/spi.h>
#include <nuttx/i2c.h>
/****************************************************************************
* Definitions
****************************************************************************/
/* Debug ********************************************************************/
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
# define message(...) lib_rawprintf(__VA_ARGS__)
# define msgflush()
# else
# define message(...) printf(__VA_ARGS__)
# define msgflush() fflush(stdout)
# endif
#else
# ifdef CONFIG_DEBUG
# define message lib_rawprintf
# define msgflush()
# else
# define message printf
# define msgflush() fflush(stdout)
# endif
#endif
/****************************************************************************
* Public Types
****************************************************************************/
/****************************************************************************
* Public Variables
****************************************************************************/
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
int l3gd20_test_configure(struct spi_dev_s *spi);
int l3gd20_test_read(struct spi_dev_s *spi);
int bma180_test_configure(struct spi_dev_s *spi);
int bma180_test_read(struct spi_dev_s *spi);
int bma180_test(struct spi_dev_s *spi);
int hmc5883l_test(struct i2c_dev_s *i2c);
#endif /* __APPS_PX4_SENSORS_H */

View File

@ -1,409 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <arch/board/board.h>
#include <nuttx/spi.h>
#include <nuttx/i2c.h>
#include "sensors.h"
__EXPORT int sensors_bringup_main(int argc, char *argv[]);
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Types
****************************************************************************/
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: user_start/adc_main
****************************************************************************/
int sensors_bringup_main(int argc, char *argv[])
{
struct spi_dev_s *spi;
int result = -1;
spi = up_spiinitialize(1);
if (!spi) {
message("Failed to initialize SPI port 1\n");
goto out;
}
struct i2c_dev_s *i2c;
i2c = up_i2cinitialize(2);
if (!i2c) {
message("Failed to initialize I2C bus 2\n");
goto out;
}
int ret;
#define EEPROM_ADDRESS 0x50
#define HMC5883L_ADDRESS 0x1E
//uint8_t devaddr = EEPROM_ADDRESS;
I2C_SETFREQUENCY(i2c, 100000);
//
// uint8_t subaddr = 0x00;
// int ret = 0;
//
// // ATTEMPT HMC5883L CONFIG
// I2C_SETADDRESS(i2c, HMC5883L_ADDRESS, 7);
// subaddr = 0x02; // mode register
// ret = I2C_WRITE(i2c, &subaddr, 0);
// if (ret < 0)
// {
// message("I2C_WRITE failed: %d\n", ret);
// }
// else
// {
// message("I2C_WRITE SUCCEEDED: %d\n", ret);
// }
//fflush(stdout);
//
//
//
#define STATUS_REGISTER 0x09 // Of HMC5883L
// ATTEMPT HMC5883L WRITE
I2C_SETADDRESS(i2c, HMC5883L_ADDRESS, 7);
uint8_t cmd = 0x09;
uint8_t status_id[4] = {0, 0, 0, 0};
ret = I2C_WRITEREAD(i2c, &cmd, 1, status_id, 4);
if (ret >= 0 && status_id[1] == 'H' && status_id[2] == '4' && status_id[3] == '3')
{
message("HMC5883L identified, device status: %d\n", status_id[0]);
} else {
message("HMC5883L identification failed: %d\n", ret);
}
#define HMC5883L_ADDR_CONF_A 0x00
#define HMC5883L_ADDR_CONF_B 0x01
#define HMC5883L_ADDR_MODE 0x02
#define HMC5883L_AVERAGING_1 (0 << 5) /* conf a register */
#define HMC5883L_AVERAGING_2 (1 << 5)
#define HMC5883L_AVERAGING_4 (2 << 5)
#define HMC5883L_AVERAGING_8 (3 << 5)
#define HMC5883L_RATE_75HZ (6 << 2) /* 75 Hz */
#define HMC5883L_RANGE_0_88GA (0 << 5)
uint8_t rate_cmd[] = {HMC5883L_ADDR_CONF_A, HMC5883L_RATE_75HZ | HMC5883L_AVERAGING_8};
ret = I2C_WRITE(i2c, rate_cmd, sizeof(rate_cmd));
message("Wrote %d into register 0x00 of HMC, result: %d (0 = success)\n", HMC5883L_RATE_75HZ | HMC5883L_AVERAGING_8, ret);
uint8_t range_cmd[] = {HMC5883L_ADDR_CONF_B, HMC5883L_RANGE_0_88GA};
ret = I2C_WRITE(i2c, range_cmd, sizeof(range_cmd));
message("Wrote %d into register 0x01 of HMC, result: %d (0 = success)\n", HMC5883L_RANGE_0_88GA, ret);
// Set HMC into continous mode
// First write address, then value
uint8_t cont_address[] = {HMC5883L_ADDR_MODE, 0x00};
ret = I2C_WRITE(i2c, cont_address, sizeof(cont_address));
message("Wrote 0x00 into register 0x02 of HMC, result: %d (0 = success)\n", ret);
// ATTEMPT HMC5883L READ
int h = 0;
I2C_SETADDRESS(i2c, HMC5883L_ADDRESS, 7);
for (h = 0; h < 5; h++)
{
cont_address[0] = HMC5883L_ADDR_MODE;
cont_address[1] = 0x01;
ret = I2C_WRITE(i2c, cont_address, sizeof(cont_address));
message("Wrote 0x01 into register 0x02 of HMC, result: %d (0 = success)\n", ret);
usleep(100000);
cont_address[1] = 0x00;
uint8_t dummy;
ret = I2C_WRITEREAD(i2c, cont_address, sizeof(cont_address), &dummy, 1);
message("Wrote 0x00 into register 0x02 of HMC, result: %d (0 = success)\n", ret);
usleep(100000);
int16_t hmc5883l_data[3] = {0, 0, 0};
uint8_t data_address = 0x03;
uint8_t* data_ptr = (uint8_t*)hmc5883l_data;
ret = I2C_WRITEREAD(i2c, &data_address, 1, data_ptr, 6);
if (ret < 0)
{
message("HMC5883L READ failed: %d\n", ret);
}
else
{
// mask out top four bits as only 12 bits are valid
hmc5883l_data[0] &= 0xFFF;
hmc5883l_data[1] &= 0xFFF;
hmc5883l_data[2] &= 0xFFF;
message("HMC5883L READ SUCCEEDED: %d, val: %d %d %d\n", ret, hmc5883l_data[0], hmc5883l_data[1], hmc5883l_data[2]);
uint8_t hmc_status;
ret = I2C_WRITEREAD(i2c, &cmd, 1, &hmc_status, 1);
message("\t status: %d\n", hmc_status);
}
}
// Possible addresses: 0x77 or 0x76
#define MS5611_ADDRESS_1 0x76
#define MS5611_ADDRESS_2 0x77
I2C_SETADDRESS(i2c, MS5611_ADDRESS_1, 7);
// Reset cmd
uint8_t ms5611_cmd[2] = {0x00, 0x1E};
ret = I2C_WRITE(i2c, ms5611_cmd, 2);
if (ret < 0)
{
message("MS5611 #1 WRITE failed: %d\n", ret);
}
else
{
message("MS5611 #1 WRITE SUCCEEDED: %d\n", ret);
}
fflush(stdout);
I2C_SETADDRESS(i2c, MS5611_ADDRESS_2, 7);
ret = I2C_WRITE(i2c, ms5611_cmd, 2);
if (ret < 0)
{
message("MS5611 #2 WRITE failed: %d\n", ret);
}
else
{
message("MS5611 #2 WRITE SUCCEEDED: %d\n", ret);
}
fflush(stdout);
// Wait for reset to complete (10 ms nominal, wait: 100 ms)
usleep(100000);
// Read PROM data
uint8_t prom_buf[2] = {0,1};
uint16_t calibration[6];
int i = 0;
prom_buf[0] = 0xA2 + (i*2);
struct i2c_msg_s msgv[2] = {
{
.addr = MS5611_ADDRESS_2,
.flags = 0,
.buffer = prom_buf,
.length = 1
},
{
.addr = MS5611_ADDRESS_2,
.flags = I2C_M_READ,
.buffer = prom_buf,
.length = 1
}
};
calibration[i] = prom_buf[0]*256;
calibration[i]+= prom_buf[1];
int retval;
if ( (retval = I2C_TRANSFER(i2c, msgv, 2)) == OK )
{
printf("SUCCESS ACCESSING PROM OF MS5611: %d, value C1: %d\n", retval, (int)calibration[0]);
}
else
{
printf("FAIL ACCESSING PROM OF MS5611\n");
}
// TESTING CODE, EEPROM READ/WRITE
uint8_t val[1] = {10};
int retval_eeprom;
uint8_t eeprom_subaddr[2] = {0, 0};
struct i2c_msg_s msgv_eeprom[2] = {
{
.addr = EEPROM_ADDRESS,
.flags = 0,
.buffer = eeprom_subaddr,
.length = 2
},
{
.addr = EEPROM_ADDRESS,
.flags = I2C_M_READ,
.buffer = val,
.length = 1
}
};
val[0] = 5;
if ( (retval_eeprom = I2C_TRANSFER(i2c, msgv_eeprom, 2)) == OK )
{
printf("SUCCESS READING EEPROM: %d, value: %d\n", retval_eeprom, (int)val[0]);
}
else
{
printf("FAIL READING EEPROM: %d, value: %d\n", retval_eeprom, (int)val[0]);
}
// Increment val
val[0] = val[0] + 1;
struct i2c_msg_s msgv_eeprom_write[2] = {
{
.addr = EEPROM_ADDRESS,
.flags = I2C_M_NORESTART,
.buffer = eeprom_subaddr,
.length = 2
},
{
.addr = EEPROM_ADDRESS,
.flags = I2C_M_NORESTART,
.buffer = val,
.length = 1
}
};
if ( (retval_eeprom = I2C_TRANSFER(i2c, msgv_eeprom_write, 2)) == OK )
{
printf("SUCCESS WRITING EEPROM: %d\n", retval_eeprom);
}
usleep(10000);
struct i2c_msg_s msgv_eeprom2[2] = {
{
.addr = EEPROM_ADDRESS,
.flags = 0,
.buffer = eeprom_subaddr,
.length = 2
},
{
.addr = EEPROM_ADDRESS,
.flags = I2C_M_READ,
.buffer = val,
.length = 1
}
};
val[0] = 5;
if ( (retval_eeprom = I2C_TRANSFER(i2c, msgv_eeprom2, 2)) == OK )
{
printf("SUCCESS READING WRITE RESULT EEPROM: %d, value: %d\n", retval_eeprom, (int)val[0]);
}
else
{
printf("FAIL READING WRITE RESULT EEPROM: %d, value: %d\n", retval_eeprom, (int)val[0]);
}
// Configure sensors
l3gd20_test_configure(spi);
bma180_test_configure(spi);
for (int i = 0; i < 3; i++)
{
l3gd20_test_read(spi);
bma180_test_read(spi);
printf("# %d of 10\n", i+1);
usleep(50000);
}
out:
msgflush();
return result;
}