1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 12:25:20 +03:00

CJMCU - Add compass driver. Update I2C configuration. Use PPM and

Brushed motors by default.
This commit is contained in:
Dominic Clifton 2014-08-01 00:56:28 +01:00
parent 5e045616fa
commit 1d5ef51373
10 changed files with 30 additions and 4 deletions

View file

@ -231,6 +231,7 @@ CJMCU_SRC = startup_stm32f10x_md_gcc.S \
drivers/accgyro_mpu6050.c \
drivers/bus_i2c_stm32f10x.c \
drivers/bus_spi.c \
drivers/compass_hmc5883l.c \
drivers/gpio_stm32f10x.c \
drivers/light_led_stm32f10x.c \
drivers/pwm_mapping.c \

View file

@ -20,6 +20,7 @@
#include <string.h>
#include "platform.h"
#include "build_config.h"
#include "common/axis.h"
@ -56,6 +57,8 @@
#include "config/config_profile.h"
#include "config/config_master.h"
#define BRUSHED_MOTORS_PWM_RATE 16000
#define BRUSHLESS_MOTORS_PWM_RATE 400
void setPIDController(int type); // FIXME PID code needs to be in flight_pid.c/h
void mixerUseConfigs(servoParam_t *servoConfToUse, flight3DConfig_t *flight3DConfigToUse,
@ -214,6 +217,9 @@ static void resetConf(void)
masterConfig.version = EEPROM_CONF_VERSION;
masterConfig.mixerConfiguration = MULTITYPE_QUADX;
featureClearAll();
#ifdef CJMCU
featureSet(FEATURE_RX_PPM);
#endif
featureSet(FEATURE_VBAT);
// global settings
@ -259,7 +265,12 @@ static void resetConf(void)
// Motor/ESC/Servo
resetEscAndServoConfig(&masterConfig.escAndServoConfig);
resetFlight3DConfig(&masterConfig.flight3DConfig);
masterConfig.motor_pwm_rate = 400;
#ifdef BRUSHED_MOTORS
masterConfig.motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE;
#else
masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
#endif
masterConfig.servo_pwm_rate = 50;
#ifdef GPS

View file

@ -162,7 +162,7 @@ void i2cInitPort(I2C_TypeDef *I2Cx)
void i2cInit(I2CDevice index)
{
i2cInitPort(I2C1); // hard coded to use I2C1 for now
i2cInitPort(I2C1); // FIXME hard coded to use I2C1 for now
}
uint16_t i2cGetErrorCounter(void)

View file

@ -126,7 +126,7 @@ void systemInit(bool overclock)
#ifndef CC3D
// Configure the rest of the stuff
i2cInit(I2CDEV_2);
i2cInit(I2C_DEVICE);
#endif
// sleep for 100ms

View file

@ -40,6 +40,8 @@
#define LED0
#define LED1
#define I2C_DEVICE (I2CDEV_1)
#define SENSORS_SET (SENSOR_ACC)
#define GPS

View file

@ -33,9 +33,12 @@
#define ACC
#define GYRO
#define MOTOR_PWM_RATE 16000
#define MAG
#define BRUSHED_MOTORS
#define I2C_DEVICE (I2CDEV_1)
// #define SOFT_I2C // enable to test software i2c
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
// #define SOFT_I2C_PB67

View file

@ -41,10 +41,13 @@
#define LED0
#define LED1
#define I2C_DEVICE (I2CDEV_2)
// #define SOFT_I2C // enable to test software i2c
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
// #define SOFT_I2C_PB67
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
#define GPS

View file

@ -30,6 +30,8 @@
#define GYRO
#define ACC
#define I2C_DEVICE (I2CDEV_1)
#define SENSORS_SET (SENSOR_ACC)
#define GPS

View file

@ -40,6 +40,8 @@
#define GYRO
#define MAG
#define I2C_DEVICE (I2CDEV_1)
// #define SOFT_I2C // enable to test software i2c
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
// #define SOFT_I2C_PB67

View file

@ -42,6 +42,8 @@
#define LED0
#define LED1
#define I2C_DEVICE (I2CDEV_1)
#define SENSORS_SET (SENSOR_ACC)
#define GPS