Код: Выделить всё
//LGT8F328P SSOP-20 32Mhz internal
#include <Wire.h>
#include <ModbusRtu.h>
#include <EEPROM.h>
#include <WDT.h>
#define call_button 3
#define txen 7
#define dev_id 2
#define zummer 2
#define mpu_adr 0x68
#define qmc_adr 0x0D
#define qmc_period 0x0B
#define qmc_cntrl_1 0x09
#define qmc_cntrl_2 0x0A
#define qmc_status 0x06
#define pwr_mgmt_1 0x6B
#define mpu_status 0x3A
#define int_en 0x38
#define gyro_out 0x43
#define accel_out 0x3B
#define qmc_out 0x00
#define depth 64
Modbus slave(dev_id, Serial, txen);
int gyro_offs[] = { 0, 0, 0 };
int accel_offs[] = { 0, 0, 0 };
int qmc_matrix[] = { -1, 1, -1, 1, -1, 1 };
float pitch_offs = 0, roll_offs = 0;
long lastTime=0;
float aver_pitch[depth], aver_roll[depth], aver_mag[depth];
float qmc_data[3];
float accel_data[3];
float gyro_data[3];
unsigned int fld_data[3];
void(* resetFunc) (void) = 0;
void setup() {
Wire.begin();
writeByte(mpu_adr, pwr_mgmt_1, 0x00);
writeByte(mpu_adr, pwr_mgmt_1, 0x01);
writeByte(qmc_adr, qmc_cntrl_2, 0x80);
writeByte(qmc_adr, qmc_period, 0x01);
writeByte(qmc_adr, qmc_cntrl_1, 0x0D);
Serial.begin(38400);
pinMode(call_button, INPUT_PULLUP);
pinMode(zummer,OUTPUT);
EEPROM.get(0, qmc_matrix[0]);
EEPROM.get(4, qmc_matrix[1]);
EEPROM.get(8, qmc_matrix[2]);
EEPROM.get(12, qmc_matrix[3]);
EEPROM.get(16, qmc_matrix[4]);
EEPROM.get(20, qmc_matrix[5]);
EEPROM.get(24, gyro_offs[0]);
EEPROM.get(28, gyro_offs[1]);
EEPROM.get(32, gyro_offs[2]);
EEPROM.get(36, accel_offs[0]);
EEPROM.get(40, accel_offs[1]);
EEPROM.get(44, accel_offs[2]);
EEPROM.get(50, pitch_offs);
EEPROM.get(60, roll_offs);
// Serial.println();
// Serial.println("QMC matrix is:");
// Serial.print(qmc_matrix[0]);
// Serial.print("\t");
// Serial.print(qmc_matrix[1]);
// Serial.print("\t");
// Serial.print(qmc_matrix[2]);
// Serial.print("\t");
// Serial.print(qmc_matrix[3]);
// Serial.print("\t");
// Serial.print(qmc_matrix[4]);
// Serial.print("\t");
// Serial.print(qmc_matrix[5]);
// Serial.println();
// Serial.println("GYRO offset is:");
// Serial.print(gyro_offs[0]);
// Serial.print("\t");
// Serial.print(gyro_offs[1]);
// Serial.print("\t");
// Serial.print(gyro_offs[2]);
// Serial.println();
// Serial.println("ACCEL offset is:");
// Serial.print(accel_offs[0]);
// Serial.print("\t");
// Serial.print(accel_offs[1]);
// Serial.print("\t");
// Serial.print(accel_offs[2]);
// Serial.println();
// Serial.println("Roll/Pitch correction is:");
// Serial.print(roll_offs);
// Serial.print("\t");
// Serial.print(pitch_offs);
// delay(5000);
slave.start();
wdt_enable(WTO_8S);
lastTime = millis();
}
void loop() {
static unsigned int count = 0;
static float g_roll, g_pitch, pitch, roll;
check_button();
wdt_reset();
long newTime = millis();
float elapsedTime = (float)(newTime - lastTime) / 1000.0f;
readMagData(qmc_data);
readAccelData(accel_data);
readGyroData(gyro_data);
float r = sqrtf(pow(accel_data[0],2)+pow(accel_data[1],2)+pow(accel_data[2],2));
roll = (-asin(accel_data[1]/r)* 180 / PI) - roll_offs;
pitch = (asin(accel_data[0]/r)* 180 / PI) - pitch_offs;
g_roll += gyro_data[0] * elapsedTime;
g_pitch += gyro_data[1] * elapsedTime;
pitch = 0.90 * g_pitch + 0.10 * pitch;
roll = 0.90 * g_roll + 0.10 * roll;
float sum_pitch = 0, sum_roll = 0;
for (byte i = depth - 1; i > 0; i--) {
aver_pitch[i] = aver_pitch[i - 1];
sum_pitch += aver_pitch[i - 1];
aver_roll[i] = aver_roll[i - 1];
sum_roll += aver_roll[i - 1];
}
aver_pitch[0] = pitch;
aver_roll[0] = roll;
roll = (sum_roll + roll) / depth;
pitch = (sum_pitch + pitch) / depth;
g_roll = roll;
g_pitch = pitch;
float pitch_rad = PI / 180 * pitch ;
float roll_rad = PI / 180 * roll;
float cx = qmc_data[0] * cos(pitch_rad) + qmc_data[1] * sin(roll_rad) * sin(pitch_rad) - qmc_data[2] * cos(roll_rad) * sin(pitch_rad);
float cy = qmc_data[1] * cos(roll_rad) + qmc_data[2] * sin(roll_rad);
int az_rad = 180 / PI * atan2(cy, cx);
int azimuth = round((int)(az_rad + 360.0) % 360);
int sum_mag = 0;
for (byte i = depth - 1; i > 0; i--) {
aver_mag[i] = aver_mag[i - 1];
sum_mag += aver_mag[i - 1];
}
aver_mag[0] = azimuth;
azimuth = (azimuth + sum_mag) / depth;
fld_data[0] = round(pitch);
fld_data[1] = round(roll);
fld_data[2] = azimuth;
slave.poll(fld_data, 3);
// Serial.println();
// Serial.print(roll);
// Serial.print("\t");
// Serial.print(pitch);
// Serial.print("\t");
// Serial.print(azimuth);
if (count % 100 == 0) digitalToggle(LED_BUILTIN);
lastTime = newTime;
count++;
}
void readAccelData(float * destination)
{
byte rawData[6];
readBytes(mpu_adr, accel_out, 6, &rawData[0]);
// destination[0] = (float)(((int)rawData[0] << 8 | rawData[1]) - accel_offs[0] ) / 16384.0;
// destination[1] = (float)(((int)rawData[2] << 8 | rawData[3]) - accel_offs[1] ) / 16384.0;
// destination[2] = (float)(((int)rawData[4] << 8 | rawData[5]) - accel_offs[2] ) / 16384.0;
destination[0] = (float)(((int)rawData[0] << 8 | rawData[1]) ) / 16384.0;
destination[1] = (float)(((int)rawData[2] << 8 | rawData[3]) ) / 16384.0;
destination[2] = (float)(((int)rawData[4] << 8 | rawData[5]) ) / 16384.0;
}
void readGyroData(float * destination)
{
byte rawData[6];
readBytes(mpu_adr, gyro_out, 6, &rawData[0]);
destination[0] = (float)(((int)rawData[0] << 8 | rawData[1]) - gyro_offs[0]) / 131.0;
destination[1] = (float)(((int)rawData[2] << 8 | rawData[3]) - gyro_offs[1]) / 131.0;
destination[2] = (float)(((int)rawData[4] << 8 | rawData[5]) - gyro_offs[2]) / 131.0;
}
void readMagData(float* destination) {
byte rawData[6];
while (!qmc_isReady()){}
readBytes(qmc_adr, qmc_out, 6, &rawData[0]);
int mX = (int)rawData[0] | rawData[1] << 8;
int mY = (int)rawData[2] | rawData[3] << 8;
int mZ = (int)rawData[4] | rawData[5] << 8;
float x_ofs = (float)(qmc_matrix[0] + qmc_matrix[1]) / 2.0;
float y_ofs = (float)(qmc_matrix[2] + qmc_matrix[3]) / 2.0;
float z_ofs = (float)(qmc_matrix[4] + qmc_matrix[5]) / 2.0;
float x_avg_delta = (float)(qmc_matrix[1] - qmc_matrix[0]) / 2.0;
float y_avg_delta = (float)(qmc_matrix[3] - qmc_matrix[2]) / 2.0;
float z_avg_delta = (float)(qmc_matrix[5] - qmc_matrix[4]) / 2.0;
float avg_delta = (x_avg_delta + y_avg_delta + z_avg_delta) / 3.0;
float x_scale = avg_delta / x_avg_delta;
float y_scale = avg_delta / y_avg_delta;
float z_scale = avg_delta / z_avg_delta;
destination[0] = (float)((mX - x_ofs) * x_scale) ;
destination[1] = (float)((mY - y_ofs) * y_scale) ;
destination[2] = (float)((mZ - z_ofs) * z_scale) ;
}
void check_button() {
byte rawData[6];
long gX = 0, gY = 0, gZ = 0;
long a_X = 0, a_Y = 0, a_Z = 0;
float pitch_err = 0, roll_err = 0;
if (!digitalRead(call_button)) {
zummer_play(1);
//Serial.println();
//Serial.println("Put MPU on horizontal surface.");
for (int i = 0; i < 5000; i++) {
readBytes(mpu_adr, gyro_out, 6, &rawData[0]);
gX += (int)rawData[0] << 8 | rawData[1];
gY += (int)rawData[2] << 8 | rawData[3];
gZ += (int)rawData[4] << 8 | rawData[5];
readBytes(mpu_adr, accel_out, 6, &rawData[0]);
a_X += (int)rawData[0] << 8 | rawData[1];
a_Y += (int)rawData[2] << 8 | rawData[3];
a_Z += (int)rawData[4] << 8 | rawData[5];
if (i % 150 == 0) {
digitalToggle(LED_BUILTIN);
wdt_reset();
// Serial.print(".");
zummer_play(5);
}
}
gyro_offs[0] = gX / 5000;
gyro_offs[1] = gY / 5000;
gyro_offs[2] = gZ / 5000;
accel_offs[0] = a_X/5000;
accel_offs[1] = a_Y/5000;
accel_offs[2] = a_Z/5000;
EEPROM.put(24, gyro_offs[0]);
EEPROM.put(28, gyro_offs[1]);
EEPROM.put(32, gyro_offs[2]);
EEPROM.put(36, accel_offs[0]);
EEPROM.put(40, accel_offs[1]);
EEPROM.put(44, accel_offs[2]);
// Serial.println();
// Serial.println("GYRO offset is:");
// Serial.print(gyro_offs[0]);
// Serial.print("\t");
// Serial.print(gyro_offs[1]);
// Serial.print("\t");
// Serial.print(gyro_offs[2]);
// Serial.println();
// Serial.println("ACCEL offset is:");
// Serial.print(accel_offs[0]);
// Serial.print("\t");
// Serial.print(accel_offs[1]);
// Serial.print("\t");
// Serial.print(accel_offs[2]);
zummer_play(2);
// Serial.println();
// Serial.println("Calculate roll/pitch correction");
for (int i = 0; i < 5000; i++) {
readBytes(mpu_adr, accel_out, 6, &rawData[0]);
// float aX = (float)(((int)rawData[0] << 8 | rawData[1]) - accel_offs[0]) / 16384.0;
// float aY = (float)(((int)rawData[2] << 8 | rawData[3]) - accel_offs[1]) / 16384.0;
// float aZ = (float)(((int)rawData[4] << 8 | rawData[5]) - accel_offs[2]) / 16384.0;
float aX = (float)(((int)rawData[0] << 8 | rawData[1]) ) / 16384.0;
float aY = (float)(((int)rawData[2] << 8 | rawData[3]) ) / 16384.0;
float aZ = (float)(((int)rawData[4] << 8 | rawData[5]) ) / 16384.0;
float r = sqrtf(pow(aX,2)+pow(aY,2)+pow(aZ,2));
roll_err += (-asin(aY/r)* 180 / PI);
pitch_err += (asin(aX/r)* 180 / PI);
if (i % 100 == 0) {
digitalToggle(LED_BUILTIN);
wdt_reset();
// Serial.print('.');
zummer_play(5);
}
}
pitch_offs = pitch_err / 5000.0;
roll_offs = roll_err / 5000.0;
EEPROM.put(50, pitch_offs);
EEPROM.put(60, roll_offs);
// Serial.println();
// Serial.println("Roll/Pitch correction is:");
// Serial.print(roll_offs);
// Serial.print("\t");
// Serial.print(pitch_offs);
zummer_play(3);
// Serial.println();
// Serial.println("Take QMC and twirl around.");
for (int i = 0; i < 5000; i++) {
while (!qmc_isReady())
readBytes(qmc_adr, qmc_out, 6, &rawData[0]);
int X = ((int)rawData[0]) | rawData[1] << 8;
int Y = ((int)rawData[2]) | rawData[3] << 8;
int Z = ((int)rawData[4]) | rawData[5] << 8;
delay(10);
if (X < 0 && X < qmc_matrix[0]) qmc_matrix[0] = X;
if (X > 0 && X > qmc_matrix[1]) qmc_matrix[1] = X;
if (Y < 0 && Y < qmc_matrix[2]) qmc_matrix[2] = Y;
if (Y > 0 && Y > qmc_matrix[3]) qmc_matrix[3] = Y;
if (Z < 0 && Z < qmc_matrix[4]) qmc_matrix[4] = Z;
if (Z > 0 && Z > qmc_matrix[5]) qmc_matrix[5] = Z;
if (i % 50 == 0) {
wdt_reset();
digitalToggle(LED_BUILTIN);
// Serial.print('.');
zummer_play(5);
}
}
EEPROM.put(0, qmc_matrix[0]);
EEPROM.put(4, qmc_matrix[1]);
EEPROM.put(8, qmc_matrix[2]);
EEPROM.put(12, qmc_matrix[3]);
EEPROM.put(16, qmc_matrix[4]);
EEPROM.put(20, qmc_matrix[5]);
// Serial.println();
// Serial.println("QMC matrix is:");
// Serial.print(qmc_matrix[0]);
// Serial.print("\t");
// Serial.print(qmc_matrix[1]);
// Serial.print("\t");
// Serial.print(qmc_matrix[2]);
// Serial.print("\t");
// Serial.print(qmc_matrix[3]);
// Serial.print("\t");
// Serial.print(qmc_matrix[4]);
// Serial.print("\t");
// Serial.print(qmc_matrix[5]);
// Serial.println();
zummer_play(4);
resetFunc();
}
}
void zummer_play(byte par) {
// Morse "K"
switch (par) {
case 1:
// Morse "K"
wdt_reset();
digitalWrite(zummer,HIGH);
delay(500);
digitalWrite(zummer,LOW);
delay(100);
digitalWrite(zummer,HIGH);
delay(250);
digitalWrite(zummer,LOW);
delay(100);
digitalWrite(zummer,HIGH);
delay(500);
digitalWrite(zummer,LOW);
delay(250);
break;
case 2:
// Morse "C"
wdt_reset();
digitalWrite(zummer,HIGH);
delay(500);
digitalWrite(zummer,LOW);
delay(100);
digitalWrite(zummer,HIGH);
delay(250);
digitalWrite(zummer,LOW);
delay(100);
digitalWrite(zummer,HIGH);
delay(500);
digitalWrite(zummer,LOW);
delay(100);
digitalWrite(zummer,HIGH);
delay(250);
digitalWrite(zummer,LOW);
delay(250);
break;
case 3:
// Morse "S"
wdt_reset();
digitalWrite(zummer,HIGH);
delay(250);
digitalWrite(zummer,LOW);
delay(100);
digitalWrite(zummer,HIGH);
delay(250);
digitalWrite(zummer,LOW);
delay(100);
digitalWrite(zummer,HIGH);
delay(250);
digitalWrite(zummer,LOW);
delay(100);
digitalWrite(zummer,LOW);
delay(250);
break;
case 4:
// Morse "Q"
wdt_reset();
digitalWrite(zummer,HIGH);
delay(500);
digitalWrite(zummer,LOW);
delay(100);
digitalWrite(zummer,HIGH);
delay(500);
digitalWrite(zummer,LOW);
delay(100);
digitalWrite(zummer,HIGH);
delay(250);
digitalWrite(zummer,LOW);
delay(100);
digitalWrite(zummer,HIGH);
delay(500);
digitalWrite(zummer,LOW);
delay(250);
break;
case 5:
digitalWrite(zummer,HIGH);
delay(10);
digitalWrite(zummer,LOW);
break;
default: break;
}
}
bool qmc_isReady(void) {
byte status = readByte(qmc_adr, qmc_status);
return bitRead(status, 0);
}
byte readByte(byte address, byte subAddress) {
byte data;
Wire.beginTransmission(address);
Wire.write(subAddress);
Wire.endTransmission(false);
Wire.requestFrom(address, (byte)1);
data = Wire.read();
return data;
}
void writeByte(byte address, byte subAddress, byte data) {
Wire.beginTransmission(address);
Wire.write(subAddress);
Wire.write(data);
Wire.endTransmission();
}
void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t* dest) {
Wire.beginTransmission(address);
Wire.write(subAddress);
Wire.endTransmission(false);
uint8_t i = 0;
Wire.requestFrom(address, count);
while (Wire.available()) dest[i++] = Wire.read();
}