MPU 9255 sketcha
parent
5e380911f7
commit
9e0a0c5c89
|
@ -0,0 +1,127 @@
|
|||
////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
// This file is part of RTIMULib-Arduino
|
||||
//
|
||||
// Copyright (c) 2014-2015, richards-tech
|
||||
//
|
||||
// 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.
|
||||
|
||||
#include <Wire.h>
|
||||
#include "I2Cdev.h"
|
||||
#include "RTIMULib/RTIMUSettings.h"
|
||||
#include "RTIMULib/RTIMU.h"
|
||||
#include "RTIMULib/RTFusionRTQF.h"
|
||||
#include "CalLib/CalLib.h"
|
||||
#include <EEPROM.h>
|
||||
|
||||
RTIMU *imu; // the IMU object
|
||||
RTFusionRTQF fusion; // the fusion object
|
||||
RTIMUSettings settings; // the settings object
|
||||
|
||||
// DISPLAY_INTERVAL sets the rate at which results are displayed
|
||||
|
||||
#define DISPLAY_INTERVAL 100 // interval between pose displays
|
||||
|
||||
// SERIAL_PORT_SPEED defines the speed to use for the debug serial port
|
||||
|
||||
#define SERIAL_PORT_SPEED 115200
|
||||
|
||||
unsigned long lastDisplay;
|
||||
unsigned long lastRate;
|
||||
int sampleCount;
|
||||
RTQuaternion gravity;
|
||||
|
||||
void setup()
|
||||
{
|
||||
int errcode;
|
||||
|
||||
Serial.begin(SERIAL_PORT_SPEED);
|
||||
Wire.begin();
|
||||
imu = RTIMU::createIMU(&settings); // create the imu object
|
||||
|
||||
Serial.print("ArduinoIMU starting using device "); Serial.println(imu->IMUName());
|
||||
if ((errcode = imu->IMUInit()) < 0) {
|
||||
Serial.print("Failed to init IMU: "); Serial.println(errcode);
|
||||
}
|
||||
|
||||
if (imu->getCalibrationValid())
|
||||
Serial.println("Using compass calibration");
|
||||
else
|
||||
Serial.println("No valid compass calibration data");
|
||||
|
||||
lastDisplay = lastRate = millis();
|
||||
sampleCount = 0;
|
||||
|
||||
gravity.setScalar(0);
|
||||
gravity.setX(0);
|
||||
gravity.setY(0);
|
||||
gravity.setZ(1);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
unsigned long now = millis();
|
||||
unsigned long delta;
|
||||
RTVector3 realAccel;
|
||||
RTQuaternion rotatedGravity;
|
||||
RTQuaternion fusedConjugate;
|
||||
RTQuaternion qTemp;
|
||||
int loopCount = 0;
|
||||
|
||||
while (imu->IMURead()) { // get the latest data if ready yet
|
||||
// this flushes remaining data in case we are falling behind
|
||||
if (++loopCount >= 10)
|
||||
continue;
|
||||
fusion.newIMUData(imu->getGyro(), imu->getAccel(), imu->getCompass(), imu->getTimestamp());
|
||||
|
||||
// do gravity rotation and subtraction
|
||||
|
||||
// create the conjugate of the pose
|
||||
|
||||
fusedConjugate = fusion.getFusionQPose().conjugate();
|
||||
|
||||
// now do the rotation - takes two steps with qTemp as the intermediate variable
|
||||
|
||||
qTemp = gravity * fusion.getFusionQPose();
|
||||
rotatedGravity = fusedConjugate * qTemp;
|
||||
|
||||
// now adjust the measured accel and change the signs to make sense
|
||||
|
||||
realAccel.setX(-(imu->getAccel().x() - rotatedGravity.x()));
|
||||
realAccel.setY(-(imu->getAccel().y() - rotatedGravity.y()));
|
||||
realAccel.setZ(-(imu->getAccel().z() - rotatedGravity.z()));
|
||||
|
||||
sampleCount++;
|
||||
if ((delta = now - lastRate) >= 1000) {
|
||||
Serial.print("Sample rate: "); Serial.print(sampleCount);
|
||||
if (!imu->IMUGyroBiasValid())
|
||||
Serial.println(", calculating gyro bias");
|
||||
else
|
||||
Serial.println();
|
||||
|
||||
sampleCount = 0;
|
||||
lastRate = now;
|
||||
}
|
||||
if ((now - lastDisplay) >= DISPLAY_INTERVAL) {
|
||||
lastDisplay = now;
|
||||
|
||||
RTMath::display("Accel:", realAccel);
|
||||
Serial.println();
|
||||
}
|
||||
}
|
||||
}
|
|
@ -0,0 +1,95 @@
|
|||
////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
// This file is part of RTIMULib-Arduino
|
||||
//
|
||||
// Copyright (c) 2014-2015, richards-tech
|
||||
//
|
||||
// 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.
|
||||
|
||||
#include "CalLib.h"
|
||||
#ifdef __SAM3X8E__
|
||||
|
||||
// Due version
|
||||
|
||||
#include "DueFlash.h"
|
||||
|
||||
DueFlash flash;
|
||||
|
||||
void calLibErase(byte device)
|
||||
{
|
||||
uint32_t data = 0;
|
||||
|
||||
flash.write(CALLIB_START + sizeof(CALLIB_DATA) * device, &data, 1); // just destroy the valid byte
|
||||
}
|
||||
|
||||
void calLibWrite(byte device, CALLIB_DATA *calData)
|
||||
{
|
||||
calData->validL = CALLIB_DATA_VALID_LOW;
|
||||
calData->validH = CALLIB_DATA_VALID_HIGH;
|
||||
|
||||
flash.write(CALLIB_START + sizeof(CALLIB_DATA) * device, (uint32_t *)calData, sizeof(CALLIB_DATA) / 4);
|
||||
}
|
||||
|
||||
boolean calLibRead(byte device, CALLIB_DATA *calData)
|
||||
{
|
||||
memcpy(calData, CALLIB_START + sizeof(CALLIB_DATA) * device, sizeof(CALLIB_DATA));
|
||||
return calData->valid == CALLIB_DATA_VALID;
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
// AVR version
|
||||
|
||||
#include <EEPROM.h>
|
||||
|
||||
void calLibErase(byte device)
|
||||
{
|
||||
EEPROM.write(sizeof(CALLIB_DATA) * device, 0); // just destroy the valid byte
|
||||
}
|
||||
|
||||
void calLibWrite(byte device, CALLIB_DATA *calData)
|
||||
{
|
||||
byte *ptr = (byte *)calData;
|
||||
byte length = sizeof(CALLIB_DATA);
|
||||
int eeprom = sizeof(CALLIB_DATA) * device;
|
||||
|
||||
calData->validL = CALLIB_DATA_VALID_LOW;
|
||||
calData->validH = CALLIB_DATA_VALID_HIGH;
|
||||
|
||||
for (byte i = 0; i < length; i++)
|
||||
EEPROM.write(eeprom + i, *ptr++);
|
||||
}
|
||||
|
||||
boolean calLibRead(byte device, CALLIB_DATA *calData)
|
||||
{
|
||||
byte *ptr = (byte *)calData;
|
||||
byte length = sizeof(CALLIB_DATA);
|
||||
int eeprom = sizeof(CALLIB_DATA) * device;
|
||||
|
||||
calData->magValid = false;
|
||||
|
||||
if ((EEPROM.read(eeprom) != CALLIB_DATA_VALID_LOW) ||
|
||||
(EEPROM.read(eeprom + 1) != CALLIB_DATA_VALID_HIGH)) {
|
||||
return false; // invalid data
|
||||
}
|
||||
|
||||
for (byte i = 0; i < length; i++)
|
||||
*ptr++ = EEPROM.read(eeprom + i);
|
||||
return true;
|
||||
}
|
||||
#endif
|
|
@ -0,0 +1,58 @@
|
|||
////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
// This file is part of RTIMULib-Arduino
|
||||
//
|
||||
// Copyright (c) 2014-2015, richards-tech
|
||||
//
|
||||
// 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.
|
||||
|
||||
#ifndef _CALLIB_H_
|
||||
#define _CALLIB_H_
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
#define CALLIB_DATA_VALID_LOW 0xfc // pattern to detect valid config - low byte
|
||||
#define CALLIB_DATA_VALID_HIGH 0x15 // pattern to detect valid config - high byte
|
||||
|
||||
#ifdef __SAM3X8E__
|
||||
#define CALLIB_START ((uint32_t *)(IFLASH1_ADDR + IFLASH1_SIZE - IFLASH1_PAGE_SIZE))
|
||||
#endif
|
||||
|
||||
typedef struct
|
||||
{
|
||||
unsigned char validL; // should contain the valid pattern if a good config
|
||||
unsigned char validH; // should contain the valid pattern if a good config
|
||||
unsigned char magValid; // true if data valid
|
||||
unsigned char pad;
|
||||
float magMin[3]; // min values
|
||||
float magMax[3]; // max values
|
||||
} CALLIB_DATA;
|
||||
|
||||
// calLibErase() erases any current data in the EEPROM
|
||||
|
||||
void calLibErase(byte device);
|
||||
|
||||
// calLibWrite() writes new data to the EEPROM
|
||||
|
||||
void calLibWrite(byte device, CALLIB_DATA * calData);
|
||||
|
||||
// calLibRead() reads existing data and returns true if valid else false in not.
|
||||
|
||||
boolean calLibRead(byte device, CALLIB_DATA * calData);
|
||||
|
||||
#endif // _CALLIB_H_
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,269 @@
|
|||
// I2Cdev library collection - Main I2C device class header file
|
||||
// Abstracts bit and byte I2C R/W functions into a convenient class
|
||||
// 6/9/2012 by Jeff Rowberg <jeff@rowberg.net>
|
||||
//
|
||||
// Changelog:
|
||||
// 2013-05-06 - add Francesco Ferrara's Fastwire v0.24 implementation with small modifications
|
||||
// 2013-05-05 - fix issue with writing bit values to words (Sasquatch/Farzanegan)
|
||||
// 2012-06-09 - fix major issue with reading > 32 bytes at a time with Arduino Wire
|
||||
// - add compiler warnings when using outdated or IDE or limited I2Cdev implementation
|
||||
// 2011-11-01 - fix write*Bits mask calculation (thanks sasquatch @ Arduino forums)
|
||||
// 2011-10-03 - added automatic Arduino version detection for ease of use
|
||||
// 2011-10-02 - added Gene Knight's NBWire TwoWire class implementation with small modifications
|
||||
// 2011-08-31 - added support for Arduino 1.0 Wire library (methods are different from 0.x)
|
||||
// 2011-08-03 - added optional timeout parameter to read* methods to easily change from default
|
||||
// 2011-08-02 - added support for 16-bit registers
|
||||
// - fixed incorrect Doxygen comments on some methods
|
||||
// - added timeout value for read operations (thanks mem @ Arduino forums)
|
||||
// 2011-07-30 - changed read/write function structures to return success or byte counts
|
||||
// - made all methods static for multi-device memory savings
|
||||
// 2011-07-28 - initial release
|
||||
|
||||
/* ============================================
|
||||
I2Cdev device library code is placed under the MIT license
|
||||
Copyright (c) 2013 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.
|
||||
===============================================
|
||||
*/
|
||||
|
||||
#ifndef _I2CDEV_H_
|
||||
#define _I2CDEV_H_
|
||||
|
||||
// -----------------------------------------------------------------------------
|
||||
// I2C interface implementation setting
|
||||
// -----------------------------------------------------------------------------
|
||||
#define I2CDEV_IMPLEMENTATION I2CDEV_ARDUINO_WIRE
|
||||
//#define I2CDEV_IMPLEMENTATION I2CDEV_BUILTIN_FASTWIRE
|
||||
|
||||
// comment this out if you are using a non-optimal IDE/implementation setting
|
||||
// but want the compiler to shut up about it
|
||||
#define I2CDEV_IMPLEMENTATION_WARNINGS
|
||||
|
||||
// -----------------------------------------------------------------------------
|
||||
// I2C interface implementation options
|
||||
// -----------------------------------------------------------------------------
|
||||
#define I2CDEV_ARDUINO_WIRE 1 // Wire object from Arduino
|
||||
#define I2CDEV_BUILTIN_NBWIRE 2 // Tweaked Wire object from Gene Knight's NBWire project
|
||||
// ^^^ NBWire implementation is still buggy w/some interrupts!
|
||||
#define I2CDEV_BUILTIN_FASTWIRE 3 // FastWire object from Francesco Ferrara's project
|
||||
#define I2CDEV_I2CMASTER_LIBRARY 4 // I2C object from DSSCircuits I2C-Master Library at https://github.com/DSSCircuits/I2C-Master-Library
|
||||
|
||||
// -----------------------------------------------------------------------------
|
||||
// Arduino-style "Serial.print" debug constant (uncomment to enable)
|
||||
// -----------------------------------------------------------------------------
|
||||
//#define I2CDEV_SERIAL_DEBUG
|
||||
|
||||
#ifdef ARDUINO
|
||||
#if ARDUINO < 100
|
||||
#include "WProgram.h"
|
||||
#else
|
||||
#include "Arduino.h"
|
||||
#endif
|
||||
#if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
|
||||
#include <Wire.h>
|
||||
#endif
|
||||
#if I2CDEV_IMPLEMENTATION == I2CDEV_I2CMASTER_LIBRARY
|
||||
#include <I2C.h>
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// 1000ms default read timeout (modify with "I2Cdev::readTimeout = [ms];")
|
||||
#define I2CDEV_DEFAULT_READ_TIMEOUT 1000
|
||||
|
||||
class I2Cdev {
|
||||
public:
|
||||
I2Cdev();
|
||||
|
||||
static int8_t readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout);
|
||||
static int8_t readBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout);
|
||||
static int8_t readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout);
|
||||
static int8_t readBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout);
|
||||
static int8_t readByte(uint8_t devAddr, uint8_t regAddr, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout);
|
||||
static int8_t readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout);
|
||||
static int8_t readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout);
|
||||
static int8_t readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout);
|
||||
|
||||
static bool writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data);
|
||||
static bool writeBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data);
|
||||
static bool writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data);
|
||||
static bool writeBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data);
|
||||
static bool writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data);
|
||||
static bool writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data);
|
||||
static bool writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data);
|
||||
static bool writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data);
|
||||
|
||||
static uint16_t readTimeout;
|
||||
};
|
||||
|
||||
#if I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE
|
||||
//////////////////////
|
||||
// FastWire 0.24
|
||||
// This is a library to help faster programs to read I2C devices.
|
||||
// Copyright(C) 2012
|
||||
// Francesco Ferrara
|
||||
//////////////////////
|
||||
|
||||
/* Master */
|
||||
#define TW_START 0x08
|
||||
#define TW_REP_START 0x10
|
||||
|
||||
/* Master Transmitter */
|
||||
#define TW_MT_SLA_ACK 0x18
|
||||
#define TW_MT_SLA_NACK 0x20
|
||||
#define TW_MT_DATA_ACK 0x28
|
||||
#define TW_MT_DATA_NACK 0x30
|
||||
#define TW_MT_ARB_LOST 0x38
|
||||
|
||||
/* Master Receiver */
|
||||
#define TW_MR_ARB_LOST 0x38
|
||||
#define TW_MR_SLA_ACK 0x40
|
||||
#define TW_MR_SLA_NACK 0x48
|
||||
#define TW_MR_DATA_ACK 0x50
|
||||
#define TW_MR_DATA_NACK 0x58
|
||||
|
||||
#define TW_OK 0
|
||||
#define TW_ERROR 1
|
||||
|
||||
class Fastwire {
|
||||
private:
|
||||
static boolean waitInt();
|
||||
|
||||
public:
|
||||
static void setup(int khz, boolean pullup);
|
||||
static byte beginTransmission(byte device);
|
||||
static byte write(byte value);
|
||||
static byte writeBuf(byte device, byte address, byte *data, byte num);
|
||||
static byte readBuf(byte device, byte address, byte *data, byte num);
|
||||
static void reset();
|
||||
static byte stop();
|
||||
};
|
||||
#endif
|
||||
|
||||
#if I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE
|
||||
// NBWire implementation based heavily on code by Gene Knight <Gene@Telobot.com>
|
||||
// Originally posted on the Arduino forum at http://arduino.cc/forum/index.php/topic,70705.0.html
|
||||
// Originally offered to the i2cdevlib project at http://arduino.cc/forum/index.php/topic,68210.30.html
|
||||
|
||||
#define NBWIRE_BUFFER_LENGTH 32
|
||||
|
||||
class TwoWire {
|
||||
private:
|
||||
static uint8_t rxBuffer[];
|
||||
static uint8_t rxBufferIndex;
|
||||
static uint8_t rxBufferLength;
|
||||
|
||||
static uint8_t txAddress;
|
||||
static uint8_t txBuffer[];
|
||||
static uint8_t txBufferIndex;
|
||||
static uint8_t txBufferLength;
|
||||
|
||||
// static uint8_t transmitting;
|
||||
static void (*user_onRequest)(void);
|
||||
static void (*user_onReceive)(int);
|
||||
static void onRequestService(void);
|
||||
static void onReceiveService(uint8_t*, int);
|
||||
|
||||
public:
|
||||
TwoWire();
|
||||
void begin();
|
||||
void begin(uint8_t);
|
||||
void begin(int);
|
||||
void beginTransmission(uint8_t);
|
||||
//void beginTransmission(int);
|
||||
uint8_t endTransmission(uint16_t timeout=0);
|
||||
void nbendTransmission(void (*function)(int)) ;
|
||||
uint8_t requestFrom(uint8_t, int, uint16_t timeout=0);
|
||||
//uint8_t requestFrom(int, int);
|
||||
void nbrequestFrom(uint8_t, int, void (*function)(int));
|
||||
void send(uint8_t);
|
||||
void send(uint8_t*, uint8_t);
|
||||
//void send(int);
|
||||
void send(char*);
|
||||
uint8_t available(void);
|
||||
uint8_t receive(void);
|
||||
void onReceive(void (*)(int));
|
||||
void onRequest(void (*)(void));
|
||||
};
|
||||
|
||||
#define TWI_READY 0
|
||||
#define TWI_MRX 1
|
||||
#define TWI_MTX 2
|
||||
#define TWI_SRX 3
|
||||
#define TWI_STX 4
|
||||
|
||||
#define TW_WRITE 0
|
||||
#define TW_READ 1
|
||||
|
||||
#define TW_MT_SLA_NACK 0x20
|
||||
#define TW_MT_DATA_NACK 0x30
|
||||
|
||||
#define CPU_FREQ 16000000L
|
||||
#define TWI_FREQ 100000L
|
||||
#define TWI_BUFFER_LENGTH 32
|
||||
|
||||
/* TWI Status is in TWSR, in the top 5 bits: TWS7 - TWS3 */
|
||||
|
||||
#define TW_STATUS_MASK (_BV(TWS7)|_BV(TWS6)|_BV(TWS5)|_BV(TWS4)|_BV(TWS3))
|
||||
#define TW_STATUS (TWSR & TW_STATUS_MASK)
|
||||
#define TW_START 0x08
|
||||
#define TW_REP_START 0x10
|
||||
#define TW_MT_SLA_ACK 0x18
|
||||
#define TW_MT_SLA_NACK 0x20
|
||||
#define TW_MT_DATA_ACK 0x28
|
||||
#define TW_MT_DATA_NACK 0x30
|
||||
#define TW_MT_ARB_LOST 0x38
|
||||
#define TW_MR_ARB_LOST 0x38
|
||||
#define TW_MR_SLA_ACK 0x40
|
||||
#define TW_MR_SLA_NACK 0x48
|
||||
#define TW_MR_DATA_ACK 0x50
|
||||
#define TW_MR_DATA_NACK 0x58
|
||||
#define TW_ST_SLA_ACK 0xA8
|
||||
#define TW_ST_ARB_LOST_SLA_ACK 0xB0
|
||||
#define TW_ST_DATA_ACK 0xB8
|
||||
#define TW_ST_DATA_NACK 0xC0
|
||||
#define TW_ST_LAST_DATA 0xC8
|
||||
#define TW_SR_SLA_ACK 0x60
|
||||
#define TW_SR_ARB_LOST_SLA_ACK 0x68
|
||||
#define TW_SR_GCALL_ACK 0x70
|
||||
#define TW_SR_ARB_LOST_GCALL_ACK 0x78
|
||||
#define TW_SR_DATA_ACK 0x80
|
||||
#define TW_SR_DATA_NACK 0x88
|
||||
#define TW_SR_GCALL_DATA_ACK 0x90
|
||||
#define TW_SR_GCALL_DATA_NACK 0x98
|
||||
#define TW_SR_STOP 0xA0
|
||||
#define TW_NO_INFO 0xF8
|
||||
#define TW_BUS_ERROR 0x00
|
||||
|
||||
//#define _MMIO_BYTE(mem_addr) (*(volatile uint8_t *)(mem_addr))
|
||||
//#define _SFR_BYTE(sfr) _MMIO_BYTE(_SFR_ADDR(sfr))
|
||||
|
||||
#ifndef sbi // set bit
|
||||
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
|
||||
#endif // sbi
|
||||
|
||||
#ifndef cbi // clear bit
|
||||
#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
|
||||
#endif // cbi
|
||||
|
||||
extern TwoWire Wire;
|
||||
|
||||
#endif // I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE
|
||||
|
||||
#endif /* _I2CDEV_H_ */
|
|
@ -0,0 +1,231 @@
|
|||
///////////////////////////////////////////////////////////
|
||||
//
|
||||
// This file is part of RTArduLink
|
||||
//
|
||||
// Copyright (c) 2014-2015 richards-tech
|
||||
//
|
||||
// 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.
|
||||
|
||||
#include "RTArduLink.h"
|
||||
#include "RTArduLinkHAL.h"
|
||||
#include "RTArduLinkUtils.h"
|
||||
|
||||
#include <string.h>
|
||||
|
||||
RTArduLink::RTArduLink()
|
||||
{
|
||||
}
|
||||
|
||||
RTArduLink::~RTArduLink()
|
||||
{
|
||||
}
|
||||
|
||||
void RTArduLink::begin(const char *identitySuffix)
|
||||
{
|
||||
RTARDULINK_PORT *portInfo;
|
||||
|
||||
if (!RTArduLinkHALEEPROMValid())
|
||||
RTArduLinkHALEEPROMDefault();
|
||||
|
||||
m_identitySuffix = identitySuffix;
|
||||
|
||||
// now set up host and subsystem ports based on EEPROM configuration
|
||||
|
||||
for (int i = 0; i < RTARDULINKHAL_MAX_PORTS; i++) {
|
||||
portInfo = m_ports + i;
|
||||
portInfo->index = i;
|
||||
portInfo->inUse = RTArduLinkHALConfigurePort(&(portInfo->portHAL), i);
|
||||
RTArduLinkRXFrameInit(&(portInfo->RXFrame), &(portInfo->RXFrameBuffer));
|
||||
}
|
||||
m_hostPort = m_ports;
|
||||
}
|
||||
|
||||
|
||||
void RTArduLink::background()
|
||||
{
|
||||
unsigned char index;
|
||||
RTARDULINK_PORT *portInfo;
|
||||
|
||||
for (index = 0; index < RTARDULINKHAL_MAX_PORTS; index++) {
|
||||
portInfo = m_ports + index;
|
||||
if (!portInfo->inUse)
|
||||
continue;
|
||||
|
||||
while (RTArduLinkHALPortAvailable(&(portInfo->portHAL))) {
|
||||
if (!RTArduLinkReassemble(&(portInfo->RXFrame), RTArduLinkHALPortRead(&(portInfo->portHAL)))) {
|
||||
sendDebugMessage("Reassembly error");
|
||||
} else {
|
||||
if (portInfo->RXFrame.complete) {
|
||||
processReceivedMessage(portInfo);
|
||||
RTArduLinkRXFrameInit(&(portInfo->RXFrame), &(portInfo->RXFrameBuffer));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void RTArduLink::processReceivedMessage(RTARDULINK_PORT *portInfo)
|
||||
{
|
||||
RTARDULINK_MESSAGE *message; // a pointer to the message part of the frame
|
||||
unsigned int address;
|
||||
|
||||
message = &(portInfo->RXFrameBuffer.message); // get the message pointer
|
||||
address = RTArduLinkConvertUC2ToUInt(message->messageAddress);
|
||||
|
||||
switch (portInfo->index) {
|
||||
case RTARDULINK_HOST_PORT:
|
||||
processHostMessage(); // came from this upstream link
|
||||
return;
|
||||
|
||||
case RTARDULINK_DAISY_PORT: // came from dasiy chain port
|
||||
if (address != RTARDULINK_HOST_PORT) // true if it came from a daisy chained subsystem, not a directly connected subsystem
|
||||
RTArduLinkConvertIntToUC2(address + RTARDULINKHAL_MAX_PORTS, message->messageAddress);
|
||||
else
|
||||
RTArduLinkConvertIntToUC2(RTARDULINK_DAISY_PORT, message->messageAddress);
|
||||
break;
|
||||
|
||||
default:
|
||||
RTArduLinkConvertIntToUC2(address + portInfo->index, message->messageAddress);
|
||||
break;
|
||||
}
|
||||
|
||||
// if get here, need to forward to host port
|
||||
|
||||
sendFrame(m_hostPort, &(portInfo->RXFrameBuffer), portInfo->RXFrameBuffer.messageLength);
|
||||
}
|
||||
|
||||
|
||||
void RTArduLink::processHostMessage()
|
||||
{
|
||||
RTARDULINK_MESSAGE *message; // a pointer to the message part of the frame
|
||||
int identityLength;
|
||||
int suffixLength;
|
||||
unsigned int address;
|
||||
|
||||
message = &(m_hostPort->RXFrameBuffer.message); // get the message pointer
|
||||
address = RTArduLinkConvertUC2ToUInt(message->messageAddress);
|
||||
|
||||
if (address == RTARDULINK_BROADCAST_ADDRESS) { // need to forward to downstream ports also
|
||||
for (int i = RTARDULINK_HOST_PORT + 1; i < RTARDULINKHAL_MAX_PORTS; i++) {
|
||||
if (m_ports[i].inUse)
|
||||
sendFrame(m_ports + i, &(m_hostPort->RXFrameBuffer), m_hostPort->RXFrameBuffer.messageLength);
|
||||
}
|
||||
}
|
||||
if ((address == RTARDULINK_MY_ADDRESS) || (address == RTARDULINK_BROADCAST_ADDRESS)) { // it's for me
|
||||
switch (message->messageType)
|
||||
{
|
||||
case RTARDULINK_MESSAGE_POLL:
|
||||
case RTARDULINK_MESSAGE_ECHO:
|
||||
RTArduLinkConvertIntToUC2(RTARDULINK_MY_ADDRESS, message->messageAddress);
|
||||
sendFrame(m_hostPort, &(m_hostPort->RXFrameBuffer), m_hostPort->RXFrameBuffer.messageLength); // just send the frame back as received
|
||||
break;
|
||||
|
||||
case RTARDULINK_MESSAGE_IDENTITY:
|
||||
identityLength = strlen(RTArduLinkHALConfig.identity);
|
||||
suffixLength = strlen(m_identitySuffix);
|
||||
|
||||
memcpy(message->data, RTArduLinkHALConfig.identity, identityLength + 1); // copy in identity
|
||||
|
||||
if ((identityLength + suffixLength) < RTARDULINK_DATA_MAX_LEN - 1) {
|
||||
memcpy(message->data + identityLength, m_identitySuffix, suffixLength + 1); // copy in suffix
|
||||
} else {
|
||||
suffixLength = 0;
|
||||
}
|
||||
RTArduLinkConvertIntToUC2(RTARDULINK_MY_ADDRESS, message->messageAddress);
|
||||
message->data[RTARDULINK_DATA_MAX_LEN - 1] = 0; // make sure zero terminated if it was truncated
|
||||
sendFrame(m_hostPort, &(m_hostPort->RXFrameBuffer), RTARDULINK_MESSAGE_HEADER_LEN + identityLength + suffixLength + 1);
|
||||
break;
|
||||
|
||||
default:
|
||||
if (message->messageType < RTARDULINK_MESSAGE_CUSTOM) { // illegal code
|
||||
message->data[0] = RTARDULINK_RESPONSE_ILLEGAL_COMMAND;
|
||||
message->data[1] = message->messageType; // this is the offending code
|
||||
message->messageType = RTARDULINK_MESSAGE_ERROR;
|
||||
RTArduLinkConvertIntToUC2(RTARDULINK_MY_ADDRESS, message->messageAddress);
|
||||
sendFrame(m_hostPort, &(m_hostPort->RXFrameBuffer), RTARDULINK_MESSAGE_HEADER_LEN + 2);
|
||||
break;
|
||||
}
|
||||
processCustomMessage(message->messageType, message->messageParam, message->data,
|
||||
m_hostPort->RXFrameBuffer.messageLength - RTARDULINK_MESSAGE_HEADER_LEN); // see if anyone wants to process it
|
||||
break;
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
if (address >= RTARDULINKHAL_MAX_PORTS) { // need to pass it to the first subsystem
|
||||
if (!m_ports[RTARDULINK_DAISY_PORT].inUse)
|
||||
return; // there is no daisy chain port
|
||||
RTArduLinkConvertIntToUC2(address - RTARDULINKHAL_MAX_PORTS, message->messageAddress); // adjust the address
|
||||
sendFrame(m_ports +RTARDULINK_DAISY_PORT, &(m_hostPort->RXFrameBuffer), m_hostPort->RXFrameBuffer.messageLength);
|
||||
return;
|
||||
}
|
||||
|
||||
// if get here, needs to go to a local subsystem port
|
||||
|
||||
if (m_ports[address].inUse) {
|
||||
RTArduLinkConvertIntToUC2(0, message->messageAddress); // indicates that the target should process it
|
||||
sendFrame(m_ports + address, &(m_hostPort->RXFrameBuffer), m_hostPort->RXFrameBuffer.messageLength);
|
||||
}
|
||||
}
|
||||
|
||||
void RTArduLink::sendDebugMessage(const char *debugMessage)
|
||||
{
|
||||
RTARDULINK_FRAME frame;
|
||||
int stringLength;
|
||||
|
||||
stringLength = strlen(debugMessage);
|
||||
if (stringLength >= RTARDULINK_DATA_MAX_LEN)
|
||||
stringLength = RTARDULINK_DATA_MAX_LEN-1;
|
||||
memcpy(frame.message.data, debugMessage, stringLength);
|
||||
frame.message.data[stringLength] = 0;
|
||||
frame.message.messageType = RTARDULINK_MESSAGE_DEBUG;
|
||||
RTArduLinkConvertIntToUC2(RTARDULINK_MY_ADDRESS, frame.message.messageAddress);
|
||||
sendFrame(m_hostPort, &frame, RTARDULINK_MESSAGE_HEADER_LEN + stringLength + 1);
|
||||
}
|
||||
|
||||
void RTArduLink::sendMessage(unsigned char messageType, unsigned char messageParam, unsigned char *data, int length)
|
||||
{
|
||||
RTARDULINK_FRAME frame;
|
||||
|
||||
RTArduLinkConvertIntToUC2(RTARDULINK_MY_ADDRESS, frame.message.messageAddress);
|
||||
frame.message.messageType = messageType;
|
||||
frame.message.messageParam = messageParam;
|
||||
|
||||
if (length > RTARDULINK_DATA_MAX_LEN)
|
||||
length = RTARDULINK_DATA_MAX_LEN;
|
||||
memcpy(frame.message.data, data, length);
|
||||
|
||||
sendFrame(m_hostPort, &frame, length + RTARDULINK_MESSAGE_HEADER_LEN);
|
||||
}
|
||||
|
||||
void RTArduLink::sendFrame(RTARDULINK_PORT *portInfo, RTARDULINK_FRAME *frame, int length)
|
||||
{
|
||||
frame->sync0 = RTARDULINK_MESSAGE_SYNC0;
|
||||
frame->sync1 = RTARDULINK_MESSAGE_SYNC1;
|
||||
frame->messageLength = length; // set length
|
||||
RTArduLinkSetChecksum(frame); // compute checksum
|
||||
RTArduLinkHALPortWrite(&(portInfo->portHAL), (unsigned char *)frame, frame->messageLength + RTARDULINK_FRAME_HEADER_LEN);
|
||||
}
|
||||
|
|
@ -0,0 +1,81 @@
|
|||
///////////////////////////////////////////////////////////
|
||||
//
|
||||
// This file is part of RTArduLink
|
||||
//
|
||||
// Copyright (c) 2014-2015 richards-tech
|
||||
//
|
||||
// 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.
|
||||
|
||||
#ifndef _RTARDULINK_H
|
||||
#define _RTARDULINK_H
|
||||
|
||||
#include "RTArduLinkDefs.h"
|
||||
#include "RTArduLinkHAL.h"
|
||||
|
||||
#define RTARDULINK_HOST_PORT 0 // host port is always 0
|
||||
#define RTARDULINK_DAISY_PORT 1 // daisy chain port is always 1
|
||||
|
||||
typedef struct
|
||||
{
|
||||
int index; // port index
|
||||
bool inUse; // true if in use
|
||||
RTARDULINK_RXFRAME RXFrame; // structure to maintain receive frame state
|
||||
RTARDULINK_FRAME RXFrameBuffer; // used to assemble received frames
|
||||
RTARDULINKHAL_PORT portHAL; // the actual hardware port interface
|
||||
} RTARDULINK_PORT;
|
||||
|
||||
class RTArduLink
|
||||
{
|
||||
public:
|
||||
RTArduLink();
|
||||
virtual ~RTArduLink();
|
||||
|
||||
void begin(const char *identitySuffix); // should be called in setup() code
|
||||
void background(); // should be called once per loop()
|
||||
void sendDebugMessage(const char *debugMesssage); // sends a debug message to the host port
|
||||
void sendMessage(unsigned char messageType, unsigned char messageParam,
|
||||
unsigned char *data, int length); // sends a message to the host port
|
||||
|
||||
protected:
|
||||
// These are functions that can be overridden
|
||||
|
||||
virtual void processCustomMessage(unsigned char messageType,
|
||||
unsigned char messageParam, unsigned char *data, int dataLength) {}
|
||||
|
||||
RTARDULINK_PORT m_ports[RTARDULINKHAL_MAX_PORTS]; // port array
|
||||
RTARDULINK_PORT *m_hostPort; // a link to the entry for the host port
|
||||
|
||||
|
||||
private:
|
||||
void processReceivedMessage(RTARDULINK_PORT *port); // process a completed message
|
||||
void processHostMessage(); // special case for stuff received from the host port
|
||||
void sendFrame(RTARDULINK_PORT *portInfo, RTARDULINK_FRAME *frame, int length); // send a frame to the host. length is length of data field
|
||||
|
||||
const char *m_identitySuffix; // what to add to the EEPROM identity string
|
||||
|
||||
};
|
||||
|
||||
#endif // _RTARDULINK_H
|
||||
|
|
@ -0,0 +1,199 @@
|
|||
///////////////////////////////////////////////////////////
|
||||
//
|
||||
// This file is part of RTArduLink
|
||||
//
|
||||
// Copyright (c) 2014-2015 richards-tech
|
||||
//
|
||||
// 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.
|
||||
|
||||
// The RTArduLink communications protocol works by exchanging frames across the host <-> subsystem interface.
|
||||
// The structure RTARDULINK_FRAME defines the frame structure. There is a 4 byte header for frame level control
|
||||
// while the remainder is available for higher level message. Note that the structure implies fixed length
|
||||
// buffers which works well with the subsystem however only the number of bytes actually used are transferred
|
||||
// across the interface.
|
||||
//
|
||||
// Note that there is no flow control at the frame level - it is assumed that the higher level interactions host -> subsystem
|
||||
// are window 1 acknowledged transfers so that the maximum possible unprocessed frames is equal to the number
|
||||
// of higher level services. Subsystem -> host transfers are always either responses to host commands or else regular
|
||||
// status updates so the rate from subsystem to host is controlled by configuration.
|
||||
//
|
||||
// The frame integrity is protected by a single byte checksum. To keep things very simple, it is the 2s complement
|
||||
// of the 8 bit sum of all the bytes in the message array. This is used in conjunction with 0xAA and 0x55 bytes
|
||||
// to determine correct sync (in case of lost bytes which should not really happen!).
|
||||
//
|
||||
// Frame sync is obtained by reading bytes until the 0xAA pattern is seen. If the next byte is not 0x55, keep
|
||||
// scanning. If it is, assume this byte is messageLength and the next one is the frameCksm value. Read in the
|
||||
// message array based on messageLength and then calculate the checksum. If the checksum is correct, sync has been
|
||||
// obtained and the message is valid. Otherwise, start looking for an 0xAA value again.
|
||||
|
||||
#ifndef _RTARDULINKDEFS_H
|
||||
#define _RTARDULINKDEFS_H
|
||||
|
||||
// Some defines to cope with compiler differences
|
||||
|
||||
#ifndef __cplusplus
|
||||
#ifndef false
|
||||
#define false 0
|
||||
#endif
|
||||
|
||||
#ifndef true
|
||||
#define true 1
|
||||
#endif
|
||||
|
||||
typedef unsigned char bool;
|
||||
#endif
|
||||
|
||||
#ifndef NULL
|
||||
#define NULL 0
|
||||
#endif
|
||||
|
||||
|
||||
// Some general purpose typedefs - used especially for transferring values greater than
|
||||
// 8 bits across the link and avoids endian issues. Assumes processor has 32 bit ints!
|
||||
|
||||
typedef unsigned char RTARDULINK_UC2[2]; // an array of two unsigned chars
|
||||
typedef unsigned char RTARDULINK_UC4[4]; // an array of four unsigned chars
|
||||
|
||||
// Port speed codes
|
||||
|
||||
#define RTARDULINK_PORT_SPEED_OFF 0 // port is unused
|
||||
#define RTARDULINK_PORT_SPEED_9600 1 // 9600 baud
|
||||
#define RTARDULINK_PORT_SPEED_19200 2 // 19200 baud
|
||||
#define RTARDULINK_PORT_SPEED_38400 3 // 38400 baud
|
||||
#define RTARDULINK_PORT_SPEED_57600 4 // 57600 baud
|
||||
#define RTARDULINK_PORT_SPEED_115200 5 // 115200 baud
|
||||
|
||||
#define RTARDULINK_PORT_SPEED_COUNT 6 // six codes total
|
||||
|
||||
extern unsigned long RTArduLinkSpeedMap[];
|
||||
|
||||
//------------------------------------------------------------------------------------------------------
|
||||
//
|
||||
// Frame level defs and structure
|
||||
|
||||
#define RTARDULINK_FRAME_MAX_LEN 64 // maximum possible length of a frame
|
||||
#define RTARDULINK_FRAME_HEADER_LEN 4 // 4 bytes in frame header (must correspond with the structure below!)
|
||||
#define RTARDULINK_MESSAGE_HEADER_LEN 4 // 4 bytes in message header (must correspond with the structure below!)
|
||||
#define RTARDULINK_MESSAGE_MAX_LEN (RTARDULINK_FRAME_MAX_LEN - RTARDULINK_FRAME_HEADER_LEN) // max length of message
|
||||
#define RTARDULINK_DATA_MAX_LEN (RTARDULINK_MESSAGE_MAX_LEN - RTARDULINK_MESSAGE_HEADER_LEN)// max length of data field
|
||||
|
||||
#define RTARDULINK_MESSAGE_SYNC0 0xAA
|
||||
#define RTARDULINK_MESSAGE_SYNC1 0x55
|
||||
|
||||
#define RTARDULINK_MY_ADDRESS 0 // the subsystem address for local processing
|
||||
#define RTARDULINK_BROADCAST_ADDRESS 0xffff // the subsystem address for all subsystems
|
||||
#define RTARDULINK_ADDRESSES 0x1000 // number of addresses
|
||||
|
||||
// RTARDULINK_MESSAGE is carried in the RTARDULINK_FRAME
|
||||
//
|
||||
// The messageAddress field allows subsystems to be daisy-chained. Valid addresses are 0 to 65534.
|
||||
// Address 65535 is a broadcast and goes to all subsystems.
|
||||
// Every message has the messageType and messageParam bytes but there can be from 0 to 56 bytes of data
|
||||
|
||||
typedef struct
|
||||
{
|
||||
RTARDULINK_UC2 messageAddress; // subsystem message address
|
||||
unsigned char messageType; // message type code
|
||||
unsigned char messageParam; // an optional parameter to the message type
|
||||
unsigned char data[RTARDULINK_DATA_MAX_LEN]; // the actual data! Length is computed from messageLength.
|
||||
} RTARDULINK_MESSAGE;
|
||||
|
||||
// RTARDULINK_FRAME is the lowest level structure used across the RTArduLink
|
||||
|
||||
typedef struct
|
||||
{
|
||||
unsigned char sync0; // sync0 code
|
||||
unsigned char sync1; // sync1 code
|
||||
unsigned char messageLength; // the length of the message in the message field - between 4 and 60 bytes
|
||||
unsigned char frameChecksum; // checksum for frame
|
||||
RTARDULINK_MESSAGE message; // the actual message
|
||||
} RTARDULINK_FRAME;
|
||||
|
||||
// RTARDULINK_RXFRAME is a type that is used to reassemble a frame from a stream of bytes in conjunction with RTArduLinkReassemble()
|
||||
|
||||
typedef struct
|
||||
{
|
||||
RTARDULINK_FRAME *frameBuffer; // the frame buffer pointer
|
||||
int length; // current length of frame
|
||||
int bytesLeft; // number of bytes needed to complete
|
||||
bool complete; // true if frame is complete and correct (as far as checksum goes)
|
||||
} RTARDULINK_RXFRAME;
|
||||
|
||||
// Message types
|
||||
|
||||
// RTARDULINK_MESSAGE_POLL
|
||||
//
|
||||
// The host should poll the RTArduLink at every RTARDULINK_POLL_INTERVAL.
|
||||
// The subsystem will respond by echoing the poll message as received.
|
||||
|
||||
#define RTARDULINK_MESSAGE_POLL 0 // poll message
|
||||
|
||||
// RTARDULINK_MESSAGE_IDENTIFY
|
||||
//
|
||||
// The host can send this message to request an identity string from the subsystem.
|
||||
// Only the messageType field is used in the request host -> subsystem. The subsystem
|
||||
// responds with an identity string in the data field.
|
||||
|
||||
#define RTARDULINK_MESSAGE_IDENTITY 1 // identity message
|
||||
|
||||
// RTARDULINK_MESSAGE_DEBUG
|
||||
//
|
||||
// This can be used to send a debug message up to the host. The data field contains a debug message
|
||||
|
||||
#define RTARDULINK_MESSAGE_DEBUG 2 // debug message
|
||||
|
||||
// RTARDULINK_MESSAGE_INFO
|
||||
//
|
||||
// This can be used to send an info message up to the host. The data field contains the message
|
||||
|
||||
#define RTARDULINK_MESSAGE_INFO 3 // info message
|
||||
|
||||
// RTARDULINK_MESSAGE_ERROR
|
||||
//
|
||||
// This code is returned by the subsystem if it received a message with an illegal message type
|
||||
// The first byte of the data is the error code. The rest of the data field depends on the error.
|
||||
|
||||
#define RTARDULINK_MESSAGE_ERROR 4 // illegal message type response
|
||||
|
||||
// RTARDULINK_MESSAGE_ECHO
|
||||
//
|
||||
// This message can be used to test link performance. The addressed subsystem just returns
|
||||
// the entire message to the host.
|
||||
|
||||
#define RTARDULINK_MESSAGE_ECHO 5 // echo message
|
||||
|
||||
// RTARDULINK_MESSAGE_CUSTOM
|
||||
//
|
||||
// This is the first message code that should be used for custom messages 16-255 are available.
|
||||
|
||||
#define RTARDULINK_MESSAGE_CUSTOM 16 // start of custom messages
|
||||
|
||||
// RTArduLink response codes
|
||||
|
||||
#define RTARDULINK_RESPONSE_OK 0 // means things worked
|
||||
#define RTARDULINK_RESPONSE_ILLEGAL_COMMAND 1 // not a supported message type, data[1] has offending type
|
||||
|
||||
|
||||
#endif // _RTARDULINKDEFS_H
|
|
@ -0,0 +1,66 @@
|
|||
///////////////////////////////////////////////////////////
|
||||
//
|
||||
// This file is part of RTArduLink
|
||||
//
|
||||
// Copyright (c) 2014-2015 richards-tech
|
||||
//
|
||||
// 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.
|
||||
|
||||
#ifndef RTARDULINKDEMODEFS_H_
|
||||
#define RTARDULINKDEMODEFS_H_
|
||||
|
||||
#include "RTArduLinkUtils.h"
|
||||
|
||||
#define SERVO_COUNT 2 // 2 servo channels
|
||||
#define PWM_COUNT 3 // 3 pwm channels
|
||||
#define INPUT_COUNT 2 // 2 inputs
|
||||
#define OUTPUT_COUNT 2 // 2 outputs
|
||||
|
||||
#define SERVO_MIN_VALUE 1000 // min servo value
|
||||
#define SERVO_CTR_VALUE 1500 // center servo value
|
||||
#define SERVO_MAX_VALUE 2000 // max servo value
|
||||
|
||||
#define PWM_MIN_VALUE 0 // min pwm value
|
||||
#define PWM_CTR_VALUE 128 // center pwm value
|
||||
#define PWM_MAX_VALUE 255 // max pwm value
|
||||
|
||||
// The command structure is sent from the host to the subsystem
|
||||
|
||||
typedef struct
|
||||
{
|
||||
RTARDULINK_UC2 servoPos[SERVO_COUNT]; // the servo positions
|
||||
unsigned char pwmValue[PWM_COUNT]; // PWM values
|
||||
unsigned char outputValue[OUTPUT_COUNT]; // the output pin values (true=high, false=low)
|
||||
} RTARDULINKDEMO_COMMAND;
|
||||
|
||||
// the response structure is sent from the subsystem to the host
|
||||
|
||||
typedef struct
|
||||
{
|
||||
unsigned char inputValue[INPUT_COUNT]; // the input pin values (true=high, false=low)
|
||||
} RTARDULINKDEMO_RESPONSE;
|
||||
|
||||
|
||||
#endif /* RTARDULINKDEMODEFS_H_ */
|
|
@ -0,0 +1,194 @@
|
|||
///////////////////////////////////////////////////////////
|
||||
//
|
||||
// This file is part of RTArduLink
|
||||
//
|
||||
// Copyright (c) 2014-2015 richards-tech
|
||||
//
|
||||
// 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.
|
||||
|
||||
#include <string.h>
|
||||
#include "RTArduLinkHAL.h"
|
||||
|
||||
//----------------------------------------------------------
|
||||
//
|
||||
// Arduino HAL
|
||||
|
||||
|
||||
// The global config structure
|
||||
|
||||
RTARDULINKHAL_EEPROM RTArduLinkHALConfig;
|
||||
|
||||
bool RTArduLinkHALAddHardwarePort(RTARDULINKHAL_PORT *port, long portSpeed, unsigned char hardwarePort);
|
||||
|
||||
// Port speed map array
|
||||
|
||||
unsigned long RTArduLinkHALSpeedMap[] = {0, 9600, 19200, 38400, 57600, 115200};
|
||||
|
||||
|
||||
bool RTArduLinkHALConfigurePort(RTARDULINKHAL_PORT *port, int portIndex)
|
||||
{
|
||||
if (RTArduLinkHALConfig.portSpeed[portIndex] == RTARDULINK_PORT_SPEED_OFF)
|
||||
return false; // port is not enabled
|
||||
|
||||
return RTArduLinkHALAddHardwarePort(port, RTArduLinkHALSpeedMap[RTArduLinkHALConfig.portSpeed[portIndex]],
|
||||
RTArduLinkHALConfig.hardwarePort[portIndex]);
|
||||
}
|
||||
|
||||
int RTArduLinkHALPortAvailable(RTARDULINKHAL_PORT *port)
|
||||
{
|
||||
return port->serialPort->available();
|
||||
}
|
||||
|
||||
unsigned char RTArduLinkHALPortRead(RTARDULINKHAL_PORT *port)
|
||||
{
|
||||
return port->serialPort->read();
|
||||
}
|
||||
|
||||
void RTArduLinkHALPortWrite(RTARDULINKHAL_PORT *port, unsigned char *data, unsigned char length)
|
||||
{
|
||||
port->serialPort->write(data, length);
|
||||
}
|
||||
|
||||
|
||||
bool RTArduLinkHALAddHardwarePort(RTARDULINKHAL_PORT *port, long portSpeed, unsigned char hardwarePort)
|
||||
{
|
||||
HardwareSerial *hardPort;
|
||||
|
||||
switch (hardwarePort) {
|
||||
case 0:
|
||||
#if defined(USBCON)
|
||||
/* Leonardo support */
|
||||
hardPort = &Serial1;
|
||||
#else
|
||||
hardPort = &Serial;
|
||||
#endif
|
||||
break;
|
||||
|
||||
case 1:
|
||||
#if defined(UBRR1H)
|
||||
hardPort = &Serial1;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
break;
|
||||
|
||||
case 2:
|
||||
#if defined(UBRR2H)
|
||||
hardPort = &Serial2;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
break;
|
||||
|
||||
case 3:
|
||||
#if defined(UBRR3H)
|
||||
hardPort = &Serial3;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
break;
|
||||
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
|
||||
port->serialPort = hardPort;
|
||||
hardPort->begin(portSpeed); // start the port
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
bool RTArduLinkHALEEPROMValid()
|
||||
{
|
||||
RTArduLinkHALEEPROMRead(); // see what it really is
|
||||
return (RTArduLinkHALConfig.sig0 == RTARDULINKHAL_SIG0) &&
|
||||
(RTArduLinkHALConfig.sig1 == RTARDULINKHAL_SIG1);
|
||||
}
|
||||
|
||||
void RTArduLinkHALEEPROMDisplay()
|
||||
{
|
||||
Serial.println();
|
||||
|
||||
if ((RTArduLinkHALConfig.sig0 != RTARDULINKHAL_SIG0) ||
|
||||
(RTArduLinkHALConfig.sig1 != RTARDULINKHAL_SIG1)) {
|
||||
Serial.println("Invalid config");
|
||||
return;
|
||||
}
|
||||
Serial.print("Identity: ");
|
||||
Serial.println(RTArduLinkHALConfig.identity);
|
||||
|
||||
for (int i = 0; i < RTARDULINKHAL_MAX_PORTS; i++)
|
||||
RTArduLinkHALEEPROMDisplayPort(i, true);
|
||||
}
|
||||
|
||||
void RTArduLinkHALEEPROMDisplayPort(int index, bool suppress)
|
||||
{
|
||||
if (suppress && (RTArduLinkHALConfig.portSpeed[index] == RTARDULINK_PORT_SPEED_OFF))
|
||||
return;
|
||||
Serial.print("Port index ");
|
||||
Serial.print(index);
|
||||
Serial.print(" speed=");
|
||||
Serial.print(RTArduLinkHALConfig.portSpeed[index]);
|
||||
Serial.print(", ");
|
||||
Serial.print("hardware port number=");
|
||||
Serial.println(RTArduLinkHALConfig.hardwarePort[index]);
|
||||
}
|
||||
|
||||
|
||||
void RTArduLinkHALEEPROMDefault()
|
||||
{
|
||||
RTArduLinkHALConfig.sig0 = RTARDULINKHAL_SIG0; // set to valid signature
|
||||
RTArduLinkHALConfig.sig1 = RTARDULINKHAL_SIG1;
|
||||
strcpy(RTArduLinkHALConfig.identity, "RTArduLink_Arduino");
|
||||
|
||||
RTArduLinkHALConfig.portSpeed[0] = RTARDULINK_PORT_SPEED_115200;
|
||||
for (int i = 1; i < RTARDULINKHAL_MAX_PORTS; i++)
|
||||
RTArduLinkHALConfig.portSpeed[i] = RTARDULINK_PORT_SPEED_OFF;
|
||||
|
||||
for (int i = 0; i < RTARDULINKHAL_MAX_PORTS; i++)
|
||||
RTArduLinkHALConfig.hardwarePort[i] = i;
|
||||
|
||||
RTArduLinkHALEEPROMWrite();
|
||||
}
|
||||
|
||||
void RTArduLinkHALEEPROMRead()
|
||||
{
|
||||
unsigned char *data;
|
||||
|
||||
data = (unsigned char *)&RTArduLinkHALConfig;
|
||||
|
||||
for (int i = 0; i < (int)sizeof(RTARDULINKHAL_EEPROM); i++)
|
||||
*data++ = EEPROM.read(i + RTARDULINKHAL_EEPROM_OFFSET);
|
||||
}
|
||||
|
||||
void RTArduLinkHALEEPROMWrite()
|
||||
{
|
||||
unsigned char *data;
|
||||
|
||||
data = (unsigned char *)&RTArduLinkHALConfig;
|
||||
|
||||
for (int i = 0; i < (int)sizeof(RTARDULINKHAL_EEPROM); i++)
|
||||
EEPROM.write(i + RTARDULINKHAL_EEPROM_OFFSET, *data++);
|
||||
}
|
|
@ -0,0 +1,141 @@
|
|||
///////////////////////////////////////////////////////////
|
||||
//
|
||||
// This file is part of RTArduLink
|
||||
//
|
||||
// Copyright (c) 2014-2015 richards-tech
|
||||
//
|
||||
// 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.
|
||||
|
||||
#ifndef _RTARDULINKHAL_H
|
||||
#define _RTARDULINKHAL_H
|
||||
|
||||
|
||||
//----------------------------------------------------------
|
||||
// Target-specific includes
|
||||
//
|
||||
//
|
||||
// Arduino HAL
|
||||
|
||||
#include <RTArduLinkDefs.h>
|
||||
#include <HardwareSerial.h>
|
||||
#include <EEPROM.h>
|
||||
|
||||
#define RTARDULINKHAL_MAX_SUBSYSTEM_PORTS 3 // maximum number of subsystem ports
|
||||
#define RTARDULINKHAL_MAX_PORTS (RTARDULINKHAL_MAX_SUBSYSTEM_PORTS + 1) // max total ports (including host)
|
||||
#define RTARDULINKHAL_EEPROM_OFFSET 256 // where the config starts in EEPROM
|
||||
|
||||
// RTARDULINKHAL_PORT should be modified as appropriate for the target.
|
||||
// There is one copy of this per port. It contains all state needed about
|
||||
// a serial port.
|
||||
|
||||
typedef struct
|
||||
{
|
||||
HardwareSerial *serialPort; // the serial port structure
|
||||
} RTARDULINKHAL_PORT;
|
||||
|
||||
// RTARDULINKHAL_EEPROM is the target-specific structure used to
|
||||
// store configs in EEPROM
|
||||
|
||||
// Signature bytes indicating valid config
|
||||
|
||||
#define RTARDULINKHAL_SIG0 0x38
|
||||
#define RTARDULINKHAL_SIG1 0xc1
|
||||
|
||||
typedef struct
|
||||
{
|
||||
unsigned char sig0; // signature byte 0
|
||||
unsigned char sig1; // signature byte 1
|
||||
char identity[RTARDULINK_DATA_MAX_LEN]; // identity string
|
||||
unsigned char portSpeed[RTARDULINKHAL_MAX_PORTS]; // port speed codes
|
||||
unsigned char hardwarePort[RTARDULINKHAL_MAX_PORTS]; // port number for hardware serial
|
||||
} RTARDULINKHAL_EEPROM;
|
||||
|
||||
// The global config structure
|
||||
|
||||
extern RTARDULINKHAL_EEPROM RTArduLinkHALConfig;
|
||||
|
||||
|
||||
|
||||
//----------------------------------------------------------
|
||||
//
|
||||
// These functions must be provided the RTArduLinkHAL for all implementations
|
||||
|
||||
// RTArduLinkHALConfigurePort() activates the specified port configuration specified by portIndex in port structure port.
|
||||
|
||||
bool RTArduLinkHALConfigurePort(RTARDULINKHAL_PORT *port, int portIndex);
|
||||
|
||||
|
||||
// RTArduLinkHALPortAvailable() returns the number of bytes availabel on the specified port.
|
||||
|
||||
int RTArduLinkHALPortAvailable(RTARDULINKHAL_PORT *port);
|
||||
|
||||
|
||||
// RTArduLinkHALPortRead() returns the next available byte from a port. Always check available bytes first
|
||||
|
||||
unsigned char RTArduLinkHALPortRead(RTARDULINKHAL_PORT *port);
|
||||
|
||||
|
||||
// RTArduLinkHALPortWrite() writes length bytes of the block pointed to by data to the specified port.
|
||||
|
||||
void RTArduLinkHALPortWrite(RTARDULINKHAL_PORT *port, unsigned char *data, unsigned char length);
|
||||
|
||||
|
||||
// RTArduLinkHALEEPROMValid() returns true if the EEPROM contains a valid configuration,
|
||||
// false otherwise.
|
||||
|
||||
bool RTArduLinkHALEEPROMValid(); // returns true if a valid config
|
||||
|
||||
|
||||
// RTArduLinkHALEEPROMDisplay() displays the current configuration
|
||||
|
||||
void RTArduLinkHALEEPROMDisplay(); // display the config
|
||||
|
||||
|
||||
// RTArduLinkHALEEPROMDisplayPort() displays the configuration for a single port
|
||||
// If suppress is true, nothing is displayed if the port is not enabled. If false
|
||||
// the port's data will be displayed regardless.
|
||||
|
||||
void RTArduLinkHALEEPROMDisplayPort(int port, bool suppress); // display the port config
|
||||
|
||||
|
||||
// RTArduLinkHALEEPROMDefault() writes a default config to EEPROM
|
||||
|
||||
void RTArduLinkHALEEPROMDefault(); // write and load default settings
|
||||
|
||||
|
||||
// RTArduLinkHALEEPROMRead() loads the EEPROM config into the RTArduLinkHALConfig
|
||||
// global structure.
|
||||
|
||||
void RTArduLinkHALEEPROMRead(); // to load the config
|
||||
|
||||
|
||||
// RTArduLinkHALEEPROMWrite() writes the config in the RTArduLinkHALConfig
|
||||
// global structure back to EEPROM.
|
||||
|
||||
void RTArduLinkHALEEPROMWrite(); // to write the config
|
||||
|
||||
|
||||
#endif // _RTARDULINKHAL_H
|
||||
|
|
@ -0,0 +1,181 @@
|
|||
///////////////////////////////////////////////////////////
|
||||
//
|
||||
// This file is part of RTArduLink
|
||||
//
|
||||
// Copyright (c) 2014-2015 richards-tech
|
||||
//
|
||||
// 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.
|
||||
|
||||
#include "RTArduLinkUtils.h"
|
||||
|
||||
// RTArduLinkRXFrameInit initializes the structure for a new frame using frameBuffer for storage
|
||||
|
||||
void RTArduLinkRXFrameInit(RTARDULINK_RXFRAME *RXFrame, RTARDULINK_FRAME *frameBuffer)
|
||||
{
|
||||
RXFrame->complete = false;
|
||||
RXFrame->length = 0;
|
||||
RXFrame->bytesLeft = 0;
|
||||
RXFrame->frameBuffer = frameBuffer;
|
||||
}
|
||||
|
||||
// RTArduLinkReassemble takes a sequence of received bytes and tries to complete a frame. It returns true if ok
|
||||
// false if error. The caller can determine if the frame is complete by checking the complete flag.
|
||||
|
||||
bool RTArduLinkReassemble(RTARDULINK_RXFRAME *RXFrame, unsigned char data)
|
||||
{
|
||||
bool flag = true;
|
||||
|
||||
((unsigned char *)(RXFrame->frameBuffer))[RXFrame->length] = data; // save byte in correct place
|
||||
switch (RXFrame->length) {
|
||||
case 0: // waiting for sync0
|
||||
if (RXFrame->frameBuffer->sync0 == RTARDULINK_MESSAGE_SYNC0) {
|
||||
RXFrame->length = 1;
|
||||
}
|
||||
break;
|
||||
|
||||
case 1: // waiting for sync1
|
||||
if (RXFrame->frameBuffer->sync1 == RTARDULINK_MESSAGE_SYNC1) {
|
||||
RXFrame->length = 2;
|
||||
} else {
|
||||
RXFrame->length = 0; // try again if not correct two byte sequence
|
||||
}
|
||||
break;
|
||||
|
||||
case 2: // should be message length
|
||||
if (RXFrame->frameBuffer->messageLength <= RTARDULINK_MESSAGE_MAX_LEN) {
|
||||
RXFrame->length = 3;
|
||||
RXFrame->bytesLeft = RXFrame->frameBuffer->messageLength + 1; // +1 to allow for the checksum
|
||||
} else {
|
||||
RXFrame->length = 0; // discard this and resync frame
|
||||
flag = false;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
RXFrame->length++;
|
||||
RXFrame->bytesLeft--;
|
||||
if (RXFrame->bytesLeft == 0) { // a complete frame!
|
||||
if (!RTArduLinkCheckChecksum(RXFrame->frameBuffer)) {
|
||||
RTArduLinkRXFrameInit(RXFrame, RXFrame->frameBuffer);
|
||||
flag = false; // flag the error
|
||||
} else {
|
||||
// this is a valid frame (so far)
|
||||
RXFrame->complete = true;
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
return flag;
|
||||
}
|
||||
|
||||
// RTArduLinkSetChecksum correctly sets the checksum field on an RCP frame prior to transmission
|
||||
//
|
||||
|
||||
void RTArduLinkSetChecksum(RTARDULINK_FRAME *frame)
|
||||
{
|
||||
int cksm;
|
||||
int i;
|
||||
unsigned char *data;
|
||||
|
||||
for (i = 0, cksm = 0, data = (unsigned char *)&(frame->message); i < frame |