2.0.2014120201

This commit is contained in:
Anthony Good 2014-12-02 23:03:17 -05:00
parent e01318a410
commit dca62e6692
15 changed files with 468 additions and 1097 deletions

View File

@ -1,114 +0,0 @@
/***************************************************************************
This is a library for the LSM303 Accelerometer and magnentometer/compass
Designed specifically to work with the Adafruit LSM303DLHC Breakout
These displays use I2C to communicate, 2 pins are required to interface.
Adafruit invests time and resources providing this open source code,
please support Adafruit andopen-source hardware by purchasing products
from Adafruit!
Written by Kevin Townsend for Adafruit Industries.
BSD license, all text above must be included in any redistribution
***************************************************************************/
#include <Adafruit_LSM303.h>
/***************************************************************************
CONSTRUCTOR
***************************************************************************/
bool Adafruit_LSM303::begin()
{
Wire.begin();
Serial.println("Wire");
// Enable the accelerometer
write8(LSM303_ADDRESS_ACCEL, LSM303_REGISTER_ACCEL_CTRL_REG1_A, 0x27);
// Enable the magnetometer
write8(LSM303_ADDRESS_MAG, LSM303_REGISTER_MAG_MR_REG_M, 0x00);
return true;
}
/***************************************************************************
PUBLIC FUNCTIONS
***************************************************************************/
void Adafruit_LSM303::read()
{
// Read the accelerometer
Wire.beginTransmission((byte)LSM303_ADDRESS_ACCEL);
Wire.write(LSM303_REGISTER_ACCEL_OUT_X_L_A | 0x80);
Wire.endTransmission();
Wire.requestFrom((byte)LSM303_ADDRESS_ACCEL, (byte)6);
// Wait around until enough data is available
while (Wire.available() < 6);
uint8_t xlo = Wire.read();
uint8_t xhi = Wire.read();
uint8_t ylo = Wire.read();
uint8_t yhi = Wire.read();
uint8_t zlo = Wire.read();
uint8_t zhi = Wire.read();
// Shift values to create properly formed integer (low byte first)
accelData.x = (xlo | (xhi << 8)) >> 4;
accelData.y = (ylo | (yhi << 8)) >> 4;
accelData.z = (zlo | (zhi << 8)) >> 4;
// Read the magnetometer
Wire.beginTransmission((byte)LSM303_ADDRESS_MAG);
Wire.write(LSM303_REGISTER_MAG_OUT_X_H_M);
Wire.endTransmission();
Wire.requestFrom((byte)LSM303_ADDRESS_MAG, (byte)6);
// Wait around until enough data is available
while (Wire.available() < 6);
// Note high before low (different than accel)
xhi = Wire.read();
xlo = Wire.read();
zhi = Wire.read();
zlo = Wire.read();
yhi = Wire.read();
ylo = Wire.read();
// Shift values to create properly formed integer (low byte first)
magData.x = (xlo | (xhi << 8));
magData.y = (ylo | (yhi << 8));
magData.z = (zlo | (zhi << 8));
// ToDo: Calculate orientation
magData.orientation = 0.0;
}
void Adafruit_LSM303::setMagGain(lsm303MagGain gain)
{
write8(LSM303_ADDRESS_MAG, LSM303_REGISTER_MAG_CRB_REG_M, (byte)gain);
}
/***************************************************************************
PRIVATE FUNCTIONS
***************************************************************************/
void Adafruit_LSM303::write8(byte address, byte reg, byte value)
{
Wire.beginTransmission(address);
Wire.write(reg);
Wire.write(value);
Wire.endTransmission();
}
byte Adafruit_LSM303::read8(byte address, byte reg)
{
byte value;
Wire.beginTransmission(address);
Wire.write(reg);
Wire.endTransmission();
Wire.requestFrom(address, (byte)1);
value = Wire.read();
Wire.endTransmission();
return value;
}

View File

@ -1,124 +0,0 @@
/***************************************************************************
This is a library for the LSM303 Accelerometer and magnentometer/compass
Designed specifically to work with the Adafruit LSM303DLHC Breakout
These displays use I2C to communicate, 2 pins are required to interface.
Adafruit invests time and resources providing this open source code,
please support Adafruit andopen-source hardware by purchasing products
from Adafruit!
Written by Kevin Townsend for Adafruit Industries.
BSD license, all text above must be included in any redistribution
***************************************************************************/
#ifndef __LSM303_H__
#define __LSM303_H__
#if (ARDUINO >= 100)
#include "Arduino.h"
#else
#include "WProgram.h"
#endif
#include "Wire.h"
#define LSM303_ADDRESS_ACCEL (0x32 >> 1) // 0011001x
#define LSM303_ADDRESS_MAG (0x3C >> 1) // 0011110x
#define LSM303_ID (0b11010100)
class Adafruit_LSM303
{
public:
typedef enum
{ // DEFAULT TYPE
LSM303_REGISTER_ACCEL_CTRL_REG1_A = 0x20, // 00000111 rw
LSM303_REGISTER_ACCEL_CTRL_REG2_A = 0x21, // 00000000 rw
LSM303_REGISTER_ACCEL_CTRL_REG3_A = 0x22, // 00000000 rw
LSM303_REGISTER_ACCEL_CTRL_REG4_A = 0x23, // 00000000 rw
LSM303_REGISTER_ACCEL_CTRL_REG5_A = 0x24, // 00000000 rw
LSM303_REGISTER_ACCEL_CTRL_REG6_A = 0x25, // 00000000 rw
LSM303_REGISTER_ACCEL_REFERENCE_A = 0x26, // 00000000 r
LSM303_REGISTER_ACCEL_STATUS_REG_A = 0x27, // 00000000 r
LSM303_REGISTER_ACCEL_OUT_X_L_A = 0x28,
LSM303_REGISTER_ACCEL_OUT_X_H_A = 0x29,
LSM303_REGISTER_ACCEL_OUT_Y_L_A = 0x2A,
LSM303_REGISTER_ACCEL_OUT_Y_H_A = 0x2B,
LSM303_REGISTER_ACCEL_OUT_Z_L_A = 0x2C,
LSM303_REGISTER_ACCEL_OUT_Z_H_A = 0x2D,
LSM303_REGISTER_ACCEL_FIFO_CTRL_REG_A = 0x2E,
LSM303_REGISTER_ACCEL_FIFO_SRC_REG_A = 0x2F,
LSM303_REGISTER_ACCEL_INT1_CFG_A = 0x30,
LSM303_REGISTER_ACCEL_INT1_SOURCE_A = 0x31,
LSM303_REGISTER_ACCEL_INT1_THS_A = 0x32,
LSM303_REGISTER_ACCEL_INT1_DURATION_A = 0x33,
LSM303_REGISTER_ACCEL_INT2_CFG_A = 0x34,
LSM303_REGISTER_ACCEL_INT2_SOURCE_A = 0x35,
LSM303_REGISTER_ACCEL_INT2_THS_A = 0x36,
LSM303_REGISTER_ACCEL_INT2_DURATION_A = 0x37,
LSM303_REGISTER_ACCEL_CLICK_CFG_A = 0x38,
LSM303_REGISTER_ACCEL_CLICK_SRC_A = 0x39,
LSM303_REGISTER_ACCEL_CLICK_THS_A = 0x3A,
LSM303_REGISTER_ACCEL_TIME_LIMIT_A = 0x3B,
LSM303_REGISTER_ACCEL_TIME_LATENCY_A = 0x3C,
LSM303_REGISTER_ACCEL_TIME_WINDOW_A = 0x3D
} lsm303AccelRegisters_t;
typedef enum
{
LSM303_REGISTER_MAG_CRA_REG_M = 0x00,
LSM303_REGISTER_MAG_CRB_REG_M = 0x01,
LSM303_REGISTER_MAG_MR_REG_M = 0x02,
LSM303_REGISTER_MAG_OUT_X_H_M = 0x03,
LSM303_REGISTER_MAG_OUT_X_L_M = 0x04,
LSM303_REGISTER_MAG_OUT_Z_H_M = 0x05,
LSM303_REGISTER_MAG_OUT_Z_L_M = 0x06,
LSM303_REGISTER_MAG_OUT_Y_H_M = 0x07,
LSM303_REGISTER_MAG_OUT_Y_L_M = 0x08,
LSM303_REGISTER_MAG_SR_REG_Mg = 0x09,
LSM303_REGISTER_MAG_IRA_REG_M = 0x0A,
LSM303_REGISTER_MAG_IRB_REG_M = 0x0B,
LSM303_REGISTER_MAG_IRC_REG_M = 0x0C,
LSM303_REGISTER_MAG_TEMP_OUT_H_M = 0x31,
LSM303_REGISTER_MAG_TEMP_OUT_L_M = 0x32
} lsm303MagRegisters_t;
typedef enum
{
LSM303_MAGGAIN_1_3 = 0x20, // +/- 1.3
LSM303_MAGGAIN_1_9 = 0x40, // +/- 1.9
LSM303_MAGGAIN_2_5 = 0x60, // +/- 2.5
LSM303_MAGGAIN_4_0 = 0x80, // +/- 4.0
LSM303_MAGGAIN_4_7 = 0xA0, // +/- 4.7
LSM303_MAGGAIN_5_6 = 0xC0, // +/- 5.6
LSM303_MAGGAIN_8_1 = 0xE0 // +/- 8.1
} lsm303MagGain;
typedef struct lsm303AccelData_s
{
float x;
float y;
float z;
} lsm303AccelData;
typedef struct lsm303MagData_s
{
float x;
float y;
float z;
float orientation;
} lsm303MagData;
bool begin(void);
void read(void);
void setMagGain(lsm303MagGain gain);
lsm303AccelData accelData; // Last read accelerometer data will be available here
lsm303MagData magData; // Last read magnetometer data will be available here
void write8(byte address, byte reg, byte value);
byte read8(byte address, byte reg);
private:
};
#endif

View File

@ -1,570 +0,0 @@
#include <LSM303.h>
#include <Wire.h>
#include <math.h>
// Defines ////////////////////////////////////////////////////////////////
// The Arduino two-wire interface uses a 7-bit number for the address,
// and sets the last bit correctly based on reads and writes
#define D_SA0_HIGH_ADDRESS 0b0011101 // D with SA0 high
#define D_SA0_LOW_ADDRESS 0b0011110 // D with SA0 low or non-D magnetometer
#define NON_D_MAG_ADDRESS 0b0011110 // D with SA0 low or non-D magnetometer
#define NON_D_ACC_SA0_LOW_ADDRESS 0b0011000 // non-D accelerometer with SA0 low
#define NON_D_ACC_SA0_HIGH_ADDRESS 0b0011001 // non-D accelerometer with SA0 high
#define TEST_REG_NACK -1
#define D_WHO_ID 0x49
#define DLM_WHO_ID 0x3C
// Constructors ////////////////////////////////////////////////////////////////
LSM303::LSM303(void)
{
/*
These values lead to an assumed magnetometer bias of 0.
Use the Calibrate example program to determine appropriate values
for your particular unit. The Heading example demonstrates how to
adjust these values in your own sketch.
*/
m_min = (LSM303::vector<int16_t>){-32767, -32767, -32767};
m_max = (LSM303::vector<int16_t>){+32767, +32767, +32767};
_device = device_auto;
io_timeout = 0; // 0 = no timeout
did_timeout = false;
}
// Public Methods //////////////////////////////////////////////////////////////
// Did a timeout occur in readAcc(), readMag(), or read() since the last call to timeoutOccurred()?
bool LSM303::timeoutOccurred()
{
bool tmp = did_timeout;
did_timeout = false;
return tmp;
}
void LSM303::setTimeout(unsigned int timeout)
{
io_timeout = timeout;
}
unsigned int LSM303::getTimeout()
{
return io_timeout;
}
bool LSM303::init(deviceType device, sa0State sa0)
{
// determine device type if necessary
if (device == device_auto)
{
if (testReg(D_SA0_HIGH_ADDRESS, WHO_AM_I) == D_WHO_ID)
{
// device responds to address 0011101 with D ID; it's a D with SA0 high
device = device_D;
sa0 = sa0_high;
}
else if (testReg(D_SA0_LOW_ADDRESS, WHO_AM_I) == D_WHO_ID)
{
// device responds to address 0011110 with D ID; it's a D with SA0 low
device = device_D;
sa0 = sa0_low;
}
// Remaining possibilities: DLHC, DLM, or DLH. DLHC seems to respond to WHO_AM_I request the
// same way as DLM, even though this register isn't documented in its datasheet, so instead,
// guess if it's a DLHC based on acc address (Pololu boards pull SA0 low on DLM and DLH;
// DLHC doesn't have SA0 but uses same acc address as DLH/DLM with SA0 high).
else if (testReg(NON_D_ACC_SA0_HIGH_ADDRESS, CTRL_REG1_A) != TEST_REG_NACK)
{
// device responds to address 0011001; guess that it's a DLHC
device = device_DLHC;
sa0 = sa0_high;
}
// Remaining possibilities: DLM or DLH. Check acc with SA0 low address to make sure it's responsive
else if (testReg(NON_D_ACC_SA0_LOW_ADDRESS, CTRL_REG1_A) != TEST_REG_NACK)
{
// device responds to address 0011000 with DLM ID; guess that it's a DLM
sa0 = sa0_low;
// Now check WHO_AM_I_M
if (testReg(NON_D_MAG_ADDRESS, WHO_AM_I_M) == DLM_WHO_ID)
{
device = device_DLM;
}
else
{
device = device_DLH;
}
}
else
{
// device hasn't responded meaningfully, so give up
return false;
}
}
// determine SA0 if necessary
if (sa0 == sa0_auto)
{
if (device == device_D)
{
if (testReg(D_SA0_HIGH_ADDRESS, WHO_AM_I) == D_WHO_ID)
{
sa0 = sa0_high;
}
else if (testReg(D_SA0_LOW_ADDRESS, WHO_AM_I) == D_WHO_ID)
{
sa0 = sa0_low;
}
else
{
// no response on either possible address; give up
return false;
}
}
else if (device == device_DLM || device == device_DLH)
{
if (testReg(NON_D_ACC_SA0_HIGH_ADDRESS, CTRL_REG1_A) != TEST_REG_NACK)
{
sa0 = sa0_high;
}
else if (testReg(NON_D_ACC_SA0_LOW_ADDRESS, CTRL_REG1_A) != TEST_REG_NACK)
{
sa0 = sa0_low;
}
else
{
// no response on either possible address; give up
return false;
}
}
}
_device = device;
// set device addresses and translated register addresses
switch (device)
{
case device_D:
acc_address = mag_address = (sa0 == sa0_high) ? D_SA0_HIGH_ADDRESS : D_SA0_LOW_ADDRESS;
translated_regs[-OUT_X_L_M] = D_OUT_X_L_M;
translated_regs[-OUT_X_H_M] = D_OUT_X_H_M;
translated_regs[-OUT_Y_L_M] = D_OUT_Y_L_M;
translated_regs[-OUT_Y_H_M] = D_OUT_Y_H_M;
translated_regs[-OUT_Z_L_M] = D_OUT_Z_L_M;
translated_regs[-OUT_Z_H_M] = D_OUT_Z_H_M;
break;
case device_DLHC:
acc_address = NON_D_ACC_SA0_HIGH_ADDRESS; // DLHC doesn't have SA0 but uses same acc address as DLH/DLM with SA0 high
mag_address = NON_D_MAG_ADDRESS;
translated_regs[-OUT_X_H_M] = DLHC_OUT_X_H_M;
translated_regs[-OUT_X_L_M] = DLHC_OUT_X_L_M;
translated_regs[-OUT_Y_H_M] = DLHC_OUT_Y_H_M;
translated_regs[-OUT_Y_L_M] = DLHC_OUT_Y_L_M;
translated_regs[-OUT_Z_H_M] = DLHC_OUT_Z_H_M;
translated_regs[-OUT_Z_L_M] = DLHC_OUT_Z_L_M;
break;
case device_DLM:
acc_address = (sa0 == sa0_high) ? NON_D_ACC_SA0_HIGH_ADDRESS : NON_D_ACC_SA0_LOW_ADDRESS;
mag_address = NON_D_MAG_ADDRESS;
translated_regs[-OUT_X_H_M] = DLM_OUT_X_H_M;
translated_regs[-OUT_X_L_M] = DLM_OUT_X_L_M;
translated_regs[-OUT_Y_H_M] = DLM_OUT_Y_H_M;
translated_regs[-OUT_Y_L_M] = DLM_OUT_Y_L_M;
translated_regs[-OUT_Z_H_M] = DLM_OUT_Z_H_M;
translated_regs[-OUT_Z_L_M] = DLM_OUT_Z_L_M;
break;
case device_DLH:
acc_address = (sa0 == sa0_high) ? NON_D_ACC_SA0_HIGH_ADDRESS : NON_D_ACC_SA0_LOW_ADDRESS;
mag_address = NON_D_MAG_ADDRESS;
translated_regs[-OUT_X_H_M] = DLH_OUT_X_H_M;
translated_regs[-OUT_X_L_M] = DLH_OUT_X_L_M;
translated_regs[-OUT_Y_H_M] = DLH_OUT_Y_H_M;
translated_regs[-OUT_Y_L_M] = DLH_OUT_Y_L_M;
translated_regs[-OUT_Z_H_M] = DLH_OUT_Z_H_M;
translated_regs[-OUT_Z_L_M] = DLH_OUT_Z_L_M;
break;
}
return true;
}
/*
Enables the LSM303's accelerometer and magnetometer. Also:
- Sets sensor full scales (gain) to default power-on values, which are
+/- 2 g for accelerometer and +/- 1.3 gauss for magnetometer
(+/- 4 gauss on LSM303D).
- Selects 50 Hz ODR (output data rate) for accelerometer and 7.5 Hz
ODR for magnetometer (6.25 Hz on LSM303D). (These are the ODR
settings for which the electrical characteristics are specified in
the datasheets.)
- Enables high resolution modes (if available).
Note that this function will also reset other settings controlled by
the registers it writes to.
*/
void LSM303::enableDefault(void)
{
if (_device == device_D)
{
// Accelerometer
// 0x57 = 0b01010111
// AFS = 0 (+/- 2 g full scale)
writeReg(CTRL2, 0x00);
// 0x57 = 0b01010111
// AODR = 0101 (50 Hz ODR); AZEN = AYEN = AXEN = 1 (all axes enabled)
writeReg(CTRL1, 0x57);
// Magnetometer
// 0x64 = 0b01100100
// M_RES = 11 (high resolution mode); M_ODR = 001 (6.25 Hz ODR)
writeReg(CTRL5, 0x64);
// 0x20 = 0b00100000
// MFS = 01 (+/- 4 gauss full scale)
writeReg(CTRL6, 0x20);
// 0x00 = 0b00000000
// MLP = 0 (low power mode off); MD = 00 (continuous-conversion mode)
writeReg(CTRL7, 0x00);
}
else if (_device == device_DLHC)
{
// Accelerometer
// 0x08 = 0b00001000
// FS = 00 (+/- 2 g full scale); HR = 1 (high resolution enable)
writeAccReg(CTRL_REG4_A, 0x08);
// 0x47 = 0b01000111
// ODR = 0100 (50 Hz ODR); LPen = 0 (normal mode); Zen = Yen = Xen = 1 (all axes enabled)
writeAccReg(CTRL_REG1_A, 0x47);
// Magnetometer
// 0x0C = 0b00001100
// DO = 011 (7.5 Hz ODR)
writeMagReg(CRA_REG_M, 0x0C);
// 0x20 = 0b00100000
// GN = 001 (+/- 1.3 gauss full scale)
writeMagReg(CRB_REG_M, 0x20);
// 0x00 = 0b00000000
// MD = 00 (continuous-conversion mode)
writeMagReg(MR_REG_M, 0x00);
}
else // DLM, DLH
{
// Accelerometer
// 0x00 = 0b00000000
// FS = 00 (+/- 2 g full scale)
writeAccReg(CTRL_REG4_A, 0x00);
// 0x27 = 0b00100111
// PM = 001 (normal mode); DR = 00 (50 Hz ODR); Zen = Yen = Xen = 1 (all axes enabled)
writeAccReg(CTRL_REG1_A, 0x27);
// Magnetometer
// 0x0C = 0b00001100
// DO = 011 (7.5 Hz ODR)
writeMagReg(CRA_REG_M, 0x0C);
// 0x20 = 0b00100000
// GN = 001 (+/- 1.3 gauss full scale)
writeMagReg(CRB_REG_M, 0x20);
// 0x00 = 0b00000000
// MD = 00 (continuous-conversion mode)
writeMagReg(MR_REG_M, 0x00);
}
}
// Writes an accelerometer register
void LSM303::writeAccReg(regAddr reg, byte value)
{
Wire.beginTransmission(acc_address);
Wire.write((byte)reg);
Wire.write(value);
last_status = Wire.endTransmission();
}
// Reads an accelerometer register
byte LSM303::readAccReg(regAddr reg)
{
byte value;
Wire.beginTransmission(acc_address);
Wire.write((byte)reg);
last_status = Wire.endTransmission();
Wire.requestFrom(acc_address, (byte)1);
value = Wire.read();
Wire.endTransmission();
return value;
}
// Writes a magnetometer register
void LSM303::writeMagReg(regAddr reg, byte value)
{
Wire.beginTransmission(mag_address);
Wire.write((byte)reg);
Wire.write(value);
last_status = Wire.endTransmission();
}
// Reads a magnetometer register
byte LSM303::readMagReg(regAddr reg)
{
byte value;
// if dummy register address (magnetometer Y/Z), look up actual translated address (based on device type)
if (reg < 0)
{
reg = translated_regs[-reg];
}
Wire.beginTransmission(mag_address);
Wire.write((byte)reg);
last_status = Wire.endTransmission();
Wire.requestFrom(mag_address, (byte)1);
value = Wire.read();
Wire.endTransmission();
return value;
}
void LSM303::writeReg(regAddr reg, byte value)
{
// mag address == acc_address for LSM303D, so it doesn't really matter which one we use.
// Use writeMagReg so it can translate OUT_[XYZ]_[HL]_M
if (_device == device_D || reg < CTRL_REG1_A)
{
writeMagReg(reg, value);
}
else
{
writeAccReg(reg, value);
}
}
// Note that this function will not work for reading TEMP_OUT_H_M and TEMP_OUT_L_M on the DLHC.
// To read those two registers, use readMagReg() instead.
byte LSM303::readReg(regAddr reg)
{
// mag address == acc_address for LSM303D, so it doesn't really matter which one we use.
// Use writeMagReg so it can translate OUT_[XYZ]_[HL]_M
if (_device == device_D || reg < CTRL_REG1_A)
{
return readMagReg(reg);
}
else
{
return readAccReg(reg);
}
}
// Reads the 3 accelerometer channels and stores them in vector a
void LSM303::readAcc(void)
{
Wire.beginTransmission(acc_address);
// assert the MSB of the address to get the accelerometer
// to do slave-transmit subaddress updating.
Wire.write(OUT_X_L_A | (1 << 7));
last_status = Wire.endTransmission();
Wire.requestFrom(acc_address, (byte)6);
unsigned int millis_start = millis();
while (Wire.available() < 6) {
if (io_timeout > 0 && ((unsigned int)millis() - millis_start) > io_timeout)
{
did_timeout = true;
return;
}
}
byte xla = Wire.read();
byte xha = Wire.read();
byte yla = Wire.read();
byte yha = Wire.read();
byte zla = Wire.read();
byte zha = Wire.read();
// combine high and low bytes
// This no longer drops the lowest 4 bits of the readings from the DLH/DLM/DLHC, which are always 0
// (12-bit resolution, left-aligned). The D has 16-bit resolution
a.x = (int16_t)(xha << 8 | xla);
a.y = (int16_t)(yha << 8 | yla);
a.z = (int16_t)(zha << 8 | zla);
}
// Reads the 3 magnetometer channels and stores them in vector m
void LSM303::readMag(void)
{
Wire.beginTransmission(mag_address);
// If LSM303D, assert MSB to enable subaddress updating
// OUT_X_L_M comes first on D, OUT_X_H_M on others
Wire.write((_device == device_D) ? translated_regs[-OUT_X_L_M] | (1 << 7) : translated_regs[-OUT_X_H_M]);
last_status = Wire.endTransmission();
Wire.requestFrom(mag_address, (byte)6);
unsigned int millis_start = millis();
while (Wire.available() < 6) {
if (io_timeout > 0 && ((unsigned int)millis() - millis_start) > io_timeout)
{
did_timeout = true;
return;
}
}
byte xlm, xhm, ylm, yhm, zlm, zhm;
if (_device == device_D)
{
/// D: X_L, X_H, Y_L, Y_H, Z_L, Z_H
xlm = Wire.read();
xhm = Wire.read();
ylm = Wire.read();
yhm = Wire.read();
zlm = Wire.read();
zhm = Wire.read();
}
else
{
// DLHC, DLM, DLH: X_H, X_L...
xhm = Wire.read();
xlm = Wire.read();
if (_device == device_DLH)
{
// DLH: ...Y_H, Y_L, Z_H, Z_L
yhm = Wire.read();
ylm = Wire.read();
zhm = Wire.read();
zlm = Wire.read();
}
else
{
// DLM, DLHC: ...Z_H, Z_L, Y_H, Y_L
zhm = Wire.read();
zlm = Wire.read();
yhm = Wire.read();
ylm = Wire.read();
}
}
// combine high and low bytes
m.x = (int16_t)(xhm << 8 | xlm);
m.y = (int16_t)(yhm << 8 | ylm);
m.z = (int16_t)(zhm << 8 | zlm);
}
// Reads all 6 channels of the LSM303 and stores them in the object variables
void LSM303::read(void)
{
readAcc();
readMag();
}
/*
Returns the angular difference in the horizontal plane between a
default vector and north, in degrees.
The default vector here is chosen to point along the surface of the
PCB, in the direction of the top of the text on the silkscreen.
This is the +X axis on the Pololu LSM303D carrier and the -Y axis on
the Pololu LSM303DLHC, LSM303DLM, and LSM303DLH carriers.
*/
float LSM303::heading(void)
{
if (_device == device_D)
{
return heading((vector<int>){1, 0, 0});
}
else
{
return heading((vector<int>){0, -1, 0});
}
}
/*
Returns the angular difference in the horizontal plane between the
"from" vector and north, in degrees.
Description of heading algorithm:
Shift and scale the magnetic reading based on calibration data to find
the North vector. Use the acceleration readings to determine the Up
vector (gravity is measured as an upward acceleration). The cross
product of North and Up vectors is East. The vectors East and North
form a basis for the horizontal plane. The From vector is projected
into the horizontal plane and the angle between the projected vector
and horizontal north is returned.
*/
template <typename T> float LSM303::heading(vector<T> from)
{
vector<int32_t> temp_m = {m.x, m.y, m.z};
// subtract offset (average of min and max) from magnetometer readings
temp_m.x -= ((int32_t)m_min.x + m_max.x) / 2;
temp_m.y -= ((int32_t)m_min.y + m_max.y) / 2;
temp_m.z -= ((int32_t)m_min.z + m_max.z) / 2;
// compute E and N
vector<float> E;
vector<float> N;
vector_cross(&temp_m, &a, &E);
vector_normalize(&E);
vector_cross(&a, &E, &N);
vector_normalize(&N);
// compute heading
float heading = atan2(vector_dot(&E, &from), vector_dot(&N, &from)) * 180 / M_PI;
if (heading < 0) heading += 360;
return heading;
}
template <typename Ta, typename Tb, typename To> void LSM303::vector_cross(const vector<Ta> *a,const vector<Tb> *b, vector<To> *out)
{
out->x = (a->y * b->z) - (a->z * b->y);
out->y = (a->z * b->x) - (a->x * b->z);
out->z = (a->x * b->y) - (a->y * b->x);
}
template <typename Ta, typename Tb> float LSM303::vector_dot(const vector<Ta> *a, const vector<Tb> *b)
{
return (a->x * b->x) + (a->y * b->y) + (a->z * b->z);
}
void LSM303::vector_normalize(vector<float> *a)
{
float mag = sqrt(vector_dot(a, a));
a->x /= mag;
a->y /= mag;
a->z /= mag;
}
// Private Methods //////////////////////////////////////////////////////////////
int LSM303::testReg(byte address, regAddr reg)
{
Wire.beginTransmission(address);
Wire.write((byte)reg);
last_status = Wire.endTransmission();
Wire.requestFrom(address, (byte)1);
if (Wire.available())
return Wire.read();
else
return TEST_REG_NACK;
}

218
LSM303.h
View File

@ -1,218 +0,0 @@
#ifndef LSM303_h
#define LSM303_h
#include <Arduino.h> // for byte data type
class LSM303
{
public:
template <typename T> struct vector
{
T x, y, z;
};
enum deviceType { device_DLH, device_DLM, device_DLHC, device_D, device_auto };
enum sa0State { sa0_low, sa0_high, sa0_auto };
// register addresses
enum regAddr
{
TEMP_OUT_L = 0x05, // D
TEMP_OUT_H = 0x06, // D
STATUS_M = 0x07, // D
INT_CTRL_M = 0x12, // D
INT_SRC_M = 0x13, // D
INT_THS_L_M = 0x14, // D
INT_THS_H_M = 0x15, // D
OFFSET_X_L_M = 0x16, // D
OFFSET_X_H_M = 0x17, // D
OFFSET_Y_L_M = 0x18, // D
OFFSET_Y_H_M = 0x19, // D
OFFSET_Z_L_M = 0x1A, // D
OFFSET_Z_H_M = 0x1B, // D
REFERENCE_X = 0x1C, // D
REFERENCE_Y = 0x1D, // D
REFERENCE_Z = 0x1E, // D
CTRL0 = 0x1F, // D
CTRL1 = 0x20, // D
CTRL_REG1_A = 0x20, // DLH, DLM, DLHC
CTRL2 = 0x21, // D
CTRL_REG2_A = 0x21, // DLH, DLM, DLHC
CTRL3 = 0x22, // D
CTRL_REG3_A = 0x22, // DLH, DLM, DLHC
CTRL4 = 0x23, // D
CTRL_REG4_A = 0x23, // DLH, DLM, DLHC
CTRL5 = 0x24, // D
CTRL_REG5_A = 0x24, // DLH, DLM, DLHC
CTRL6 = 0x25, // D
CTRL_REG6_A = 0x25, // DLHC
HP_FILTER_RESET_A = 0x25, // DLH, DLM
CTRL7 = 0x26, // D
REFERENCE_A = 0x26, // DLH, DLM, DLHC
STATUS_A = 0x27, // D
STATUS_REG_A = 0x27, // DLH, DLM, DLHC
OUT_X_L_A = 0x28,
OUT_X_H_A = 0x29,
OUT_Y_L_A = 0x2A,
OUT_Y_H_A = 0x2B,
OUT_Z_L_A = 0x2C,
OUT_Z_H_A = 0x2D,
FIFO_CTRL = 0x2E, // D
FIFO_CTRL_REG_A = 0x2E, // DLHC
FIFO_SRC = 0x2F, // D
FIFO_SRC_REG_A = 0x2F, // DLHC
IG_CFG1 = 0x30, // D
INT1_CFG_A = 0x30, // DLH, DLM, DLHC
IG_SRC1 = 0x31, // D
INT1_SRC_A = 0x31, // DLH, DLM, DLHC
IG_THS1 = 0x32, // D
INT1_THS_A = 0x32, // DLH, DLM, DLHC
IG_DUR1 = 0x33, // D
INT1_DURATION_A = 0x33, // DLH, DLM, DLHC
IG_CFG2 = 0x34, // D
INT2_CFG_A = 0x34, // DLH, DLM, DLHC
IG_SRC2 = 0x35, // D
INT2_SRC_A = 0x35, // DLH, DLM, DLHC
IG_THS2 = 0x36, // D
INT2_THS_A = 0x36, // DLH, DLM, DLHC
IG_DUR2 = 0x37, // D
INT2_DURATION_A = 0x37, // DLH, DLM, DLHC
CLICK_CFG = 0x38, // D
CLICK_CFG_A = 0x38, // DLHC
CLICK_SRC = 0x39, // D
CLICK_SRC_A = 0x39, // DLHC
CLICK_THS = 0x3A, // D
CLICK_THS_A = 0x3A, // DLHC
TIME_LIMIT = 0x3B, // D
TIME_LIMIT_A = 0x3B, // DLHC
TIME_LATENCY = 0x3C, // D
TIME_LATENCY_A = 0x3C, // DLHC
TIME_WINDOW = 0x3D, // D
TIME_WINDOW_A = 0x3D, // DLHC
Act_THS = 0x3E, // D
Act_DUR = 0x3F, // D
CRA_REG_M = 0x00, // DLH, DLM, DLHC
CRB_REG_M = 0x01, // DLH, DLM, DLHC
MR_REG_M = 0x02, // DLH, DLM, DLHC
SR_REG_M = 0x09, // DLH, DLM, DLHC
IRA_REG_M = 0x0A, // DLH, DLM, DLHC
IRB_REG_M = 0x0B, // DLH, DLM, DLHC
IRC_REG_M = 0x0C, // DLH, DLM, DLHC
WHO_AM_I_M = 0x0F, // DLM
WHO_AM_I = 0x0F, // D
TEMP_OUT_H_M = 0x31, // DLHC
TEMP_OUT_L_M = 0x32, // DLHC
// dummy addresses for registers in different locations on different devices;
// the library translates these based on device type
// value with sign flipped is used as index into translated_regs array
OUT_X_H_M = -1,
OUT_X_L_M = -2,
OUT_Y_H_M = -3,
OUT_Y_L_M = -4,
OUT_Z_H_M = -5,
OUT_Z_L_M = -6,
// update dummy_reg_count if registers are added here!
// device-specific register addresses
DLH_OUT_X_H_M = 0x03,
DLH_OUT_X_L_M = 0x04,
DLH_OUT_Y_H_M = 0x05,
DLH_OUT_Y_L_M = 0x06,
DLH_OUT_Z_H_M = 0x07,
DLH_OUT_Z_L_M = 0x08,
DLM_OUT_X_H_M = 0x03,
DLM_OUT_X_L_M = 0x04,
DLM_OUT_Z_H_M = 0x05,
DLM_OUT_Z_L_M = 0x06,
DLM_OUT_Y_H_M = 0x07,
DLM_OUT_Y_L_M = 0x08,
DLHC_OUT_X_H_M = 0x03,
DLHC_OUT_X_L_M = 0x04,
DLHC_OUT_Z_H_M = 0x05,
DLHC_OUT_Z_L_M = 0x06,
DLHC_OUT_Y_H_M = 0x07,
DLHC_OUT_Y_L_M = 0x08,
D_OUT_X_L_M = 0x08,
D_OUT_X_H_M = 0x09,
D_OUT_Y_L_M = 0x0A,
D_OUT_Y_H_M = 0x0B,
D_OUT_Z_L_M = 0x0C,
D_OUT_Z_H_M = 0x0D
};
vector<int16_t> a; // accelerometer readings
vector<int16_t> m; // magnetometer readings
vector<int16_t> m_max; // maximum magnetometer values, used for calibration
vector<int16_t> m_min; // minimum magnetometer values, used for calibration
byte last_status; // status of last I2C transmission
LSM303(void);
bool init(deviceType device = device_auto, sa0State sa0 = sa0_auto);
byte getDeviceType(void) { return _device; }
void enableDefault(void);
void writeAccReg(regAddr reg, byte value);
byte readAccReg(regAddr reg);
void writeMagReg(regAddr reg, byte value);
byte readMagReg(regAddr reg);
void writeReg(regAddr reg, byte value);
byte readReg(regAddr reg);
void readAcc(void);
void readMag(void);
void read(void);
void setTimeout(unsigned int timeout);
unsigned int getTimeout(void);
bool timeoutOccurred(void);
float heading(void);
template <typename T> float heading(vector<T> from);
// vector functions
template <typename Ta, typename Tb, typename To> static void vector_cross(const vector<Ta> *a, const vector<Tb> *b, vector<To> *out);
template <typename Ta, typename Tb> static float vector_dot(const vector<Ta> *a,const vector<Tb> *b);
static void vector_normalize(vector<float> *a);
private:
deviceType _device; // chip type (DLH, DLM, or DLHC)
byte acc_address;
byte mag_address;
static const int dummy_reg_count = 6;
regAddr translated_regs[dummy_reg_count + 1]; // index 0 not used
unsigned int io_timeout;
bool did_timeout;
int testReg(byte address, regAddr reg);
};
#endif

103
TimerFive.cpp Normal file
View File

@ -0,0 +1,103 @@
/*
* Interrupt and PWM utilities for 16 bit Timer5 on ATmega640/1280/2560
* Original code by Jesse Tane for http://labs.ideo.com August 2008
* Modified March 2009 by Jérôme Despatis and Jesse Tane for ATmega328 support
* Modified June 2009 by Michael Polli and Jesse Tane to fix a bug in setPeriod() which caused the timer to stop
* Modified Oct 2009 by Dan Clemens to work with timer3 of the ATMega1280 or Arduino Mega
* Modified Aug 2011 by RobotFreak to work with timer5 of the ATMega640/1280/2560 or Arduino Mega/ADK
*
* This is free software. You can redistribute it and/or modify it under
* the terms of Creative Commons Attribution 3.0 United States License.
* To view a copy of this license, visit http://creativecommons.org/licenses/by/3.0/us/
* or send a letter to Creative Commons, 171 Second Street, Suite 300, San Francisco, California, 94105, USA.
*
*/
#include "TimerFive.h"
TimerFive Timer5; // preinstatiate
ISR(TIMER5_OVF_vect) // interrupt service routine that wraps a user defined function supplied by attachInterrupt
{
Timer5.isrCallback();
}
void TimerFive::initialize(long microseconds)
{
TCCR5A = 0; // clear control register A
TCCR5B = _BV(WGM53); // set mode as phase and frequency correct pwm, stop the timer
setPeriod(microseconds);
}
void TimerFive::setPeriod(long microseconds)
{
long cycles = (F_CPU * microseconds) / 2000000; // the counter runs backwards after TOP, interrupt is at BOTTOM so divide microseconds by 2
if(cycles < RESOLUTION) clockSelectBits = _BV(CS50); // no prescale, full xtal
else if((cycles >>= 3) < RESOLUTION) clockSelectBits = _BV(CS51); // prescale by /8
else if((cycles >>= 3) < RESOLUTION) clockSelectBits = _BV(CS51) | _BV(CS50); // prescale by /64
else if((cycles >>= 2) < RESOLUTION) clockSelectBits = _BV(CS52); // prescale by /256
else if((cycles >>= 2) < RESOLUTION) clockSelectBits = _BV(CS52) | _BV(CS50); // prescale by /1024
else cycles = RESOLUTION - 1, clockSelectBits = _BV(CS52) | _BV(CS50); // request was out of bounds, set as maximum
ICR5 = pwmPeriod = cycles; // ICR1 is TOP in p & f correct pwm mode
TCCR5B &= ~(_BV(CS50) | _BV(CS51) | _BV(CS52));
TCCR5B |= clockSelectBits; // reset clock select register
}
void TimerFive::setPwmDuty(char pin, int duty)
{
unsigned long dutyCycle = pwmPeriod;
dutyCycle *= duty;
dutyCycle >>= 10;
if(pin == 46) OCR5A = dutyCycle;
if(pin == 45) OCR5B = dutyCycle;
if(pin == 44) OCR5C = dutyCycle;
}
void TimerFive::pwm(char pin, int duty, long microseconds) // expects duty cycle to be 10 bit (1024)
{
if(microseconds > 0) setPeriod(microseconds);
// sets data direction register for pwm output pin
// activates the output pin
if(pin == 46) { DDRE |= _BV(PORTL3); TCCR5A |= _BV(COM5A1); }
if(pin == 45) { DDRE |= _BV(PORTL4); TCCR5A |= _BV(COM5B1); }
if(pin == 44) { DDRE |= _BV(PORTL5); TCCR5A |= _BV(COM5C1); }
setPwmDuty(pin, duty);
start();
}
void TimerFive::disablePwm(char pin)
{
if(pin == 46) TCCR5A &= ~_BV(COM5A1); // clear the bit that enables pwm on PE3
if(pin == 45) TCCR5A &= ~_BV(COM5B1); // clear the bit that enables pwm on PE4
if(pin == 44) TCCR5A &= ~_BV(COM5C1); // clear the bit that enables pwm on PE5
}
void TimerFive::attachInterrupt(void (*isr)(), long microseconds)
{
if(microseconds > 0) setPeriod(microseconds);
isrCallback = isr; // register the user's callback with the real ISR
TIMSK5 = _BV(TOIE5); // sets the timer overflow interrupt enable bit
sei(); // ensures that interrupts are globally enabled
start();
}
void TimerFive::detachInterrupt()
{
TIMSK5 &= ~_BV(TOIE5); // clears the timer overflow interrupt enable bit
}
void TimerFive::start()
{
TCCR5B |= clockSelectBits;
}
void TimerFive::stop()
{
TCCR5B &= ~(_BV(CS50) | _BV(CS51) | _BV(CS52)); // clears all clock selects bits
}
void TimerFive::restart()
{
TCNT5 = 0;
}

42
TimerFive.h Executable file
View File

@ -0,0 +1,42 @@
/*
* Interrupt and PWM utilities for 16 bit Timer5 on ATmega640/1280/2560
* Original code by Jesse Tane for http://labs.ideo.com August 2008
* Modified March 2009 by Jérôme Despatis and Jesse Tane for ATmega328 support
* Modified June 2009 by Michael Polli and Jesse Tane to fix a bug in setPeriod() which caused the timer to stop
* Modified Aug 2011 by RobotFreak to work with timer5 of the ATMega640/1280/2560 or Arduino Mega/ADK
*
* This is free software. You can redistribute it and/or modify it under
* the terms of Creative Commons Attribution 3.0 United States License.
* To view a copy of this license, visit http://creativecommons.org/licenses/by/3.0/us/
* or send a letter to Creative Commons, 171 Second Street, Suite 300, San Francisco, California, 94105, USA.
*
*/
#include <avr/io.h>
#include <avr/interrupt.h>
#define RESOLUTION 65536 // Timer5 is 16 bit
class TimerFive
{
public:
// properties
unsigned int pwmPeriod;
unsigned char clockSelectBits;
// methods
void initialize(long microseconds=1000000);
void start();
void stop();
void restart();
void pwm(char pin, int duty, long microseconds=-1);
void disablePwm(char pin);
void attachInterrupt(void (*isr)(), long microseconds=-1);
void detachInterrupt();
void setPeriod(long microseconds);
void setPwmDuty(char pin, int duty);
void (*isrCallback)();
};
extern TimerFive Timer5;

View File

@ -281,10 +281,12 @@
configuration.az_stepper_motor_last_direction, configuration.az_stepper_motor_last_pin_state, configuration.el_stepper_motor_last_direction, configuration.el_stepper_motor_last_pin_state
OPTION_HAMLIB_EASYCOM_NO_TERMINATOR_CHARACTER_HACK ; HARDWARE_WB6KCN
FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
*/
#define CODE_VERSION "2.0.2014112502"
#define CODE_VERSION "2.0.2014120201"
#include <avr/pgmspace.h>
#include <EEPROM.h>
@ -302,6 +304,7 @@
#endif
#include "rotator_dependencies.h"
#ifdef FEATURE_4_BIT_LCD_DISPLAY
#include <LiquidCrystal.h> // required for classic 4 bit interface LCD display (FEATURE_4_BIT_LCD_DISPLAY)
#endif // FEATURE_4_BIT_LCD_DISPLAY
@ -356,6 +359,7 @@
#include "Ethernet.h"
#endif
#include "rotator.h"
#ifdef HARDWARE_EA4TX_ARS_USB
#include "rotator_pins_ea4tx_ars_usb.h"
@ -374,6 +378,9 @@
#else
#include "rotator_settings.h"
#endif
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
#include "TimerFive.h"
#endif
@ -692,22 +699,15 @@ unsigned int ethernet_slave_reconnects = 0;
unsigned long last_activity_time = 0;
#endif //FEATURE_POWER_SWITCH
#ifdef FEATURE_STEPPER_MOTOR
//byte az_stepper_motor_last_direction = STEPPER_UNDEF;
//byte az_stepper_motor_last_pin_state = LOW;
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
unsigned long az_stepper_pulse_period_us = 0;
unsigned long az_stepper_pulses_remaining = 0;
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
unsigned int az_stepper_freq_count = 0;
#ifdef FEATURE_ELEVATION_CONTROL
unsigned long el_stepper_pulse_period_us = 0;
unsigned long el_stepper_pulses_remaining = 0;
unsigned int el_stepper_freq_count = 0;
#endif //FEATURE_ELEVATION_CONTROL
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#ifdef FEATURE_ELEVATION_CONTROL
//byte el_stepper_motor_last_direction = STEPPER_UNDEF;
//byte el_stepper_motor_last_pin_state = LOW;
#endif //FEATURE_ELEVATION_CONTROL
#endif //FEATURE_STEPPER_MOTOR
unsigned long service_stepper_motor_pulse_pins_count = 0;
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
#if defined(FEATURE_STEPPER_MOTOR) && defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE)
byte az_stepper_freq_pin = 0;
@ -2468,6 +2468,9 @@ void check_buttons(){
debug_println("check_buttons: moon tracking on");
#endif // DEBUG_BUTTONS
moon_tracking_active = 1;
#ifdef FEATURE_SUN_TRACKING
sun_tracking_active = 0;
#endif // FEATURE_SUN_TRACKING
} else {
#ifdef DEBUG_BUTTONS
debug_println("check_buttons: moon tracking off");
@ -2497,6 +2500,9 @@ void check_buttons(){
debug_println("check_buttons: sun tracking on");
#endif // DEBUG_BUTTONS
sun_tracking_active = 1;
#ifdef FEATURE_MOON_TRACKING
moon_tracking_active = 0;
#endif // FEATURE_MOON_TRACKING
} else {
#ifdef DEBUG_BUTTONS
debug_print("check_buttons: sun tracking off");
@ -4796,7 +4802,12 @@ void output_debug(){
debug_println("");
#endif //FEATURE_GPS
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
//debug_print("service_stepper_motor_pulse_pins_count: ");
//char service_stepper_motor_pulse_pins_count_temp[12];
//dtostrf(service_stepper_motor_pulse_pins_count,0,0,service_stepper_motor_pulse_pins_count_temp);
//debug_println(service_stepper_motor_pulse_pins_count_temp);
#endif FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
debug_println("\n\n\n");
@ -4804,10 +4815,12 @@ void output_debug(){
last_debug_output_time = millis();
#endif //DEBUG_DUMP
}
#endif // defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
#endif //DEBUG_DUMP
} /* output_debug */
@ -4872,6 +4885,8 @@ void output_debug(){
// --------------------------------------------------------------
void print_to_port(char * print_this,byte port){
#if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
switch(port){
case CONTROL_PORT0: control_port->println(print_this);break;
#ifdef FEATURE_ETHERNET
@ -4881,6 +4896,8 @@ void print_to_port(char * print_this,byte port){
#endif //ETHERNET_TCP_PORT_1
#endif //FEATURE_ETHERNET
}
#endif //defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
}
@ -5368,7 +5385,7 @@ void update_el_variable_outputs(byte speed_voltage){
#endif // DEBUG_VARIABLE_OUTPUTS
el_tone = map(speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH);
#ifndef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#if !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE) && !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2)
if ((el_tone < 31) && (el_tone != 0)) {el_tone = 31;}
if (el_tone > 20000) {el_tone = 20000;}
if (el_tone > 0) {
@ -5376,11 +5393,17 @@ void update_el_variable_outputs(byte speed_voltage){
} else {
noTone(el_stepper_motor_pulse);
}
#endif
//zzzzzzzz
#else //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
set_el_stepper_freq(el_stepper_motor_pulse,el_tone);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
set_el_stepper_freq(el_tone);
#endif
@ -5491,7 +5514,7 @@ void update_az_variable_outputs(byte speed_voltage){
#endif // DEBUG_VARIABLE_OUTPUTS
az_tone = map(speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH);
#ifndef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#if !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE) && !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2)
if ((az_tone < 31) && (az_tone != 0)) {az_tone = 31;}
if (az_tone > 20000) {az_tone = 20000;}
if (az_tone > 0) {
@ -5499,10 +5522,16 @@ void update_az_variable_outputs(byte speed_voltage){
} else {
noTone(az_stepper_motor_pulse);
}
#else //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#endif
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
set_az_stepper_freq(az_stepper_motor_pulse,az_tone);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
set_az_stepper_freq(az_tone);
#endif
#ifdef DEBUG_VARIABLE_OUTPUTS
@ -5570,11 +5599,24 @@ void rotator(byte rotation_action, byte rotation_type) {
}
if (rotate_ccw_freq) {
noTone(rotate_ccw_freq);
}
}
#ifdef FEATURE_STEPPER_MOTOR
if (az_stepper_motor_pulse) {
#if !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE) && !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2)
noTone(az_stepper_motor_pulse);
digitalWriteEnhanced(az_stepper_motor_pulse, LOW);
}
digitalWriteEnhanced(az_stepper_motor_pulse,LOW);
#endif
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
set_az_stepper_freq(az_stepper_motor_pulse,0);
digitalWriteEnhanced(az_stepper_motor_pulse,LOW);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
set_az_stepper_freq(0);
digitalWriteEnhanced(az_stepper_motor_pulse,LOW);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
}
#endif //FEATURE_STEPPER_MOTOR
} else {
if (rotate_cw_pwm) {
analogWriteEnhanced(rotate_cw_pwm, normal_az_speed_voltage);
@ -5590,10 +5632,20 @@ void rotator(byte rotation_action, byte rotation_type) {
}
if (rotate_ccw_freq) {
noTone(rotate_ccw_freq);
}
}
#ifdef FEATURE_STEPPER_MOTOR
if (az_stepper_motor_pulse) {
#if !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE) && !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2)
tone(az_stepper_motor_pulse, map(normal_az_speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH));
}
#endif
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
set_az_stepper_freq(az_stepper_motor_pulse,map(normal_az_speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH));
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
set_az_stepper_freq(map(normal_az_speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH));
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
}
#endif //FEATURE_STEPPER_MOTOR
}
if (rotate_cw) {
digitalWriteEnhanced(rotate_cw, ROTATE_PIN_ACTIVE_VALUE);
@ -5647,12 +5699,23 @@ void rotator(byte rotation_action, byte rotation_type) {
if (rotate_cw_freq) {
noTone(rotate_cw_freq);
}
#ifdef FEATURE_STEPPER_MOTOR
if (az_stepper_motor_pulse) {
#if !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE) && !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2)
noTone(az_stepper_motor_pulse);
digitalWriteEnhanced(az_stepper_motor_pulse, HIGH);
}
#endif //FEATURE_STEPPER_MOTOR
digitalWriteEnhanced(az_stepper_motor_pulse,HIGH);
#endif
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
set_az_stepper_freq(az_stepper_motor_pulse,0);
digitalWriteEnhanced(az_stepper_motor_pulse,HIGH);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
set_az_stepper_freq(0);
digitalWriteEnhanced(az_stepper_motor_pulse,HIGH);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
}
#endif //FEATURE_STEPPER_MOTOR
}
break;
case CCW:
@ -5683,13 +5746,23 @@ void rotator(byte rotation_action, byte rotation_type) {
}
if (rotate_ccw_freq) {
noTone(rotate_ccw_freq);
}
}
#ifdef FEATURE_STEPPER_MOTOR
if (az_stepper_motor_pulse) {
#if !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE) && !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2)
noTone(az_stepper_motor_pulse);
digitalWriteEnhanced(az_stepper_motor_pulse, LOW);
}
#endif //FEATURE_STEPPER_MOTOR
digitalWriteEnhanced(az_stepper_motor_pulse,LOW);
#endif
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
set_az_stepper_freq(az_stepper_motor_pulse,0);
digitalWriteEnhanced(az_stepper_motor_pulse,LOW);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
set_az_stepper_freq(0);
digitalWriteEnhanced(az_stepper_motor_pulse,LOW);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
}
#endif //FEATURE_STEPPER_MOTOR
} else {
if (rotate_cw_pwm) {
analogWriteEnhanced(rotate_cw_pwm, 0); digitalWriteEnhanced(rotate_cw_pwm, LOW);
@ -5705,12 +5778,20 @@ void rotator(byte rotation_action, byte rotation_type) {
}
if (rotate_ccw_freq) {
tone(rotate_ccw_freq, map(normal_az_speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH));
}
}
#ifdef FEATURE_STEPPER_MOTOR
if (az_stepper_motor_pulse) {
#if !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE) && !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2)
tone(az_stepper_motor_pulse, map(normal_az_speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH));
}
#endif //FEATURE_STEPPER_MOTOR
#endif
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
set_az_stepper_freq(az_stepper_motor_pulse,map(normal_az_speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH));
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
set_az_stepper_freq(map(normal_az_speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH));
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
}
#endif //FEATURE_STEPPER_MOTOR
}
if (rotate_cw) {
digitalWriteEnhanced(rotate_cw, ROTATE_PIN_INACTIVE_VALUE);
@ -5796,14 +5877,18 @@ void rotator(byte rotation_action, byte rotation_type) {
}
#ifdef FEATURE_STEPPER_MOTOR
if (el_stepper_motor_pulse) {
#ifndef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#if !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE) && !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2)
noTone(el_stepper_motor_pulse);
digitalWriteEnhanced(el_stepper_motor_pulse,LOW);
#else //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#endif
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
set_el_stepper_freq(el_stepper_motor_pulse,0);
digitalWriteEnhanced(el_stepper_motor_pulse,LOW);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
set_el_stepper_freq(0);
digitalWriteEnhanced(el_stepper_motor_pulse,LOW);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
}
#endif //FEATURE_STEPPER_MOTOR
} else {
@ -5821,12 +5906,15 @@ void rotator(byte rotation_action, byte rotation_type) {
}
#ifdef FEATURE_STEPPER_MOTOR
if (el_stepper_motor_pulse) {
#ifndef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#if !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE) && !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2)
tone(el_stepper_motor_pulse, map(normal_el_speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH));
#else //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#endif
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
set_el_stepper_freq(el_stepper_motor_pulse,map(normal_el_speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH));
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
set_el_stepper_freq(map(normal_el_speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH));
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
}
#endif //FEATURE_STEPPER_MOTOR
if (rotate_down_freq) {
@ -5880,13 +5968,18 @@ void rotator(byte rotation_action, byte rotation_type) {
}
#ifdef FEATURE_STEPPER_MOTOR
if (el_stepper_motor_pulse) {
#ifndef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#if !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE) && !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2)
noTone(el_stepper_motor_pulse);
digitalWriteEnhanced(el_stepper_motor_pulse,HIGH);
#else //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#endif
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
set_el_stepper_freq(el_stepper_motor_pulse,0);
digitalWriteEnhanced(el_stepper_motor_pulse,HIGH);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
set_el_stepper_freq(0);
digitalWriteEnhanced(el_stepper_motor_pulse,HIGH);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
}
#endif //FEATURE_STEPPER_MOTOR
@ -5924,13 +6017,18 @@ void rotator(byte rotation_action, byte rotation_type) {
}
#ifdef FEATURE_STEPPER_MOTOR
if (el_stepper_motor_pulse) {
#ifndef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#if !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE) && !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2)
noTone(el_stepper_motor_pulse);
digitalWriteEnhanced(el_stepper_motor_pulse,LOW);
#else //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#endif
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
set_el_stepper_freq(el_stepper_motor_pulse,0);
digitalWriteEnhanced(el_stepper_motor_pulse,LOW);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
set_el_stepper_freq(0);
digitalWriteEnhanced(el_stepper_motor_pulse,LOW);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
}
#endif //FEATURE_STEPPER_MOTOR
} else {
@ -5951,13 +6049,18 @@ void rotator(byte rotation_action, byte rotation_type) {
}
#ifdef FEATURE_STEPPER_MOTOR
if (el_stepper_motor_pulse) {
#ifndef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#if !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE) && !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2)
tone(el_stepper_motor_pulse, map(normal_el_speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH));
digitalWriteEnhanced(el_stepper_motor_pulse,LOW);
#else //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#endif
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
set_el_stepper_freq(el_stepper_motor_pulse,map(normal_el_speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH));
digitalWriteEnhanced(el_stepper_motor_pulse,LOW);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
set_el_stepper_freq(map(normal_el_speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH));
digitalWriteEnhanced(el_stepper_motor_pulse,LOW);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
}
#endif //FEATURE_STEPPER_MOTOR
}
@ -6008,13 +6111,18 @@ void rotator(byte rotation_action, byte rotation_type) {
}
#ifdef FEATURE_STEPPER_MOTOR
if (el_stepper_motor_pulse) {
#ifndef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#if !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE) && !defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2)
noTone(el_stepper_motor_pulse);
digitalWriteEnhanced(el_stepper_motor_pulse,HIGH);
#else //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#endif
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
set_el_stepper_freq(el_stepper_motor_pulse,0);
digitalWriteEnhanced(el_stepper_motor_pulse,HIGH);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
set_el_stepper_freq(0);
digitalWriteEnhanced(el_stepper_motor_pulse,HIGH);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
}
#endif //FEATURE_STEPPER_MOTOR
}
@ -6041,6 +6149,11 @@ void initialize_interrupts(){
attachInterrupt(EL_POSITION_PULSE_PIN_INTERRUPT, el_position_pulse_interrupt_handler, FALLING);
#endif // FEATURE_EL_POSITION_PULSE_INPUT
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
Timer5.initialize(250); // 250 us = 4 khz rate
Timer5.attachInterrupt(service_stepper_motor_pulse_pins);
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
}
@ -6332,6 +6445,7 @@ void initialize_pins(){
#endif //FEATURE_ANALOG_OUTPUT_PINS
} /* initialize_pins */
// --------------------------------------------------------------
@ -6820,7 +6934,7 @@ void service_rotation(){
#ifdef FEATURE_ELEVATION_CONTROL
#ifdef FEATURE_ELEVATION_CONTROL
if (el_state == INITIALIZE_NORMAL_UP) {
update_el_variable_outputs(normal_el_speed_voltage);
rotator(ACTIVATE, UP);
@ -7027,9 +7141,12 @@ void service_rotation(){
// check rotation target --------------------------------------------------------------------------------------------------------
if ((el_state != IDLE) && (el_request_queue_state == IN_PROGRESS_TO_TARGET) ) {
read_elevation(0);
if ((el_state == NORMAL_UP) || (el_state == SLOW_START_UP) || (el_state == SLOW_DOWN_UP)) {
if ((abs(elevation - target_elevation) < (ELEVATION_TOLERANCE * HEADING_MULTIPLIER)) || ((elevation > target_elevation) && ((elevation - target_elevation) < ((ELEVATION_TOLERANCE + 5) * HEADING_MULTIPLIER)))) {
#ifndef OPTION_NO_ELEVATION_CHECK_TARGET_DELAY
delay(50);
#endif //OPTION_NO_ELEVATION_CHECK_TARGET_DELAY
read_elevation(0);
if ((abs(elevation - target_elevation) < (ELEVATION_TOLERANCE * HEADING_MULTIPLIER)) || ((elevation > target_elevation) && ((elevation - target_elevation) < ((ELEVATION_TOLERANCE + 5) * HEADING_MULTIPLIER)))) {
rotator(DEACTIVATE, UP);
@ -7039,7 +7156,10 @@ void service_rotation(){
#ifdef DEBUG_SERVICE_ROTATION
debug_print("service_rotation: IDLE");
#endif // DEBUG_SERVICE_ROTATION
/*control_port->println(abs(elevation - target_elevation));
read_elevation(0);
control_port->println(abs(elevation - target_elevation));
control_port->println();*/
#if defined(FEATURE_PARK)
if ((park_status == PARK_INITIATED) && (az_state == IDLE)) {
park_status = PARKED;
@ -7049,10 +7169,13 @@ void service_rotation(){
}
}
} else {
if ((abs(elevation - target_elevation) < (ELEVATION_TOLERANCE * HEADING_MULTIPLIER)) || ((elevation < target_elevation) && ((target_elevation - elevation) < ((ELEVATION_TOLERANCE + 5) * HEADING_MULTIPLIER)))) {
read_elevation(0);
if ((abs(elevation - target_elevation) <= (ELEVATION_TOLERANCE * HEADING_MULTIPLIER)) || ((elevation < target_elevation) && ((target_elevation - elevation) < ((ELEVATION_TOLERANCE + 5) * HEADING_MULTIPLIER)))) {
#ifndef OPTION_NO_ELEVATION_CHECK_TARGET_DELAY
delay(50);
#endif //OPTION_NO_ELEVATION_CHECK_TARGET_DELAY
read_elevation(0);
if ((abs(elevation - target_elevation) < (ELEVATION_TOLERANCE * HEADING_MULTIPLIER)) || ((elevation < target_elevation) && ((target_elevation - elevation) < ((ELEVATION_TOLERANCE + 5) * HEADING_MULTIPLIER)))) {
if ((abs(elevation - target_elevation) <= (ELEVATION_TOLERANCE * HEADING_MULTIPLIER)) || ((elevation < target_elevation) && ((target_elevation - elevation) < ((ELEVATION_TOLERANCE + 5) * HEADING_MULTIPLIER)))) {
rotator(DEACTIVATE, UP);
rotator(DEACTIVATE, DOWN);
el_state = IDLE;
@ -7060,7 +7183,10 @@ void service_rotation(){
#ifdef DEBUG_SERVICE_ROTATION
debug_print("service_rotation: IDLE");
#endif // DEBUG_SERVICE_ROTATION
/*control_port->println(abs(elevation - target_elevation));
read_elevation(0);
control_port->println(abs(elevation - target_elevation));
control_port->println();*/
#if defined(FEATURE_PARK)
if ((park_status == PARK_INITIATED) && (az_state == IDLE)) {
park_status = PARKED;
@ -9680,9 +9806,9 @@ byte process_backslash_command(byte input_buffer[], int input_buffer_index, byte
case '1':
sun_tracking_active = 1;
strcpy(return_string, "Sun tracking activated.");
#ifdef FEATURE_MOON_TRACKING
#ifdef FEATURE_MOON_TRACKING
moon_tracking_active = 0;
#endif // FEATURE_MOON_TRACKING
#endif // FEATURE_MOON_TRACKING
break;
default: strcpy(return_string, "Error."); break;
}
@ -9868,9 +9994,12 @@ char * az_el_calibrated_string(){
// --------------------------------------------------------------
void debug_print(char * print_string){
#if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
if (debug_mode & CONTROL_PORT0){
control_port->print(print_string);
}
#endif //defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
#ifdef FEATURE_ETHERNET
if (debug_mode & ETHERNET_PORT0){
@ -9888,9 +10017,11 @@ void debug_print(char * print_string){
// --------------------------------------------------------------
void debug_println(char * print_string){
#if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
if (debug_mode & CONTROL_PORT0){
control_port->println(print_string);
}
#endif //defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
#ifdef FEATURE_ETHERNET
if (debug_mode & ETHERNET_PORT0){
@ -9908,9 +10039,11 @@ void debug_println(char * print_string){
// --------------------------------------------------------------
void debug_print_char(char print_char){
#if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
if (debug_mode & CONTROL_PORT0){
control_port->print(print_char);
}
#endif //defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
#ifdef FEATURE_ETHERNET
if (debug_mode & ETHERNET_PORT0){
@ -9927,9 +10060,11 @@ void debug_print_char(char print_char){
// --------------------------------------------------------------
void debug_write(char * print_string){
#if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
if (debug_mode & CONTROL_PORT0){
control_port->write(print_string);
}
#endif //defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
#ifdef FEATURE_ETHERNET
if (debug_mode & ETHERNET_PORT0){
@ -9947,9 +10082,11 @@ void debug_write(char * print_string){
// --------------------------------------------------------------
void debug_print_int(int print_int){
#if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
if (debug_mode & CONTROL_PORT0){
control_port->print(print_int);
}
#endif //defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
#ifdef FEATURE_ETHERNET
if (debug_mode & ETHERNET_PORT0){
@ -9968,9 +10105,11 @@ void debug_print_int(int print_int){
// --------------------------------------------------------------
void debug_write_int(int write_int){
#if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
if (debug_mode & CONTROL_PORT0){
control_port->write(write_int);
}
#endif //defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
#ifdef FEATURE_ETHERNET
if (debug_mode & ETHERNET_PORT0){
@ -9992,9 +10131,11 @@ void debug_print_float(float print_float,byte places){
dtostrf(print_float,0,places,tempstring);
#if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
if (debug_mode & CONTROL_PORT0){
control_port->print(tempstring);
}
#endif //defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
#ifdef FEATURE_ETHERNET
if (debug_mode & ETHERNET_PORT0){
@ -11420,7 +11561,8 @@ void process_remote_slave_command(byte * slave_command_buffer, int slave_command
// --------------------------------------------------------------
void port_flush(){
#ifdef CONTROL_PORT_MAPPED_TO
#if defined(CONTROL_PORT_MAPPED_TO) && (defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION))
control_port->flush();
#endif //CONTROL_PORT_MAPPED_TO
@ -11571,10 +11713,109 @@ void set_el_stepper_freq(byte pin, unsigned int frequency){
}
#endif //defined(FEATURE_ELEVATION_CONTROL) && defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE) && defined(FEATURE_STEPPER_MOTOR)
//------------------------------------------------------FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
#if defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2) && defined(FEATURE_STEPPER_MOTOR)
void service_stepper_motor_pulse_pins(){
service_stepper_motor_pulse_pins_count++;
static unsigned int az_stepper_pin_transition_counter = 0;
static byte az_stepper_pin_last_state = LOW;
if (az_stepper_freq_count > 0){
az_stepper_pin_transition_counter++;
if (az_stepper_pin_transition_counter >= az_stepper_freq_count){
if (az_stepper_pin_last_state == LOW){
digitalWrite(az_stepper_motor_pulse,HIGH);
az_stepper_pin_last_state = HIGH;
} else {
digitalWrite(az_stepper_motor_pulse,LOW);
az_stepper_pin_last_state = LOW;
}
az_stepper_pin_transition_counter = 0;
}
} else {
az_stepper_pin_transition_counter = 0;
}
#ifdef FEATURE_ELEVATION_CONTROL
static unsigned int el_stepper_pin_transition_counter = 0;
static byte el_stepper_pin_last_state = LOW;
if (el_stepper_freq_count > 0){
el_stepper_pin_transition_counter++;
if (el_stepper_pin_transition_counter >= el_stepper_freq_count){
if (el_stepper_pin_last_state == LOW){
digitalWrite(el_stepper_motor_pulse,HIGH);
el_stepper_pin_last_state = HIGH;
} else {
digitalWrite(el_stepper_motor_pulse,LOW);
el_stepper_pin_last_state = LOW;
}
el_stepper_pin_transition_counter = 0;
}
} else {
el_stepper_pin_transition_counter = 0;
}
#endif //FEATURE_ELEVATION_CONTROL
}
#endif //defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2) && defined(FEATURE_STEPPER_MOTOR)
//------------------------------------------------------FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
void set_az_stepper_freq(unsigned int frequency){
if (frequency > 0) {
az_stepper_freq_count = 2000 / frequency;
} else {
az_stepper_freq_count = 0;
}
#ifdef DEBUG_STEPPER
debug_print("set_az_stepper_freq: ");
debug_print_int(frequency);
debug_print(" az_stepper_freq_count:");
debug_print_int(el_stepper_freq_count);
debug_println("");
#endif //DEBUG_STEPPER
}
#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
//------------------------------------------------------FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2
#if defined(FEATURE_ELEVATION_CONTROL) && defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2) && defined(FEATURE_STEPPER_MOTOR)
void set_el_stepper_freq(unsigned int frequency){
if (frequency > 0) {
el_stepper_freq_count = 2000 / frequency;
} else {
el_stepper_freq_count = 0;
}
#ifdef DEBUG_STEPPER
debug_print("set_el_stepper_freq: ");
debug_print_int(frequency);
debug_print(" el_stepper_freq_count:");
debug_print_int(el_stepper_freq_count);
debug_println("");
#endif //DEBUG_STEPPER
}
#endif //defined(FEATURE_ELEVATION_CONTROL) && defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2) && defined(FEATURE_STEPPER_MOTOR)
//------------------------------------------------------
#if defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE) && defined(FEATURE_STEPPER_MOTOR)
void service_stepper_motor_pulse_pins(){
static byte az_stepper_freq_pin_active = 0;
static unsigned long az_stepper_freq_pin_next_transition = 0;
static byte az_stepper_freq_pin_last_state = 0;

View File

@ -1,6 +1,9 @@
/* ---------------------- dependency checking - don't touch this unless you know what you are doing ---------------------*/
#if defined(FEATURE_YAESU_EMULATION) && defined(FEATURE_EASYCOM_EMULATION)
#error "You can't activate both FEATURE_YAESU_EMULATION and FEATURE_EASYCOM_EMULATION!"
#endif
#if (defined(FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT) || defined(FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT)) && (!defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) && !defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE))
#error "You must activate FEATURE_MASTER_WITH_SERIAL_SLAVE or FEATURE_MASTER_WITH_ETHERNET_SLAVE when using FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT or FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT"

View File

@ -19,6 +19,7 @@
//#define FEATURE_ETHERNET
//#define FEATURE_STEPPER_MOTOR
//#define FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
//#define FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2 // requires this library: https://code.google.com/p/rogue-code/wiki/ToneLibraryDocumentation
#define LANGUAGE_ENGLISH
//#define LANGUAGE_SPANISH
@ -45,7 +46,7 @@
//#define FEATURE_AZ_POSITION_HH12_AS5045_SSI
//#define FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
//#define FEATURE_EL_POSITION_POTENTIOMETER
#define FEATURE_EL_POSITION_POTENTIOMETER
//#define FEATURE_EL_POSITION_ROTARY_ENCODER
//#define FEATURE_EL_POSITION_PULSE_INPUT
//#define FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB // Uncomment for elevation ADXL345 accelerometer support using ADXL345 library
@ -114,10 +115,10 @@
//#define OPTION_DISPLAY_BIG_CLOCK // display date & time clock (set row with #define LCD_BIG_CLOCK_ROW)
//#define OPTION_CLOCK_ALWAYS_HAVE_HOUR_LEADING_ZERO
#define OPTION_DISPLAY_GPS_INDICATOR // display GPS indicator on LCD - set position with LCD_GPS_INDICATOR_POSITION and LCD_GPS_INDICATOR_ROW
#define OPTION_DISPLAY_MOON_TRACKING_CONTINUOUSLY
//#define OPTION_DISPLAY_MOON_TRACKING_CONTINUOUSLY
//#define OPTION_DISPLAY_DIRECTION_STATUS // N, W, E, S, NW, etc. direction indicator in row 1 center
#define OPTION_DISPLAY_SUN_TRACKING_CONTINUOUSLY
//#define OPTION_DISPLAY_MOON_OR_SUN_TRACKING_CONDITIONAL
//#define OPTION_DISPLAY_SUN_TRACKING_CONTINUOUSLY
#define OPTION_DISPLAY_MOON_OR_SUN_TRACKING_CONDITIONAL
//#define OPTION_DISPLAY_VERSION_ON_STARTUP //code provided by Paolo, IT9IPQ
//#define FEATURE_POWER_SWITCH
//#define OPTION_EXTERNAL_ANALOG_REFERENCE //Activate external analog voltage reference (needed for RemoteQTH.com unit)
@ -125,6 +126,7 @@
//#define OPTION_DISABLE_HMC5883L_ERROR_CHECKING
//#define OPTION_HAMLIB_EASYCOM_AZ_EL_COMMAND_HACK
//#define OPTION_HAMLIB_EASYCOM_NO_TERMINATOR_CHARACTER_HACK
//#define OPTION_NO_ELEVATION_CHECK_TARGET_DELAY
@ -142,9 +144,9 @@
#define DEFAULT_DEBUG_STATE 0// this should be set to zero unless you're debugging something at startup
#define DEFAULT_DEBUG_STATE 0 // 1 = activate debug mode at startup; this should be set to zero unless you're debugging something at startup
#define DEBUG_DUMP
#define DEBUG_DUMP // normally compile with this activated unless you're really trying to save memory
// #define DEBUG_MEMORY
// #define DEBUG_BUTTONS
// #define DEBUG_SERIAL
@ -192,6 +194,7 @@
// #define DEBUG_SYNC_MASTER_CLOCK_TO_SLAVE
// #define DEBUG_HMC5883L
// #define DEBUG_POLOLU_LSM303_CALIBRATION
// #define DEBUG_STEPPER

View File

@ -18,7 +18,8 @@
//#define FEATURE_RTC_PCF8583
//#define FEATURE_ETHERNET
#define FEATURE_STEPPER_MOTOR
#define FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
//#define FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#define FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE_2 // requires this library: https://code.google.com/p/rogue-code/wiki/ToneLibraryDocumentation
#define LANGUAGE_ENGLISH
//#define LANGUAGE_SPANISH
@ -124,6 +125,7 @@
//#define OPTION_DISABLE_HMC5883L_ERROR_CHECKING
#define OPTION_HAMLIB_EASYCOM_AZ_EL_COMMAND_HACK
//#define OPTION_HAMLIB_EASYCOM_NO_TERMINATOR_CHARACTER_HACK
#define OPTION_NO_ELEVATION_CHECK_TARGET_DELAY
@ -192,6 +194,7 @@
// #define DEBUG_SYNC_MASTER_CLOCK_TO_SLAVE
// #define DEBUG_HMC5883L
// #define DEBUG_POLOLU_LSM303_CALIBRATION
// #define DEBUG_STEPPER

View File

@ -6,4 +6,4 @@
//#define HARDWARE_M0UPU
//#define HARDWARE_EA4TX_ARS_USB // if using EA4TX ARS USB hardware, customize rotator_features_e4tx_ars_usb.h (not rotator_features.h)
#define HARDWARE_WB6KCN
//#define HARDWARE_WB6KCN // customize rotator_features_wb6kcn.h, rotators_pins_wb6kcn.h, rotator_settings_wb6kcn.h

View File

@ -164,7 +164,7 @@
#ifdef FEATURE_SUN_TRACKING
#define sun_tracking_active_pin 0 // goes high when sun tracking is active
#define sun_tracking_activate_line 0 // ground this pin to activate sun tracking (not for use with a button)
#define sun_tracking_button 0 // use with a normally open momentary switch to ground
#define sun_tracking_button 0 // use with a normally open momentary switch to ground
#endif //FEATURE_SUN_TRACKING
#ifdef FEATURE_GPS

View File

@ -186,4 +186,4 @@
#endif //FEATURE_ANALOG_OUTPUT_PINS

View File

@ -99,9 +99,9 @@ You can tweak these, but read the online documentation!
#define GPS_PORT_BAUD_RATE 9600
#define GPS_MIRROR_PORT_BAUD_RATE 9600
#define CONTROL_PORT_MAPPED_TO &Serial // change this line to map the control port to a different serial port (Serial1, Serial2, etc.)
#define REMOTE_PORT_MAPPED_TO &Serial1 // change this line to map the remote_unit port to a different serial port
//#define REMOTE_PORT_MAPPED_TO &Serial1 // change this line to map the remote_unit port to a different serial port
#define GPS_PORT_MAPPED_TO &Serial2 // change this line to map the GPS port to a different serial port
//#define GPS_MIRROR_PORT &Serial3 // use this to mirror output from a GPS unit into the Arduino out another port (uncomment to enable)
#define GPS_MIRROR_PORT &Serial1 //3 // use this to mirror output from a GPS unit into the Arduino out another port (uncomment to enable)
#define LCD_COLUMNS 20 //16
#define LCD_ROWS 4 //2

View File

@ -536,3 +536,5 @@ PCF8583 rtc(0xA0);
#define LCD_ROWS 2
#endif //HARDWARE_EA4TX_ARS_USB