Skip to content

Commit

Permalink
New board supported: PARIS v5 OSD
Browse files Browse the repository at this point in the history
Added support for ITG3050 and BMA280 sensors
  • Loading branch information
SirAlex committed Feb 10, 2014
1 parent 5a7fe85 commit 04eb468
Show file tree
Hide file tree
Showing 12 changed files with 51 additions and 66 deletions.
1 change: 1 addition & 0 deletions ArduCopter/APM_Config.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
HK_RED_MULTIWII_PRO -- HobbyKing MultiWii Pro RED board with ITG3205 and BMA180, BMP085 sensors
BLACK_VORTEX
MULTIWII_PRO_EZ3_BLACK -- ReadyToFlyQuads - MultiWii PRO Ez3.0 Blacked MAG Editon Flight Controller w/ GPS Option (NO COMPASS)
PARIS_V5_OSD -- PARIS v5 Mega iOSD - http://www.multiwiicopter.com/products/multiwii-paris-v5-mega-iosd-gps-autopilot
*/

// Currently not supported
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/ArduCopter.pde
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef THISFIRMWARE
# define THISFIRMWARE "ArduCopter-MPNG V3.0.1 R3b"
# define THISFIRMWARE "ArduCopter-MPNG V3.0.1 R4"
#endif
/*
* ArduCopter Version 3.0
Expand Down
4 changes: 4 additions & 0 deletions ArduCopter/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,10 @@
#if MPNG_BOARD_TYPE == HK_RED_MULTIWII_PRO || MPNG_BOARD_TYPE == BLACK_VORTEX
# define CONFIG_IMU_TYPE CONFIG_IMU_ITG3200
# define CONFIG_BARO AP_BARO_BMP085_MPNG
#elif MPNG_BOARD_TYPE == PARIS_V5_OSD
# define CONFIG_IMU_TYPE CONFIG_IMU_ITG3200
# define CONFIG_BARO AP_BARO_MS5611
# define CONFIG_MS5611_SERIAL AP_BARO_MS5611_I2C
#else
# define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000_I2C
# define CONFIG_BARO AP_BARO_MS5611
Expand Down
1 change: 1 addition & 0 deletions ArduCopter/defines.h
Original file line number Diff line number Diff line change
Expand Up @@ -420,6 +420,7 @@ enum ap_message {
#define HK_RED_MULTIWII_PRO 3
#define BLACK_VORTEX 4
#define MULTIWII_PRO_EZ3_BLACK 5
#define PARIS_V5_OSD 6


// Error message sub systems and error codes
Expand Down
1 change: 1 addition & 0 deletions ArduPlane/APM_Config.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
HK_RED_MULTIWII_PRO -- HobbyKing MultiWii Pro board with ITG3205 and BMA180, BMP085 sensors
BLACK_VORTEX
MULTIWII_PRO_EZ3_BLACK -- ReadyToFlyQuads - MultiWii PRO Ez3.0 Blacked MAG Editon Flight Controller w/ GPS Option (NO COMPASS)
PARIS_V5_OSD -- PARIS v5 Mega iOSD - http://www.multiwiicopter.com/products/multiwii-paris-v5-mega-iosd-gps-autopilot
*/

// GPS port speed (Serial2) 38400 by default
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/ArduPlane.pde
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef THISFIRMWARE
# define THISFIRMWARE "ArduPlane V2.74beta MPNG-R3b"
# define THISFIRMWARE "ArduPlane V2.74beta MPNG-R4"
#endif
/*
* Lead developer: Andrew Tridgell
Expand Down
4 changes: 4 additions & 0 deletions ArduPlane/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -135,6 +135,10 @@
#if MPNG_BOARD_TYPE == HK_RED_MULTIWII_PRO || MPNG_BOARD_TYPE == BLACK_VORTEX
# define CONFIG_INS_TYPE CONFIG_INS_ITG3200
# define CONFIG_BARO AP_BARO_BMP085_MPNG
#elif MPNG_BOARD_TYPE == PARIS_V5_OSD
# define CONFIG_INS_TYPE CONFIG_INS_ITG3200
# define CONFIG_BARO AP_BARO_MS5611
# define CONFIG_MS5611_SERIAL AP_BARO_MS5611_I2C
#else
# define CONFIG_INS_TYPE CONFIG_INS_MPU6000_I2C
# define CONFIG_BARO AP_BARO_MS5611
Expand Down
1 change: 1 addition & 0 deletions ArduPlane/defines.h
Original file line number Diff line number Diff line change
Expand Up @@ -266,6 +266,7 @@ enum log_messages {
#define HK_RED_MULTIWII_PRO 3
#define BLACK_VORTEX 4
#define MULTIWII_PRO_EZ3_BLACK 5
#define PARIS_V5_OSD 6

// altitude control algorithms
enum {
Expand Down
47 changes: 0 additions & 47 deletions MPNG - README - MPNG.txt

This file was deleted.

2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Release Notes for MegaPirateNG 3.0.1 R3 BETA (based on ArduPilot 3.0.1)
# Release Notes for MegaPirateNG 3.0.1 R4 (based on ArduPilot 3.0.1)

## How to compile and configure MegaPirateNG
Follow instructions at: http://docs.megapirateng.com
Expand Down
46 changes: 31 additions & 15 deletions libraries/AP_InertialSensor/AP_InertialSensor_ITG3200.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,10 +10,6 @@ extern const AP_HAL::HAL& hal;

#define ITG3200_ADDRESS 0x68 // 0xD0

// accelerometer scaling
#define ACCEL_SCALE_1G (GRAVITY_MSS / 2730.0)


#define GYRO_SMPLRT_50HZ 19 // 1KHz/(divider+1)
#define GYRO_SMPLRT_100HZ 9 // 1KHz/(divider+1)
#define GYRO_SMPLRT_200HZ 4 // 1KHz/(divider+1)
Expand All @@ -25,7 +21,10 @@ extern const AP_HAL::HAL& hal;
#define GYRO_DLPF_CFG_98HZ 2

// ITG-3200 14.375 LSB/degree/s
const float AP_InertialSensor_ITG3200::_gyro_scale = 0.0012141421; // ToRad(1/14.375)
float AP_InertialSensor_ITG3200::_gyro_scale = 0.0012141421; // ToRad(1/14.375)
float AP_InertialSensor_ITG3200::_accel_scale_1G = (GRAVITY_MSS / 2730.0f); // 2730 LSB = 1G



uint8_t AP_InertialSensor_ITG3200::_gyro_data_index[3] = { 1, 2, 0 };
uint8_t AP_InertialSensor_ITG3200::_accel_data_index[3] = { 4, 5, 6 };
Expand All @@ -35,6 +34,7 @@ int8_t AP_InertialSensor_ITG3200::_accel_data_sign[3] = { 1, 1, -1 };
const uint8_t AP_InertialSensor_ITG3200::_temp_data_index = 3;

uint8_t AP_InertialSensor_ITG3200::_accel_addr = 0x40;
uint8_t AP_InertialSensor_ITG3200::_board_type = 0;
uint16_t AP_InertialSensor_ITG3200::_micros_per_sample = 9500; // 100Hz

/* Static I2C device driver */
Expand All @@ -45,10 +45,20 @@ static volatile uint32_t _ins_timer = 0;
AP_InertialSensor_ITG3200::AP_InertialSensor_ITG3200(uint8_t board_type): AP_InertialSensor()
{
_initialised = false;
_board_type = board_type;

if (board_type == BLACK_VORTEX) {
if (_board_type == BLACK_VORTEX) {
_accel_addr = 0x41;
}
_accel_scale_1G = (GRAVITY_MSS / 1024.0f); // BMA280 - 1024 LSB = 1G
} else if (_board_type == PARIS_V5_OSD) {
_accel_addr = 0x18;
_gyro_scale = 0.0010642251536551; // ITG3050 - 16.4 LSB/degree/s = ToRad(1/16.4)
_accel_scale_1G = (GRAVITY_MSS / 1024.0f); // BMA280 - 1024 LSB = 1G
_gyro_data_index[0] = 2; _gyro_data_index[1] = 1; _gyro_data_index[2] = 0;
_accel_data_index[0] = 4; _accel_data_index[1] = 5; _accel_data_index[2] = 6;
_gyro_data_sign[0] = -1; _gyro_data_sign[1] = 1; _gyro_data_sign[2] = -1;
_accel_data_sign[0] = 1; _accel_data_sign[1] = 1; _accel_data_sign[2] = -1;
}
}

uint16_t AP_InertialSensor_ITG3200::_init_sensor(Sample_rate sample_rate)
Expand Down Expand Up @@ -148,7 +158,7 @@ bool AP_InertialSensor_ITG3200::update( void )
_accel_data_sign[2] * sum[_accel_data_index[2]]);

_accel.rotate(_board_orientation);
_accel *= count_scale * ACCEL_SCALE_1G;
_accel *= count_scale * _accel_scale_1G;
_accel.x *= accel_scale.x;
_accel.y *= accel_scale.y;
_accel.z *= accel_scale.z;
Expand Down Expand Up @@ -246,7 +256,7 @@ void AP_InertialSensor_ITG3200::_read_data_transaction()

memset(raw,0,6);
hal.i2c->readRegisters(_accel_addr, 0x02, 6, raw);
_sum[4] += (int16_t)(((uint16_t)raw[3] << 8) | raw[2]) >> 2;
_sum[4] += (int16_t)(((uint16_t)raw[3] << 8) | raw[2]) >> 2; // Lower 2 bits has no data, we just cut it
_sum[5] += (int16_t)(((uint16_t)raw[1] << 8) | raw[0]) >> 2;
_sum[6] += (int16_t)(((uint16_t)raw[5] << 8) | raw[4]) >> 2;

Expand Down Expand Up @@ -327,13 +337,19 @@ bool AP_InertialSensor_ITG3200::hardware_init(Sample_rate sample_rate)
hal.i2c->writeRegister(ITG3200_ADDRESS, 0x3E, 0x03);
hal.scheduler->delay(10);

hal.i2c->writeRegister(_accel_addr, 0x0D, 1<<4);
hal.scheduler->delay(1);
hal.i2c->writeRegister(_accel_addr, 0x35, 3<<1);
hal.scheduler->delay(1);
hal.i2c->writeRegister(_accel_addr, 0x20, 0<<4);
if (_board_type == PARIS_V5_OSD) {
hal.i2c->writeRegister(_accel_addr, 0x10, 0x09); // acceleration data filter bandwidth = 15,63Hz
hal.scheduler->delay(5);
hal.i2c->writeRegister(_accel_addr, 0x0F, 0x08); // range = 8G
} else {
hal.i2c->writeRegister(_accel_addr, 0x0D, 1<<4);
hal.scheduler->delay(1);
hal.i2c->writeRegister(_accel_addr, 0x35, 3<<1); // range = 8G
hal.scheduler->delay(1);
hal.i2c->writeRegister(_accel_addr, 0x20, 0<<4);
}
hal.scheduler->delay(10);

_i2c_sem->give();

return true;
Expand Down
6 changes: 5 additions & 1 deletion libraries/AP_InertialSensor/AP_InertialSensor_ITG3200.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
#define RCTIMER_CRIUS_V2 2
#define HK_RED_MULTIWII_PRO 3
#define BLACK_VORTEX 4
#define MULTIWII_PRO_EZ3_BLACK 5
#define PARIS_V5_OSD 6

class AP_InertialSensor_ITG3200 : public AP_InertialSensor
{
Expand Down Expand Up @@ -55,7 +57,8 @@ class AP_InertialSensor_ITG3200 : public AP_InertialSensor

float _temp_to_celsius( uint16_t );

static const float _gyro_scale;
static float _gyro_scale;
static float _accel_scale_1G;

static uint8_t _gyro_data_index[3];
static int8_t _gyro_data_sign[3];
Expand All @@ -66,6 +69,7 @@ class AP_InertialSensor_ITG3200 : public AP_InertialSensor
static const uint8_t _temp_data_index;

static uint8_t _accel_addr;
static uint8_t _board_type;
static uint16_t _micros_per_sample;

// ensure we can't initialise twice
Expand Down

0 comments on commit 04eb468

Please sign in to comment.