// Descriptions: Contains code to interface with various sensors:
// -Gyro/Accelerometer (MPU6050/I2Cdev) - https://github.com/jrowberg/i2cdevlib by Jeff Rowberg <jeff@rowberg.net>
// -Temperature (DS18B20) - http://bildr.org/2011/07/ds18b20-arduino/
// -Hall Effect Sensor - https://diyhacking.com/arduino-hall-effect-sensor-tutorial/
// -AttoPilot Current and Voltage Sensing - https://www.sparkfun.com/products/9028
//
// And for transmission to Taranis handheld radio transmitter via MavLink/FrSky X8R SPort interface:
// http://diydrones.com/profiles/blogs/how-to-get-apm-pixhawk-telemetry-on-your-taranis-brought-to-you
/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2012 Jeff Rowberg
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
===============================================
*/
//MPU6050 Gyro/Accelerometer Includes
#include "I2Cdev2.h"
//#include "Wire.h"
#include "MPU6050_6Axis_MotionApps20a.h"
// class default I2C address is 0x68
// specific I2C addresses may be passed as a parameter here
// AD0 low = 0x68 (default for SparkFun breakout and InvenSense evaluation board)
// AD0 high = 0x69
MPU6050a mpu;
//MPU6050 mpu(0x69); // <-- use for AD0 high
#define OUTPUT_READABLE_REALACCEL
//Temperature Sensor Includes
#include <OneWire.h>
//I2C Communication Includes
//#include "I2C_Anything.h"
#include <i2c_t3.h>
//#include <i2c_t3a.h>
// MAVLINK_FRSKYSPORT Includes
//#include <GCS_MAVLink.h>
#include "FrSkySPort.h"
#define debugSerial Serial
#define _MavLinkSerial Serial2
#define START 1
#define MSG_RATE 10 // Hertz
#include <AltSoftSerial.h>
//Setup LED blinking
#define LED_PIN 13 // (Arduino is 13, Teensy is 11, Teensy++ is 6)
bool blinkState = false;
// MPU6050 Gyro/Accel control/status vars
bool dmpReady = false; // set true if DMP init was successful
uint8_t mpuIntStatus; // holds actual interrupt status byte from MPU
uint8_t devStatus; // return status after each device operation (0 = success, !0 = error)
uint16_t packetSize; // expected DMP packet size (default is 42 bytes)
uint16_t fifoCount; // count of all bytes currently in FIFO
uint8_t fifoBuffer[64]; // FIFO storage buffer
uint8_t TeensyIntPin = 3; //Identify Teensy interrupt pin
// MPU6050 Gyro/Accel orientation/motion vars
Quaternion q; // [w, x, y, z] quaternion container
VectorInt16 aa; // [x, y, z] accel sensor measurements
VectorInt16 aaReal; // [x, y, z] gravity-free accel sensor measurements
VectorInt16 aaWorld; // [x, y, z] world-frame accel sensor measurements
VectorFloat gravity; // [x, y, z] gravity vector
float euler[3]; // [psi, theta, phi] Euler angle container
float ypr[3]; // [yaw, pitch, roll] yaw/pitch/roll container and gravity vector
// packet structure for InvenSense teapot demo
uint8_t teapotPacket[14] = { '$', 0x02, 0, 0, 0, 0, 0, 0, 0, 0, 0x00, 0x00, '\r', '\n' };
// ======================================================================
// MAVLINK_FRSKYSPORT Declarations
// ******************************************
// Message #0 HEARTHBEAT
uint8_t ap_type = 0;
uint8_t ap_autopilot = 0;
uint8_t ap_base_mode = 0;
uint32_t ap_custom_mode = 0;
uint8_t ap_system_status = 0;
uint8_t ap_mavlink_version = 0;
// Message # 1 SYS_STATUS
uint16_t ap_voltage_battery = 0; // 1000 = 1V
int16_t ap_current_battery = 0; // 10 = 1A
// Message #24 GPS_RAW_INT
uint8_t ap_fixtype = 0; // 0= No GPS, 1 = No Fix, 2 = 2D Fix, 3 = 3D Fix
uint8_t ap_sat_visible = 0; // numbers of visible satelites
// FrSky Taranis uses the first recieved lat/long as homeposition.
int32_t ap_latitude = 0; // 585522540;
int32_t ap_longitude = 0; // 162344467;
int32_t ap_gps_altitude = 0; // 1000 = 1m
// Message #74 VFR_HUD
int32_t ap_airspeed = 0;
uint32_t ap_groundspeed = 0;
uint32_t ap_heading = 0;
uint16_t ap_throttle = 0;
// FrSky Taranis uses the first recieved value after 'PowerOn' or 'Telemetry Reset' as zero altitude
int32_t ap_bar_altitude = 0; // 100 = 1m
int32_t ap_climb_rate = 0; // 100= 1m/s
// Message #27 RAW IMU
int32_t ap_accX = 0;
int32_t ap_accY = 0;
int32_t ap_accZ = 0;
int32_t ap_accX_old = 0;
int32_t ap_accY_old = 0;
int32_t ap_accZ_old = 0;
// ******************************************
// These are special for FrSky
int32_t adc2 = 0; // 100 = 1.0V
int32_t vfas = 0; // 100 = 1,0V
int32_t gps_status = 0; // (ap_sat_visible * 10) + ap_fixtype
// ex. 83 = 8 sattelites visible, 3D lock
// ******************************************
//uint8_t MavLink_Connected;
//uint8_t buf[MAVLINK_MAX_PACKET_LEN];
uint16_t hb_count;
unsigned long MavLink_Connected_timer;
unsigned long hb_timer;
unsigned long acc_timer;
int led = 13;
//mavlink_message_t msg;
// ***************************
AltSoftSerial altSerial;
int DS18S20_Pin = 2; //DS18S20 Signal pin on digital 2 (tempearature sensor)
//Temperature chip i/o
OneWire ds(DS18S20_Pin); // on digital pin 2
int count = 0;
//=======================================================================
//Arduino Hall Effect Sensor
volatile byte half_revolutions;
unsigned int rpm;
unsigned long timeold;
int US1881_Pin = 4; //US1881 Signal pin on digital 4 (hall effect sensor)
//byte Wiredata[8];
//volatile boolean haveData=false;
//volatile float VFinal;
//volatile float IFinal;
//const byte MY_ADDRESS = 42;
//--------------------------------------------
//Get Volt/Curr Data
#define MEM_LEN 256
int VRaw; //This will store our raw ADC data
int IRaw;
float VFinal; //This will store the converted data
float IFinal;
//--------------------------------------------
//i2c_t3 I2C Comm Declarations
//----------------------------------------------
// Function prototypes
void receiveEvent(size_t count);
void requestEvent(void);
//Memory
uint8_t databuf[MEM_LEN];
volatile uint8_t received;
//----------------------------------------------
// ================================================================
// === INTERRUPT DETECTION ROUTINE ===
// ================================================================
volatile bool mpuInterrupt = false; // indicates whether MPU interrupt pin has gone high
void dmpDataReady() {
mpuInterrupt = true;
}
float getTemp() {
//returns the temperature from one DS18S20 in DEG Celsius
byte data[12];
byte addr[8];
if ( !ds.search(addr)) {
//no more sensors on chain, reset search
ds.reset_search();
return -1000;
}
if ( OneWire::crc8( addr, 7) != addr[7]) {
Serial.println("CRC is not valid!");
return -1000;
}
if ( addr[0] != 0x10 && addr[0] != 0x28) {
Serial.print("Device is not recognized");
return -1000;
}
ds.reset();
ds.select(addr);
ds.write(0x44, 1); // start conversion, with parasite power on at the end
byte present = ds.reset();
ds.select(addr);
ds.write(0xBE); // Read Scratchpad
for (int i = 0; i < 9; i++) { // we need 9 bytes
data[i] = ds.read();
}
ds.reset_search();
byte MSB = data[1];
byte LSB = data[0];
//Serial.println(data);
float tempRead = ((MSB << 8) | LSB); //using two's compliment
float TemperatureSum = tempRead / 16;
return TemperatureSum;
}
// ================================================================
// === INITIAL SETUP ===
// ================================================================
void setup() {
//Activate internal pullup resistor for DS18S20 temp sensor
pinMode(DS18S20_Pin, INPUT_PULLUP);
// join I2C bus (I2Cdev library doesn't do this automatically)
#if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
Wire.begin(MPU6050_DEFAULT_ADDRESS);
//TWBR = 24; // 400kHz I2C clock (200kHz if CPU is 8MHz)
#elif I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE
Fastwire::setup(400, true);
#endif
// initialize serial communication
// (115200 chosen because it is required for Teapot Demo output, but it's
// really up to you depending on your project)
Serial.begin(115200);
altSerial.begin(115200);
while (!Serial); // wait for Leonardo enumeration, others continue immediately
// NOTE: 8MHz or slower host processors, like the Teensy @ 3.3v or Ardunio
// Pro Mini running at 3.3v, cannot handle this baud rate reliably due to
// the baud timing being too misaligned with processor ticks. You must use
// 38400 or slower in these cases, or use some kind of external separate
// crystal solution for the UART timer.
// initialize device
Serial.println(F("Initializing I2C devices..."));
mpu.initialize();
// verify connection
Serial.println(F("Testing device connections..."));
Serial.println(mpu.testConnection() ? F("MPU6050 connection successful") : F("MPU6050 connection failed"));
// wait for ready
//Serial.println(F("\nSend any character to begin DMP programming and demo: "));
//while (Serial.available() && Serial.read()); // empty buffer
//while (!Serial.available()); // wait for data
//while (Serial.available() && Serial.read()); // empty buffer again
// load and configure the DMP
Serial.println(F("Initializing DMP..."));
devStatus = mpu.dmpInitialize();
// supply your own gyro offsets here, scaled for min sensitivity
mpu.setXGyroOffset(220);
mpu.setYGyroOffset(76);
mpu.setZGyroOffset(-85);
mpu.setZAccelOffset(1788); // 1688 factory default for my test chip
// make sure it worked (returns 0 if so)
if (devStatus == 0) {
// turn on the DMP, now that it's ready
Serial.println(F("Enabling DMP..."));
mpu.setDMPEnabled(true);
// enable Arduino interrupt detection
//Serial.println(F("Enabling interrupt detection (Arduino external interrupt 0)..."));
//attachInterrupt(0, dmpDataReady, RISING);
Serial.println(F("Enabling interrupt detection (Teensy external interrupt TeensyIntPin)...")); //MattC
pinMode(TeensyIntPin, INPUT); // sets the digital pin as input //MattC
attachInterrupt(TeensyIntPin, dmpDataReady, RISING); //MattC
mpuIntStatus = mpu.getIntStatus();
// set our DMP Ready flag so the main loop() function knows it's okay to use it
Serial.println(F("DMP ready! Waiting for first interrupt..."));
dmpReady = true;
// get expected DMP packet size for later comparison
packetSize = mpu.dmpGetFIFOPacketSize();
} else {
// ERROR!
// 1 = initial memory load failed
// 2 = DMP configuration updates failed
// (if it's going to break, usually the code will be 1)
Serial.print(F("DMP Initialization failed (code "));
Serial.print(devStatus);
Serial.println(F(")"));
}
// configure LED for output
pinMode(LED_PIN, OUTPUT);
// ======================================
// MAVLINK_FRSKYSPORT Setup
FrSkySPort_Init();
_MavLinkSerial.begin(57600);
debugSerial.begin(57600);
//MavLink_Connected = 0;
MavLink_Connected_timer = millis();
hb_timer = millis();
acc_timer = hb_timer;
hb_count = 0;
pinMode(led, OUTPUT);
//-----------------------------------------------
//Get Volt/Curr Data
//pinMode(12, INPUT); // Control for Send
//pinMode(11,INPUT); // Control for Receive
// Setup for Master mode, pins 18/19, external pullups, 400kHz, 200ms default timeout
//Wire.begin(I2C_MASTER, 0x00, I2C_PINS_18_19, I2C_PULLUP_EXT, 400000);
//Wire.setDefaultTimeout(200000); // 200ms
//-----------------------------------------------
pinMode(14, INPUT);
analogReference(DEFAULT);
// =====================================
//Activate internal pullup resistor for DS18S20 temp sensor
pinMode(US1881_Pin, INPUT_PULLUP);
Serial.begin(115200);
attachInterrupt(US1881_Pin, magnet_detect, RISING);//Initialize the intterrupt pin (Arduino digital pin 2)
half_revolutions = 0;
rpm = 0;
timeold = 0;
// Wire.begin (MY_ADDRESS);
//Serial.begin (115200);
// Wire.onReceive (receiveEvent);
//i2c_t3 I2C Teensy Comm Setup
//------------------------------------------
// Setup for Slave mode, address 0x66, pins 18/19, external pullups, 400kHz
Wire1.begin(I2C_SLAVE, 0x66, I2C_PINS_18_19, I2C_PULLUP_EXT, 400000);
// Data init
received = 0;
memset(databuf, 0, sizeof(databuf));
// register events
Wire1.onReceive(receiveEvent);
Wire1.onRequest(requestEvent);
//------------------------------------------
}
void magnet_detect()//This function is called whenever a magnet/interrupt is detected by the arduino
{
half_revolutions++;
Serial.println("==================detect==================");
}
// called by interrupt service routine when incoming data arrives
//void receiveEvent (int howMany)
//{
//if (howMany >= (sizeof VFinal) + (sizeof IFinal))
// {
// I2C_readAnything (VFinal);
// I2C_readAnything (IFinal);
// haveData = true;
// } // end if have enough data
//
//} // end of receiveEvent
// ================================================================
// === MAIN PROGRAM LOOP ===
// ================================================================
void loop() {
//--------------------------------------------------------
//Measurement
VRaw = analogRead(A0);
IRaw = analogRead(A1);
//Conversion
//VFinal = VRaw/49.44; //45 Amp board
//VFinal = VRaw/12.99; //90 Amp board
//VFinal = VRaw/12.99; //180 Amp board
VFinal = VRaw / 19.6; //90 Amp board
//IFinal = IRaw/14.9; //45 Amp board
//IFinal = IRaw/7.4; //90 Amp board
//IFinal = IRaw/3.7; //180 Amp board
IFinal = IRaw / 10.36; //Calibrated current
//Display
//digitalWrite(ledPin, HIGH); // set the LED on
Serial.print("$V");
if (abs(VFinal) < 10.0) {
Serial.print(" ");
}
Serial.print(VFinal);
Serial.println(" a"); //Note that this extra white space ensures the text string is exactly 18 characters
//Serial.println(" Volts");
Serial.print("$A");
if (abs(IFinal) < 10) {
Serial.print(" ");
}
Serial.print(IFinal * 1.00);
Serial.println(" a"); //Note that this extra white space ensures the text string is exactly 18 characters
//Serial.println(" Amps");
//--------------------------------------------------------
//Wire.beginTransmission(8);
// Wire.requestFrom(8, 8); // request 6 bytes from slave device #8
//
// if(Wire.available())
// {
// int i = 0;
// while(Wire.available()) // slave may send less than requested
// {
// Wiredata[i] = Wire.receive(); // receive a byte as character
// i = i + 1;
// }
//
// //A union datatypes makes the byte and float elements share the same piece of memory, which enables conversion from a byte array to a float possible
// union Volt_tag {byte Volt_b[4]; float Volt_fval;} Volt_Union;
// Volt_Union.Volt_b[0] = Wiredata[0];
// Volt_Union.Volt_b[1] = Wiredata[1];
// Volt_Union.Volt_b[2] = Wiredata[2];
// Volt_Union.Volt_b[3] = Wiredata[3];
// Voltage = Volt_Union.Volt_fval;
// Serial.print("$V");
// Serial.println(Voltage);
//
// union Curr_tag {byte Curr_b[4]; float Curr_fval;} Curr_Union; //Curr = Drum Revs per Second
// Curr_Union.Curr_b[0] = Wiredata[4];
// Curr_Union.Curr_b[1] = Wiredata[5];
// Curr_Union.Curr_b[2] = Wiredata[6];
// Curr_Union.Curr_b[3] = Wiredata[7];
// Current = Curr_Union.Curr_fval;
// Serial.print("$I");
// Serial.println(Current);
// }
// //Wire.endTransmission();
// while(Wire.available()) // slave may send less than requested
// {
// int c = Wire.receive(); // receive a byte as character
// //char c = Wire.read(); // receive a byte as character
// Serial.print(c); // print the character
// }
//Serial.println();
//============================================================================
// MPU 6050 Accelerometer
// if programming failed, don't try to do anything
if (!dmpReady) return;
// wait for MPU interrupt or extra packet(s) available
while (!mpuInterrupt && fifoCount < packetSize) {
// other program behavior stuff here
// .
// .
// .
// if you are really paranoid you can frequently test in between other
// stuff to see if mpuInterrupt is true, and if so, "break;" from the
// while() loop to immediately process the MPU data
// .
// .
// .
}
// reset interrupt flag and get INT_STATUS byte
mpuInterrupt = false;
mpuIntStatus = mpu.getIntStatus();
// get current FIFO count
fifoCount = mpu.getFIFOCount();
// check for overflow (this should never happen unless our code is too inefficient)
if ((mpuIntStatus & 0x10) || fifoCount == 1024) {
// reset so we can continue cleanly
mpu.resetFIFO();
Serial.println(F("FIFO overflow!"));
// otherwise, check for DMP data ready interrupt (this should happen frequently)
} else if (mpuIntStatus & 0x02) {
// wait for correct available data length, should be a VERY short wait
while (fifoCount < packetSize) fifoCount = mpu.getFIFOCount();
// read a packet from FIFO
mpu.getFIFOBytes(fifoBuffer, packetSize);
// track FIFO count here in case there is > 1 packet available
// (this lets us immediately read more without waiting for an interrupt)
fifoCount -= packetSize;
// MPU6050 Gyro/Accel Read and Print Data to Serial
#ifdef OUTPUT_READABLE_REALACCEL
// display real acceleration, adjusted to remove gravity
mpu.dmpGetQuaternion(&q, fifoBuffer);
mpu.dmpGetAccel(&aa, fifoBuffer);
mpu.dmpGetGravity(&gravity, &q);
mpu.dmpGetLinearAccel(&aaReal, &aa, &gravity);
Serial.print("$");
if (aaReal.x >= 0) {
Serial.print(' ');
}
if (abs(aaReal.x) < 1000) {
Serial.print(' ');
}
if (abs(aaReal.x) < 100) {
Serial.print(' ');
}
if (abs(aaReal.x) < 10) {
Serial.print(' ');
}
Serial.print(aaReal.x);
Serial.print("\t");
if (aaReal.y >= 0) {
Serial.print(' ');
}
if (abs(aaReal.y) < 1000) {
Serial.print(' ');
}
if (abs(aaReal.y) < 100) {
Serial.print(' ');
}
if (abs(aaReal.y) < 10) {
Serial.print(' ');
}
Serial.print(aaReal.y);
Serial.print("\t");
if (aaReal.z >= 0) {
Serial.print(' ');
}
if (abs(aaReal.z) < 1000) {
Serial.print(' ');
}
if (abs(aaReal.z) < 100) {
Serial.print(' ');
}
if (abs(aaReal.z) < 10) {
Serial.print(' ');
}
Serial.print(aaReal.z);
Serial.println();
#endif
//============================================================================
// ======================================
// MAVLINK_FRSKYSPORT Loop
uint16_t len;
// if (millis() - hb_timer > 1500) {
// hb_timer = millis();
// if (!MavLink_Connected) { // Start requesting data streams from MavLink
// digitalWrite(led, HIGH);
// mavlink_msg_request_data_stream_pack(0xFF, 0xBE, &msg, 1, 1, MAV_DATA_STREAM_EXTENDED_STATUS, MSG_RATE, START);
// len = mavlink_msg_to_send_buffer(buf, &msg);
// _MavLinkSerial.write(buf, len);
// delay(10);
// mavlink_msg_request_data_stream_pack(0xFF, 0xBE, &msg, 1, 1, MAV_DATA_STREAM_EXTRA2, MSG_RATE, START);
// len = mavlink_msg_to_send_buffer(buf, &msg);
// _MavLinkSerial.write(buf, len);
// delay(10);
// mavlink_msg_request_data_stream_pack(0xFF, 0xBE, &msg, 1, 1, MAV_DATA_STREAM_RAW_SENSORS, MSG_RATE, START);
// len = mavlink_msg_to_send_buffer(buf, &msg);
// _MavLinkSerial.write(buf, len);
// digitalWrite(led, LOW);
// }
// }
//
// if ((millis() - MavLink_Connected_timer) > 1500) { // if no HEARTBEAT from APM in 1.5s then we are not connected
// MavLink_Connected = 0;
// hb_count = 0;
// }
//_MavLink_receive(); // Check MavLink communication
FrSkySPort_Process(); // Check FrSky S.Port communication
adc2 = analogRead(0) / 4; // Read ananog value from A0 (Pin 14). ( Will be A2 value on FrSky LCD)
if ((millis() - acc_timer) > 1000) { // Reset timer for AccX, AccY and AccZ
ap_accX_old = ap_accX;
ap_accY_old = ap_accY;
ap_accZ_old = ap_accZ;
acc_timer = millis();
//debugSerial.println(adc2);
}
// ======================================
// if (count>100) {
float temperature = getTemp();
Serial.print("$T");
Serial.print(temperature);
Serial.println(" a"); //Note that this extra white space ensures the text string is exactly 18 characters
count = 0;
// }
// else{
// count=count+1;
// }
//Measure RPM
if (half_revolutions >= 20) {
rpm = 30 * 1000 / (millis() - timeold) * half_revolutions;
timeold = millis();
half_revolutions = 0;
//Serial.println(rpm,DEC);
}
// if (haveData)
// {
// Serial.print ("$V");
// Serial.println (VFinal);
// Serial.print ("$I");
// Serial.println (IFinal);
// haveData = false;
// } // end if haveData
//Serial.println();
// blink LED to indicate activity
blinkState = !blinkState;
digitalWrite(LED_PIN, blinkState);
}
}
//
// handle Rx Event (incoming I2C data)
//
void receiveEvent(size_t count)
{
size_t idx = 0;
while (idx < count)
{
if (idx < MEM_LEN) // drop data beyond mem boundary
databuf[idx++] = Wire1.readByte(); // copy data to mem
else
Wire1.readByte(); // drop data if mem full
}
received = count; // set received flag to count, this triggers print in main loop
}
//
// handle Tx Event (outgoing I2C data)
//
void requestEvent(void)
{
//Wire1.write(databuf, MEM_LEN); // fill Tx buffer (send full mem)
char Vf[MEM_LEN];
sprintf(Vf, "V%f A%f", (double)VFinal, (double)IFinal);
Wire1.write(Vf);
Serial.printf("Sending '%s'\n", Vf);
//Wire1.write((byte)VFinal); // fill Tx buffer (send full mem)
//Wire1.write(Vfinal); // fill Tx buffer (send full mem)
}