version 2.0 commit

This commit is contained in:
Anthony Good 2014-07-02 17:49:28 -04:00
parent 49570a21d4
commit f8318b4f27
26 changed files with 13234 additions and 4634 deletions

143
HMC5883L.cpp Executable file
View File

@ -0,0 +1,143 @@
/*
HMC5883L.cpp - Class file for the HMC5883L Triple Axis Magnetometer Arduino Library.
Copyright (C) 2011 Love Electronics (loveelectronics.co.uk)/ 2012 bildr.org (Arduino 1.0 compatible)
This program is free software: you can redistribute it and/or modify
it under the terms of the version 3 GNU General Public License as
published by the Free Software Foundation.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
WARNING: THE HMC5883L IS NOT IDENTICAL TO THE HMC5883!
Datasheet for HMC5883L:
http://www51.honeywell.com/aero/common/documents/myaerospacecatalog-documents/Defense_Brochures-documents/HMC5883L_3-Axis_Digital_Compass_IC.pdf
*/
#include <Arduino.h>
#include "HMC5883L.h"
HMC5883L::HMC5883L()
{
m_Scale = 1;
}
MagnetometerRaw HMC5883L::ReadRawAxis()
{
uint8_t* buffer = Read(DataRegisterBegin, 6);
MagnetometerRaw raw = MagnetometerRaw();
raw.XAxis = (buffer[0] << 8) | buffer[1];
raw.ZAxis = (buffer[2] << 8) | buffer[3];
raw.YAxis = (buffer[4] << 8) | buffer[5];
return raw;
}
MagnetometerScaled HMC5883L::ReadScaledAxis()
{
MagnetometerRaw raw = ReadRawAxis();
MagnetometerScaled scaled = MagnetometerScaled();
scaled.XAxis = raw.XAxis * m_Scale;
scaled.ZAxis = raw.ZAxis * m_Scale;
scaled.YAxis = raw.YAxis * m_Scale;
return scaled;
}
int HMC5883L::SetScale(float gauss)
{
uint8_t regValue = 0x00;
if(gauss == 0.88)
{
regValue = 0x00;
m_Scale = 0.73;
}
else if(gauss == 1.3)
{
regValue = 0x01;
m_Scale = 0.92;
}
else if(gauss == 1.9)
{
regValue = 0x02;
m_Scale = 1.22;
}
else if(gauss == 2.5)
{
regValue = 0x03;
m_Scale = 1.52;
}
else if(gauss == 4.0)
{
regValue = 0x04;
m_Scale = 2.27;
}
else if(gauss == 4.7)
{
regValue = 0x05;
m_Scale = 2.56;
}
else if(gauss == 5.6)
{
regValue = 0x06;
m_Scale = 3.03;
}
else if(gauss == 8.1)
{
regValue = 0x07;
m_Scale = 4.35;
}
else
return ErrorCode_1_Num;
// Setting is in the top 3 bits of the register.
regValue = regValue << 5;
Write(ConfigurationRegisterB, regValue);
}
int HMC5883L::SetMeasurementMode(uint8_t mode)
{
Write(ModeRegister, mode);
}
void HMC5883L::Write(int address, int data)
{
Wire.beginTransmission(HMC5883L_Address);
Wire.write(address);
Wire.write(data);
Wire.endTransmission();
}
uint8_t* HMC5883L::Read(int address, int length)
{
Wire.beginTransmission(HMC5883L_Address);
Wire.write(address);
Wire.endTransmission();
Wire.beginTransmission(HMC5883L_Address);
Wire.requestFrom(HMC5883L_Address, length);
uint8_t buffer[length];
if(Wire.available() == length)
{
for(uint8_t i = 0; i < length; i++)
{
buffer[i] = Wire.read();
}
}
Wire.endTransmission();
return buffer;
}
char* HMC5883L::GetErrorText(int errorCode)
{
if(ErrorCode_1_Num == 1)
return ErrorCode_1;
return "Error not defined.";
}

78
HMC5883L.h Executable file
View File

@ -0,0 +1,78 @@
/*
HMC5883L.h - Header file for the HMC5883L Triple Axis Magnetometer Arduino Library.
Copyright (C) 2011 Love Electronics (loveelectronics.co.uk) / 2012 bildr.org (Arduino 1.0 compatible)
This program is free software: you can redistribute it and/or modify
it under the terms of the version 3 GNU General Public License as
published by the Free Software Foundation.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
WARNING: THE HMC5883L IS NOT IDENTICAL TO THE HMC5883!
Datasheet for HMC5883L:
http://www51.honeywell.com/aero/common/documents/myaerospacecatalog-documents/Defense_Brochures-documents/HMC5883L_3-Axis_Digital_Compass_IC.pdf
*/
#ifndef HMC5883L_h
#define HMC5883L_h
#include <Arduino.h>
#include <Wire.h>
#define HMC5883L_Address 0x1E
#define ConfigurationRegisterA 0x00
#define ConfigurationRegisterB 0x01
#define ModeRegister 0x02
#define DataRegisterBegin 0x03
#define Measurement_Continuous 0x00
#define Measurement_SingleShot 0x01
#define Measurement_Idle 0x03
#define ErrorCode_1 "Entered scale was not valid, valid gauss values are: 0.88, 1.3, 1.9, 2.5, 4.0, 4.7, 5.6, 8.1"
#define ErrorCode_1_Num 1
struct MagnetometerScaled
{
float XAxis;
float YAxis;
float ZAxis;
};
struct MagnetometerRaw
{
int XAxis;
int YAxis;
int ZAxis;
};
class HMC5883L
{
public:
HMC5883L();
MagnetometerRaw ReadRawAxis();
MagnetometerScaled ReadScaledAxis();
int SetMeasurementMode(uint8_t mode);
int SetScale(float gauss);
char* GetErrorText(int errorCode);
protected:
void Write(int address, int byte);
uint8_t* Read(int address, int length);
private:
float m_Scale;
};
#endif

184
PCF8583.cpp Executable file
View File

@ -0,0 +1,184 @@
/*
Implements a simple interface to the time function of the PCF8583 RTC chip
Works around the device's limited year storage by keeping the year in the
first two bytes of user accessible storage
Assumes device is attached in the standard location - Analog pins 4 and 5
Device address is the 8 bit address (as in the device datasheet - normally A0)
Copyright (c) 2009, Erik DeBill
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include <Arduino.h>
#include <Wire.h>
#include "PCF8583.h"
namespace {
bool IsLeapYear(int year) {
return !(year % 400) || ((year % 100) && !(year % 4));
}
byte DayOfWeek(const PCF8583 &now) {
static char PROGMEM MonthTable[24] = {0, 3, 3, 6, 1, 4, 6, 2, 5, 0, 3, 5, -1, 2, 3, 6, 1, 4, 6, 2, 5, 0, 3, 5};
byte y = now.year % 100, c = 6 - 2 * ((now.year / 100) % 4);
return (now.day + pgm_read_byte_near(MonthTable + IsLeapYear(now.year) * 12 + now.month - 1) + y + (y / 4) + c) % 7;
}
}
// provide device address as a full 8 bit address (like the datasheet)
PCF8583::PCF8583(int device_address) {
address = device_address >> 1; // convert to 7 bit so Wire doesn't choke
Wire.begin();
}
// initialization
void PCF8583::init()
{
Wire.beginTransmission(address);
Wire.write(0x00);
Wire.write(0x04); // Set alarm on int\ will turn to vcc
Wire.endTransmission();
}
void PCF8583::get_time(){
Wire.beginTransmission(address);
Wire.write(0xC0); // stop counting, don't mask
Wire.endTransmission();
Wire.beginTransmission(address);
Wire.write(0x02);
Wire.endTransmission();
Wire.requestFrom(address, 5);
second = bcd_to_byte(Wire.read());
minute = bcd_to_byte(Wire.read());
hour = bcd_to_byte(Wire.read());
byte incoming = Wire.read(); // year/date counter
day = bcd_to_byte(incoming & 0x3f);
year = (int)((incoming >> 6) & 0x03); // it will only hold 4 years...
incoming = Wire.read();
month = bcd_to_byte(incoming & 0x1f);
dow = incoming >> 5;
// but that's not all - we need to find out what the base year is
// so we can add the 2 bits we got above and find the real year
Wire.beginTransmission(address);
Wire.write(0x10);
Wire.endTransmission();
Wire.requestFrom(address, 2);
year_base = 0;
year_base = Wire.read();
year_base = year_base << 8;
year_base = year_base | Wire.read();
year = year + year_base;
}
void PCF8583::set_time()
{
if (!IsLeapYear(year) && 2 == month && 29 == day) {
month = 3;
day = 1;
}
// Attempt to find the previous leap year
year_base = year - year % 4;
if (!IsLeapYear(year_base)) {
// Not a leap year (new century), make sure the calendar won't use a 29 days February.
year_base = year - 1;
}
dow = DayOfWeek(*this);
Wire.beginTransmission(address);
Wire.write(0xC0); // stop counting, don't mask
Wire.endTransmission();
Wire.beginTransmission(address);
Wire.write(0x02);
Wire.write(int_to_bcd(second));
Wire.write(int_to_bcd(minute));
Wire.write(int_to_bcd(hour));
Wire.write(((byte)(year - year_base) << 6) | int_to_bcd(day));
Wire.write((dow << 5) | (int_to_bcd(month) & 0x1f));
Wire.endTransmission();
Wire.beginTransmission(address);
Wire.write(0x10);
Wire.write(year_base >> 8);
Wire.write(year_base & 0x00ff);
Wire.endTransmission();
init(); // re set the control/status register to 0x04
}
//Get the alarm at 0x09 adress
void PCF8583::get_alarm()
{
Wire.beginTransmission(address);
Wire.write(0x0A); // Set the register pointer to (0x0A)
Wire.endTransmission();
Wire.requestFrom(address, 4); // Read 4 values
alarm_second = bcd_to_byte(Wire.read());
alarm_minute = bcd_to_byte(Wire.read());
alarm_hour = bcd_to_byte(Wire.read());
Wire.beginTransmission(address);
Wire.write(0x0E);
Wire.endTransmission();
Wire.requestFrom(address, 1); // Read weekday value
alarm_day = bcd_to_byte(Wire.read());
}
//Set a daily alarm
void PCF8583::set_daily_alarm()
{
Wire.beginTransmission(address);
Wire.write(0x08);
Wire.write(0x90); // daily alarm set
Wire.endTransmission();
Wire.beginTransmission(address);
Wire.write(0x09); // Set the register pointer to (0x09)
Wire.write(0x00); // Set 00 at milisec
Wire.write(int_to_bcd(alarm_second));
Wire.write(int_to_bcd(alarm_minute));
Wire.write(int_to_bcd(alarm_hour));
Wire.write(0x00); // Set 00 at day
Wire.endTransmission();
}
int PCF8583::bcd_to_byte(byte bcd){
return ((bcd >> 4) * 10) + (bcd & 0x0f);
}
byte PCF8583::int_to_bcd(int in){
return ((in / 10) << 4) + (in % 10);
}

90
PCF8583.h Executable file
View File

@ -0,0 +1,90 @@
/*
Implements a simple interface to the time function of the PCF8583 RTC chip
Works around the device's limited year storage by keeping the year in the
first two bytes of user accessible storage
Assumes device is attached in the standard location - Analog pins 4 and 5
Device address is the 8 bit address (as in the device datasheet - normally A0)
Copyright (c) 2009, Erik DeBill
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
/*
Usage:
PCF8583 pcf(0xA0);
pcf.get_time();
Serial.print("year: ");
Serial.println(pcf.year);
pcf.hour = 14;
pcf.minute = 30
pcf.second = 0
pcf.year = 2009
pcf.month = 9
pcf.day = 12
pcf.set_time();
*/
#ifndef PCF8583_H
#define PCF8583_H
#include <Arduino.h>
#include <../Wire/Wire.h>
class PCF8583 {
int address;
int dow;
public:
int second;
int minute;
int hour;
int day;
int month;
int year;
int year_base;
int alarm_milisec;
int alarm_second;
int alarm_minute;
int alarm_hour;
int alarm_day;
PCF8583(int device_address);
void init ();
void get_time();
void set_time();
void get_alarm();
int get_day_of_week() const {
return dow;
}
void set_daily_alarm();
int bcd_to_byte(byte bcd);
byte int_to_bcd(int in);
};
#endif //PCF8583_H

246
RTClib.cpp Executable file
View File

@ -0,0 +1,246 @@
// Code by JeeLabs http://news.jeelabs.org/code/
// Released to the public domain! Enjoy!
#include <Wire.h>
#include "RTClib.h"
#ifdef __AVR__
#include <avr/pgmspace.h>
#define WIRE Wire
#else
#define PROGMEM
#define pgm_read_byte(addr) (*(const unsigned char *)(addr))
#define WIRE Wire1
#endif
#define DS1307_ADDRESS 0x68
#define SECONDS_PER_DAY 86400L
#define SECONDS_FROM_1970_TO_2000 946684800
#if (ARDUINO >= 100)
#include <Arduino.h> // capital A so it is error prone on case-sensitive filesystems
#else
#include <WProgram.h>
#endif
////////////////////////////////////////////////////////////////////////////////
// utility code, some of this could be exposed in the DateTime API if needed
const uint8_t daysInMonth [] PROGMEM = { 31,28,31,30,31,30,31,31,30,31,30,31 };
// number of days since 2000/01/01, valid for 2001..2099
static uint16_t date2days(uint16_t y, uint8_t m, uint8_t d) {
if (y >= 2000)
y -= 2000;
uint16_t days = d;
for (uint8_t i = 1; i < m; ++i)
days += pgm_read_byte(daysInMonth + i - 1);
if (m > 2 && y % 4 == 0)
++days;
return days + 365 * y + (y + 3) / 4 - 1;
}
static long time2long(uint16_t days, uint8_t h, uint8_t m, uint8_t s) {
return ((days * 24L + h) * 60 + m) * 60 + s;
}
////////////////////////////////////////////////////////////////////////////////
// DateTime implementation - ignores time zones and DST changes
// NOTE: also ignores leap seconds, see http://en.wikipedia.org/wiki/Leap_second
DateTime::DateTime (uint32_t t) {
t -= SECONDS_FROM_1970_TO_2000; // bring to 2000 timestamp from 1970
ss = t % 60;
t /= 60;
mm = t % 60;
t /= 60;
hh = t % 24;
uint16_t days = t / 24;
uint8_t leap;
for (yOff = 0; ; ++yOff) {
leap = yOff % 4 == 0;
if (days < 365 + leap)
break;
days -= 365 + leap;
}
for (m = 1; ; ++m) {
uint8_t daysPerMonth = pgm_read_byte(daysInMonth + m - 1);
if (leap && m == 2)
++daysPerMonth;
if (days < daysPerMonth)
break;
days -= daysPerMonth;
}
d = days + 1;
}
DateTime::DateTime (uint16_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec) {
if (year >= 2000)
year -= 2000;
yOff = year;
m = month;
d = day;
hh = hour;
mm = min;
ss = sec;
}
static uint8_t conv2d(const char* p) {
uint8_t v = 0;
if ('0' <= *p && *p <= '9')
v = *p - '0';
return 10 * v + *++p - '0';
}
// A convenient constructor for using "the compiler's time":
// DateTime now (__DATE__, __TIME__);
// NOTE: using PSTR would further reduce the RAM footprint
DateTime::DateTime (const char* date, const char* time) {
// sample input: date = "Dec 26 2009", time = "12:34:56"
yOff = conv2d(date + 9);
// Jan Feb Mar Apr May Jun Jul Aug Sep Oct Nov Dec
switch (date[0]) {
case 'J': m = date[1] == 'a' ? 1 : m = date[2] == 'n' ? 6 : 7; break;
case 'F': m = 2; break;
case 'A': m = date[2] == 'r' ? 4 : 8; break;
case 'M': m = date[2] == 'r' ? 3 : 5; break;
case 'S': m = 9; break;
case 'O': m = 10; break;
case 'N': m = 11; break;
case 'D': m = 12; break;
}
d = conv2d(date + 4);
hh = conv2d(time);
mm = conv2d(time + 3);
ss = conv2d(time + 6);
}
uint8_t DateTime::dayOfWeek() const {
uint16_t day = date2days(yOff, m, d);
return (day + 6) % 7; // Jan 1, 2000 is a Saturday, i.e. returns 6
}
uint32_t DateTime::unixtime(void) const {
uint32_t t;
uint16_t days = date2days(yOff, m, d);
t = time2long(days, hh, mm, ss);
t += SECONDS_FROM_1970_TO_2000; // seconds from 1970 to 2000
return t;
}
////////////////////////////////////////////////////////////////////////////////
// RTC_DS1307 implementation
static uint8_t bcd2bin (uint8_t val) { return val - 6 * (val >> 4); }
static uint8_t bin2bcd (uint8_t val) { return val + 6 * (val / 10); }
uint8_t RTC_DS1307::begin(void) {
return 1;
}
#if (ARDUINO >= 100)
uint8_t RTC_DS1307::isrunning(void) {
WIRE.beginTransmission(DS1307_ADDRESS);
WIRE.write(0);
WIRE.endTransmission();
WIRE.requestFrom(DS1307_ADDRESS, 1);
uint8_t ss = WIRE.read();
return !(ss>>7);
}
void RTC_DS1307::adjust(const DateTime& dt) {
WIRE.beginTransmission(DS1307_ADDRESS);
WIRE.write(0);
WIRE.write(bin2bcd(dt.second()));
WIRE.write(bin2bcd(dt.minute()));
WIRE.write(bin2bcd(dt.hour()));
WIRE.write(bin2bcd(0));
WIRE.write(bin2bcd(dt.day()));
WIRE.write(bin2bcd(dt.month()));
WIRE.write(bin2bcd(dt.year() - 2000));
WIRE.write(0);
WIRE.endTransmission();
}
DateTime RTC_DS1307::now() {
WIRE.beginTransmission(DS1307_ADDRESS);
WIRE.write(0);
WIRE.endTransmission();
WIRE.requestFrom(DS1307_ADDRESS, 7);
uint8_t ss = bcd2bin(WIRE.read() & 0x7F);
uint8_t mm = bcd2bin(WIRE.read());
uint8_t hh = bcd2bin(WIRE.read());
WIRE.read();
uint8_t d = bcd2bin(WIRE.read());
uint8_t m = bcd2bin(WIRE.read());
uint16_t y = bcd2bin(WIRE.read()) + 2000;
return DateTime (y, m, d, hh, mm, ss);
}
#else
uint8_t RTC_DS1307::isrunning(void) {
WIRE.beginTransmission(DS1307_ADDRESS);
WIRE.send(0);
WIRE.endTransmission();
WIRE.requestFrom(DS1307_ADDRESS, 1);
uint8_t ss = WIRE.receive();
return !(ss>>7);
}
void RTC_DS1307::adjust(const DateTime& dt) {
WIRE.beginTransmission(DS1307_ADDRESS);
WIRE.send(0);
WIRE.send(bin2bcd(dt.second()));
WIRE.send(bin2bcd(dt.minute()));
WIRE.send(bin2bcd(dt.hour()));
WIRE.send(bin2bcd(0));
WIRE.send(bin2bcd(dt.day()));
WIRE.send(bin2bcd(dt.month()));
WIRE.send(bin2bcd(dt.year() - 2000));
WIRE.send(0);
WIRE.endTransmission();
}
DateTime RTC_DS1307::now() {
WIRE.beginTransmission(DS1307_ADDRESS);
WIRE.send(0);
WIRE.endTransmission();
WIRE.requestFrom(DS1307_ADDRESS, 7);
uint8_t ss = bcd2bin(WIRE.receive() & 0x7F);
uint8_t mm = bcd2bin(WIRE.receive());
uint8_t hh = bcd2bin(WIRE.receive());
WIRE.receive();
uint8_t d = bcd2bin(WIRE.receive());
uint8_t m = bcd2bin(WIRE.receive());
uint16_t y = bcd2bin(WIRE.receive()) + 2000;
return DateTime (y, m, d, hh, mm, ss);
}
#endif
////////////////////////////////////////////////////////////////////////////////
// RTC_Millis implementation
long RTC_Millis::offset = 0;
void RTC_Millis::adjust(const DateTime& dt) {
offset = dt.unixtime() - millis() / 1000;
}
DateTime RTC_Millis::now() {
return (uint32_t)(offset + millis() / 1000);
}
////////////////////////////////////////////////////////////////////////////////

52
RTClib.h Executable file
View File

@ -0,0 +1,52 @@
// Code by JeeLabs http://news.jeelabs.org/code/
// Released to the public domain! Enjoy!
#ifndef _RTCLIB_H_
#define _RTCLIB_H_
// Simple general-purpose date/time class (no TZ / DST / leap second handling!)
class DateTime {
public:
DateTime (uint32_t t =0);
DateTime (uint16_t year, uint8_t month, uint8_t day,
uint8_t hour =0, uint8_t min =0, uint8_t sec =0);
DateTime (const char* date, const char* time);
uint16_t year() const { return 2000 + yOff; }
uint8_t month() const { return m; }
uint8_t day() const { return d; }
uint8_t hour() const { return hh; }
uint8_t minute() const { return mm; }
uint8_t second() const { return ss; }
uint8_t dayOfWeek() const;
// 32-bit times as seconds since 1/1/2000
long secondstime() const;
// 32-bit times as seconds since 1/1/1970
uint32_t unixtime(void) const;
protected:
uint8_t yOff, m, d, hh, mm, ss;
};
// RTC based on the DS1307 chip connected via I2C and the Wire library
class RTC_DS1307 {
public:
static uint8_t begin(void);
static void adjust(const DateTime& dt);
uint8_t isrunning(void);
static DateTime now();
};
// RTC using the internal millis() clock, has to be initialized before use
// NOTE: this clock won't be correct once the millis() timer rolls over (>49d?)
class RTC_Millis {
public:
static void begin(const DateTime& dt) { adjust(dt); }
static void adjust(const DateTime& dt);
static DateTime now();
protected:
static long offset;
};
#endif // _RTCLIB_H_

429
TinyGPS.cpp Executable file
View File

@ -0,0 +1,429 @@
/*
TinyGPS - a small GPS library for Arduino providing basic NMEA parsing
Based on work by and "distance_to" and "course_to" courtesy of Maarten Lamers.
Suggestion to add satellites(), course_to(), and cardinal(), by Matt Monson.
Precision improvements suggested by Wayne Holder.
Copyright (C) 2008-2013 Mikal Hart
All rights reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include "TinyGPS.h"
#define _GPRMC_TERM "GPRMC"
#define _GPGGA_TERM "GPGGA"
TinyGPS::TinyGPS()
: _time(GPS_INVALID_TIME)
, _date(GPS_INVALID_DATE)
, _latitude(GPS_INVALID_ANGLE)
, _longitude(GPS_INVALID_ANGLE)
, _altitude(GPS_INVALID_ALTITUDE)
, _speed(GPS_INVALID_SPEED)
, _course(GPS_INVALID_ANGLE)
, _hdop(GPS_INVALID_HDOP)
, _numsats(GPS_INVALID_SATELLITES)
, _last_time_fix(GPS_INVALID_FIX_TIME)
, _last_position_fix(GPS_INVALID_FIX_TIME)
, _parity(0)
, _is_checksum_term(false)
, _sentence_type(_GPS_SENTENCE_OTHER)
, _term_number(0)
, _term_offset(0)
, _gps_data_good(false)
#ifndef _GPS_NO_STATS
, _encoded_characters(0)
, _good_sentences(0)
, _failed_checksum(0)
#endif
{
_term[0] = '\0';
}
//
// public methods
//
bool TinyGPS::encode(char c)
{
bool valid_sentence = false;
#ifndef _GPS_NO_STATS
++_encoded_characters;
#endif
switch(c)
{
case ',': // term terminators
_parity ^= c;
case '\r':
case '\n':
case '*':
if (_term_offset < sizeof(_term))
{
_term[_term_offset] = 0;
valid_sentence = term_complete();
}
++_term_number;
_term_offset = 0;
_is_checksum_term = c == '*';
return valid_sentence;
case '$': // sentence begin
_term_number = _term_offset = 0;
_parity = 0;
_sentence_type = _GPS_SENTENCE_OTHER;
_is_checksum_term = false;
_gps_data_good = false;
return valid_sentence;
}
// ordinary characters
if (_term_offset < sizeof(_term) - 1)
_term[_term_offset++] = c;
if (!_is_checksum_term)
_parity ^= c;
return valid_sentence;
}
#ifndef _GPS_NO_STATS
void TinyGPS::stats(unsigned long *chars, unsigned short *sentences, unsigned short *failed_cs)
{
if (chars) *chars = _encoded_characters;
if (sentences) *sentences = _good_sentences;
if (failed_cs) *failed_cs = _failed_checksum;
}
#endif
//
// internal utilities
//
int TinyGPS::from_hex(char a)
{
if (a >= 'A' && a <= 'F')
return a - 'A' + 10;
else if (a >= 'a' && a <= 'f')
return a - 'a' + 10;
else
return a - '0';
}
unsigned long TinyGPS::parse_decimal()
{
char *p = _term;
bool isneg = *p == '-';
if (isneg) ++p;
unsigned long ret = 100UL * gpsatol(p);
while (gpsisdigit(*p)) ++p;
if (*p == '.')
{
if (gpsisdigit(p[1]))
{
ret += 10 * (p[1] - '0');
if (gpsisdigit(p[2]))
ret += p[2] - '0';
}
}
return isneg ? -ret : ret;
}
// Parse a string in the form ddmm.mmmmmmm...
unsigned long TinyGPS::parse_degrees()
{
char *p;
unsigned long left_of_decimal = gpsatol(_term);
unsigned long hundred1000ths_of_minute = (left_of_decimal % 100UL) * 100000UL;
for (p=_term; gpsisdigit(*p); ++p);
if (*p == '.')
{
unsigned long mult = 10000;
while (gpsisdigit(*++p))
{
hundred1000ths_of_minute += mult * (*p - '0');
mult /= 10;
}
}
return (left_of_decimal / 100) * 1000000 + (hundred1000ths_of_minute + 3) / 6;
}
#define COMBINE(sentence_type, term_number) (((unsigned)(sentence_type) << 5) | term_number)
// Processes a just-completed term
// Returns true if new sentence has just passed checksum test and is validated
bool TinyGPS::term_complete()
{
if (_is_checksum_term)
{
byte checksum = 16 * from_hex(_term[0]) + from_hex(_term[1]);
if (checksum == _parity)
{
if (_gps_data_good)
{
#ifndef _GPS_NO_STATS
++_good_sentences;
#endif
_last_time_fix = _new_time_fix;
_last_position_fix = _new_position_fix;
switch(_sentence_type)
{
case _GPS_SENTENCE_GPRMC:
_time = _new_time;
_date = _new_date;
_latitude = _new_latitude;
_longitude = _new_longitude;
_speed = _new_speed;
_course = _new_course;
break;
case _GPS_SENTENCE_GPGGA:
_altitude = _new_altitude;
_time = _new_time;
_latitude = _new_latitude;
_longitude = _new_longitude;
_numsats = _new_numsats;
_hdop = _new_hdop;
break;
}
return true;
}
}
#ifndef _GPS_NO_STATS
else
++_failed_checksum;
#endif
return false;
}
// the first term determines the sentence type
if (_term_number == 0)
{
if (!gpsstrcmp(_term, _GPRMC_TERM))
_sentence_type = _GPS_SENTENCE_GPRMC;
else if (!gpsstrcmp(_term, _GPGGA_TERM))
_sentence_type = _GPS_SENTENCE_GPGGA;
else
_sentence_type = _GPS_SENTENCE_OTHER;
return false;
}
if (_sentence_type != _GPS_SENTENCE_OTHER && _term[0])
switch(COMBINE(_sentence_type, _term_number))
{
case COMBINE(_GPS_SENTENCE_GPRMC, 1): // Time in both sentences
case COMBINE(_GPS_SENTENCE_GPGGA, 1):
_new_time = parse_decimal();
_new_time_fix = millis();
break;
case COMBINE(_GPS_SENTENCE_GPRMC, 2): // GPRMC validity
_gps_data_good = _term[0] == 'A';
break;
case COMBINE(_GPS_SENTENCE_GPRMC, 3): // Latitude
case COMBINE(_GPS_SENTENCE_GPGGA, 2):
_new_latitude = parse_degrees();
_new_position_fix = millis();
break;
case COMBINE(_GPS_SENTENCE_GPRMC, 4): // N/S
case COMBINE(_GPS_SENTENCE_GPGGA, 3):
if (_term[0] == 'S')
_new_latitude = -_new_latitude;
break;
case COMBINE(_GPS_SENTENCE_GPRMC, 5): // Longitude
case COMBINE(_GPS_SENTENCE_GPGGA, 4):
_new_longitude = parse_degrees();
break;
case COMBINE(_GPS_SENTENCE_GPRMC, 6): // E/W
case COMBINE(_GPS_SENTENCE_GPGGA, 5):
if (_term[0] == 'W')
_new_longitude = -_new_longitude;
break;
case COMBINE(_GPS_SENTENCE_GPRMC, 7): // Speed (GPRMC)
_new_speed = parse_decimal();
break;
case COMBINE(_GPS_SENTENCE_GPRMC, 8): // Course (GPRMC)
_new_course = parse_decimal();
break;
case COMBINE(_GPS_SENTENCE_GPRMC, 9): // Date (GPRMC)
_new_date = gpsatol(_term);
break;
case COMBINE(_GPS_SENTENCE_GPGGA, 6): // Fix data (GPGGA)
_gps_data_good = _term[0] > '0';
break;
case COMBINE(_GPS_SENTENCE_GPGGA, 7): // Satellites used (GPGGA)
_new_numsats = (unsigned char)atoi(_term);
break;
case COMBINE(_GPS_SENTENCE_GPGGA, 8): // HDOP
_new_hdop = parse_decimal();
break;
case COMBINE(_GPS_SENTENCE_GPGGA, 9): // Altitude (GPGGA)
_new_altitude = parse_decimal();
break;
}
return false;
}
long TinyGPS::gpsatol(const char *str)
{
long ret = 0;
while (gpsisdigit(*str))
ret = 10 * ret + *str++ - '0';
return ret;
}
int TinyGPS::gpsstrcmp(const char *str1, const char *str2)
{
while (*str1 && *str1 == *str2)
++str1, ++str2;
return *str1;
}
/* static */
float TinyGPS::distance_between (float lat1, float long1, float lat2, float long2)
{
// returns distance in meters between two positions, both specified
// as signed decimal-degrees latitude and longitude. Uses great-circle
// distance computation for hypothetical sphere of radius 6372795 meters.
// Because Earth is no exact sphere, rounding errors may be up to 0.5%.
// Courtesy of Maarten Lamers
float delta = radians(long1-long2);
float sdlong = sin(delta);
float cdlong = cos(delta);
lat1 = radians(lat1);
lat2 = radians(lat2);
float slat1 = sin(lat1);
float clat1 = cos(lat1);
float slat2 = sin(lat2);
float clat2 = cos(lat2);
delta = (clat1 * slat2) - (slat1 * clat2 * cdlong);
delta = sq(delta);
delta += sq(clat2 * sdlong);
delta = sqrt(delta);
float denom = (slat1 * slat2) + (clat1 * clat2 * cdlong);
delta = atan2(delta, denom);
return delta * 6372795;
}
float TinyGPS::course_to (float lat1, float long1, float lat2, float long2)
{
// returns course in degrees (North=0, West=270) from position 1 to position 2,
// both specified as signed decimal-degrees latitude and longitude.
// Because Earth is no exact sphere, calculated course may be off by a tiny fraction.
// Courtesy of Maarten Lamers
float dlon = radians(long2-long1);
lat1 = radians(lat1);
lat2 = radians(lat2);
float a1 = sin(dlon) * cos(lat2);
float a2 = sin(lat1) * cos(lat2) * cos(dlon);
a2 = cos(lat1) * sin(lat2) - a2;
a2 = atan2(a1, a2);
if (a2 < 0.0)
{
a2 += TWO_PI;
}
return degrees(a2);
}
const char *TinyGPS::cardinal (float course)
{
static const char* directions[] = {"N", "NNE", "NE", "ENE", "E", "ESE", "SE", "SSE", "S", "SSW", "SW", "WSW", "W", "WNW", "NW", "NNW"};
int direction = (int)((course + 11.25f) / 22.5f);
return directions[direction % 16];
}
// lat/long in MILLIONTHs of a degree and age of fix in milliseconds
// (note: versions 12 and earlier gave this value in 100,000ths of a degree.
void TinyGPS::get_position(long *latitude, long *longitude, unsigned long *fix_age)
{
if (latitude) *latitude = _latitude;
if (longitude) *longitude = _longitude;
if (fix_age) *fix_age = _last_position_fix == GPS_INVALID_FIX_TIME ?
GPS_INVALID_AGE : millis() - _last_position_fix;
}
// date as ddmmyy, time as hhmmsscc, and age in milliseconds
void TinyGPS::get_datetime(unsigned long *date, unsigned long *time, unsigned long *age)
{
if (date) *date = _date;
if (time) *time = _time;
if (age) *age = _last_time_fix == GPS_INVALID_FIX_TIME ?
GPS_INVALID_AGE : millis() - _last_time_fix;
}
void TinyGPS::f_get_position(float *latitude, float *longitude, unsigned long *fix_age)
{
long lat, lon;
get_position(&lat, &lon, fix_age);
*latitude = lat == GPS_INVALID_ANGLE ? GPS_INVALID_F_ANGLE : (lat / 1000000.0);
*longitude = lat == GPS_INVALID_ANGLE ? GPS_INVALID_F_ANGLE : (lon / 1000000.0);
}
void TinyGPS::crack_datetime(int *year, byte *month, byte *day,
byte *hour, byte *minute, byte *second, byte *hundredths, unsigned long *age)
{
unsigned long date, time;
get_datetime(&date, &time, age);
if (year)
{
*year = date % 100;
*year += *year > 80 ? 1900 : 2000;
}
if (month) *month = (date / 100) % 100;
if (day) *day = date / 10000;
if (hour) *hour = time / 1000000;
if (minute) *minute = (time / 10000) % 100;
if (second) *second = (time / 100) % 100;
if (hundredths) *hundredths = time % 100;
}
float TinyGPS::f_altitude()
{
return _altitude == GPS_INVALID_ALTITUDE ? GPS_INVALID_F_ALTITUDE : _altitude / 100.0;
}
float TinyGPS::f_course()
{
return _course == GPS_INVALID_ANGLE ? GPS_INVALID_F_ANGLE : _course / 100.0;
}
float TinyGPS::f_speed_knots()
{
return _speed == GPS_INVALID_SPEED ? GPS_INVALID_F_SPEED : _speed / 100.0;
}
float TinyGPS::f_speed_mph()
{
float sk = f_speed_knots();
return sk == GPS_INVALID_F_SPEED ? GPS_INVALID_F_SPEED : _GPS_MPH_PER_KNOT * sk;
}
float TinyGPS::f_speed_mps()
{
float sk = f_speed_knots();
return sk == GPS_INVALID_F_SPEED ? GPS_INVALID_F_SPEED : _GPS_MPS_PER_KNOT * sk;
}
float TinyGPS::f_speed_kmph()
{
float sk = f_speed_knots();
return sk == GPS_INVALID_F_SPEED ? GPS_INVALID_F_SPEED : _GPS_KMPH_PER_KNOT * sk;
}
const float TinyGPS::GPS_INVALID_F_ANGLE = 1000.0;
const float TinyGPS::GPS_INVALID_F_ALTITUDE = 1000000.0;
const float TinyGPS::GPS_INVALID_F_SPEED = -1.0;

157
TinyGPS.h Executable file
View File

@ -0,0 +1,157 @@
/*
TinyGPS - a small GPS library for Arduino providing basic NMEA parsing
Based on work by and "distance_to" and "course_to" courtesy of Maarten Lamers.
Suggestion to add satellites(), course_to(), and cardinal(), by Matt Monson.
Precision improvements suggested by Wayne Holder.
Copyright (C) 2008-2013 Mikal Hart
All rights reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifndef TinyGPS_h
#define TinyGPS_h
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif
#include <stdlib.h>
#define _GPS_VERSION 13 // software version of this library
#define _GPS_MPH_PER_KNOT 1.15077945
#define _GPS_MPS_PER_KNOT 0.51444444
#define _GPS_KMPH_PER_KNOT 1.852
#define _GPS_MILES_PER_METER 0.00062137112
#define _GPS_KM_PER_METER 0.001
// #define _GPS_NO_STATS
class TinyGPS
{
public:
enum {
GPS_INVALID_AGE = 0xFFFFFFFF, GPS_INVALID_ANGLE = 999999999,
GPS_INVALID_ALTITUDE = 999999999, GPS_INVALID_DATE = 0,
GPS_INVALID_TIME = 0xFFFFFFFF, GPS_INVALID_SPEED = 999999999,
GPS_INVALID_FIX_TIME = 0xFFFFFFFF, GPS_INVALID_SATELLITES = 0xFF,
GPS_INVALID_HDOP = 0xFFFFFFFF
};
static const float GPS_INVALID_F_ANGLE, GPS_INVALID_F_ALTITUDE, GPS_INVALID_F_SPEED;
TinyGPS();
bool encode(char c); // process one character received from GPS
TinyGPS &operator << (char c) {encode(c); return *this;}
// lat/long in MILLIONTHs of a degree and age of fix in milliseconds
// (note: versions 12 and earlier gave lat/long in 100,000ths of a degree.
void get_position(long *latitude, long *longitude, unsigned long *fix_age = 0);
// date as ddmmyy, time as hhmmsscc, and age in milliseconds
void get_datetime(unsigned long *date, unsigned long *time, unsigned long *age = 0);
// signed altitude in centimeters (from GPGGA sentence)
inline long altitude() { return _altitude; }
// course in last full GPRMC sentence in 100th of a degree
inline unsigned long course() { return _course; }
// speed in last full GPRMC sentence in 100ths of a knot
inline unsigned long speed() { return _speed; }
// satellites used in last full GPGGA sentence
inline unsigned short satellites() { return _numsats; }
// horizontal dilution of precision in 100ths
inline unsigned long hdop() { return _hdop; }
void f_get_position(float *latitude, float *longitude, unsigned long *fix_age = 0);
void crack_datetime(int *year, byte *month, byte *day,
byte *hour, byte *minute, byte *second, byte *hundredths = 0, unsigned long *fix_age = 0);
float f_altitude();
float f_course();
float f_speed_knots();
float f_speed_mph();
float f_speed_mps();
float f_speed_kmph();
static int library_version() { return _GPS_VERSION; }
static float distance_between (float lat1, float long1, float lat2, float long2);
static float course_to (float lat1, float long1, float lat2, float long2);
static const char *cardinal(float course);
#ifndef _GPS_NO_STATS
void stats(unsigned long *chars, unsigned short *good_sentences, unsigned short *failed_cs);
#endif
private:
enum {_GPS_SENTENCE_GPGGA, _GPS_SENTENCE_GPRMC, _GPS_SENTENCE_OTHER};
// properties
unsigned long _time, _new_time;
unsigned long _date, _new_date;
long _latitude, _new_latitude;
long _longitude, _new_longitude;
long _altitude, _new_altitude;
unsigned long _speed, _new_speed;
unsigned long _course, _new_course;
unsigned long _hdop, _new_hdop;
unsigned short _numsats, _new_numsats;
unsigned long _last_time_fix, _new_time_fix;
unsigned long _last_position_fix, _new_position_fix;
// parsing state variables
byte _parity;
bool _is_checksum_term;
char _term[15];
byte _sentence_type;
byte _term_number;
byte _term_offset;
bool _gps_data_good;
#ifndef _GPS_NO_STATS
// statistics
unsigned long _encoded_characters;
unsigned short _good_sentences;
unsigned short _failed_checksum;
unsigned short _passed_checksum;
#endif
// internal utilities
int from_hex(char a);
unsigned long parse_decimal();
unsigned long parse_degrees();
bool term_complete();
bool gpsisdigit(char c) { return c >= '0' && c <= '9'; }
long gpsatol(const char *str);
int gpsstrcmp(const char *str1, const char *str2);
};
#if !defined(ARDUINO)
// Arduino 0012 workaround
#undef int
#undef char
#undef long
#undef byte
#undef float
#undef abs
#undef round
#endif
#endif

135
hh12.cpp Executable file
View File

@ -0,0 +1,135 @@
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif
#include "hh12.h"
/*
Code adapted from here: http://www.madscientisthut.com/forum_php/viewtopic.php?f=11&t=7
*/
int hh12_clock_pin = 0;
int hh12_cs_pin = 0;
int hh12_data_pin = 0;
int inputstream = 0; //one bit read from pin
long packeddata = 0; //two bytes concatenated from inputstream
long angle = 0; //holds processed angle value
float floatangle = 0;
long anglemask = 65472; //0x1111111111000000: mask to obtain first 10 digits with position info
long statusmask = 63; //0x000000000111111; mask to obtain last 6 digits containing status info
long statusbits; //holds status/error information
int DECn; //bit holding decreasing magnet field error data
int INCn; //bit holding increasing magnet field error data
int OCF; //bit holding startup-valid bit
int COF; //bit holding cordic DSP processing error data
int LIN; //bit holding magnet field displacement error data
//-----------------------------------------------------------------------------------------------------
hh12::hh12(){
}
//-----------------------------------------------------------------------------------------------------
void hh12::initialize(int _hh12_clock_pin, int _hh12_cs_pin, int _hh12_data_pin){
hh12_clock_pin = _hh12_clock_pin;
hh12_cs_pin = _hh12_cs_pin;
hh12_data_pin = _hh12_data_pin;
pinMode(hh12_clock_pin, OUTPUT);
pinMode(hh12_cs_pin, OUTPUT);
pinMode(hh12_data_pin, INPUT);
}
//-----------------------------------------------------------------------------------------------------
float hh12::heading(){
digitalWrite(hh12_cs_pin, HIGH); // CSn high
digitalWrite(hh12_clock_pin, HIGH); // CLK high
digitalWrite(hh12_cs_pin, LOW); // CSn low: start of transfer
delayMicroseconds(HH12_DELAY); // delay for chip initialization
digitalWrite(hh12_clock_pin, LOW); // CLK goes low: start clocking
delayMicroseconds(HH12_DELAY); // hold low
for (int x=0; x <16; x++) // clock signal, 16 transitions, output to clock pin
{
digitalWrite(hh12_clock_pin, HIGH); //clock goes high
delayMicroseconds(HH12_DELAY); //
inputstream =digitalRead(hh12_data_pin); // read one bit of data from pin
#ifdef DEBUG_HH12
Serial.print(inputstream, DEC);
#endif
packeddata = ((packeddata << 1) + inputstream);// left-shift summing variable, add pin value
digitalWrite(hh12_clock_pin, LOW);
delayMicroseconds(HH12_DELAY); // end of one clock cycle
}
// end of entire clock cycle
#ifdef DEBUG_HH12
Serial.print("hh12: packed:");
Serial.println(packeddata,DEC);
Serial.print("hh12: pack bin: ");
Serial.println(packeddata,BIN);
#endif
angle = packeddata & anglemask; // mask rightmost 6 digits of packeddata to zero, into angle
#ifdef DEBUG_HH12
Serial.print("hh12: mask: ");
Serial.println(anglemask, BIN);
Serial.print("hh12: bin angle:");
Serial.println(angle, BIN);
Serial.print("hh12: angle: ");
Serial.println(angle, DEC);
#endif
angle = (angle >> 6); // shift 16-digit angle right 6 digits to form 10-digit value
#ifdef DEBUG_HH12
Serial.print("hh12: angleshft:");
Serial.println(angle, BIN);
Serial.print("hh12: angledec: ");
Serial.println(angle, DEC);
#endif
floatangle = angle * 0.3515; // angle * (360/1024) == actual degrees
#ifdef DEBUG_HH12
statusbits = packeddata & statusmask;
DECn = statusbits & 2; // goes high if magnet moved away from IC
INCn = statusbits & 4; // goes high if magnet moved towards IC
LIN = statusbits & 8; // goes high for linearity alarm
COF = statusbits & 16; // goes high for cordic overflow: data invalid
OCF = statusbits & 32; // this is 1 when the chip startup is finished
if (DECn && INCn) {
Serial.println("hh12: magnet moved out of range");
} else {
if (DECn) {
Serial.println("hh12: magnet moved away from chip");
}
if (INCn) {
Serial.println("hh12: magnet moved towards chip");
}
}
if (LIN) {
Serial.println("hh12: linearity alarm: magnet misaligned? data questionable");
}
if (COF) {
Serial.println("hh12: cordic overflow: magnet misaligned? data invalid");
}
#endif //DEBUG_HH12
return(floatangle);
}

21
hh12.h Executable file
View File

@ -0,0 +1,21 @@
#ifndef hh12_h
#define hh12_h
#define HH12_DELAY 100 // microseconds
class hh12 {
public:
hh12();
void initialize(int _hh12_clock_pin, int _hh12_cs_pin, int _hh12_data_pin);
float heading();
private:
int hh12_clock_pin;
int hh12_cs_pin;
int hh12_data_pin;
};
#endif //hh12_h

File diff suppressed because it is too large Load Diff

330
moon2.cpp Executable file
View File

@ -0,0 +1,330 @@
#include <Arduino.h>
#include <math.h>
#include <string.h>
#include <ctype.h>
// Translated from the WSJT Fortran code by Pete VE5VA
/////////////////////////////////////////////////////////
///////////// G R I D 2 D E G /////////////
/////////////////////////////////////////////////////////
// Choose which version of the grid conversion to use.
// Defining WSJT uses the one from WSJT
// Removing the define of WSJT uses the code based on
// the PERL script at wikipedia which seems to be
// slightly more accurate.
//#define WSJT
#ifdef WSJT
// grid = DO62QC <-> lat = 52.104167 lon = -106.658332
// grid = JO62MM <-> lat = 52.520832 lon = 13.008334
// The WSJT code returns West as positive but moon2 uses
// West is negative
// CHANGE this so that it returns West longitude as NEGATIVE
void grid2deg(char *grid0,double *dlong,double *dlat)
{
char grid[8];
int nlong,n20d;
int nlat;
double xminlong,xminlat;
// Initialize the grid with a default string
strncpy(grid,"AA00MM",6);
// copy in the grid
strncpy(grid,grid0,6);
// Convert the grid to upper case
for(int i = 0;i < 6;i++)grid[i] = toupper(grid[i]);
// Fix any errors
if(!isalpha(grid[0]))grid[0] = 'A';
if(!isalpha(grid[1]))grid[1] = 'A';
if(!isdigit(grid[2]))grid[2] = '0';
if(!isdigit(grid[3]))grid[3] = '0';
if(!isalpha(grid[4]))grid[4] = 'M';
if(!isalpha(grid[5]))grid[5] = 'M';
nlong = 180 - 20*(grid[0] - 'A');
n20d = 2*(grid[2] - '0');
xminlong = 5*(grid[4]-'A')+ 0.5;
// Make west longitude negative
*dlong = -(nlong - n20d -xminlong/60.);
nlat = -90 + 10*(grid[1] - 'A') + grid[3] - '0';
xminlat = 2.5*(grid[5] - 'A' + 0.5);
*dlat = nlat + xminlat/60.;
}
#else
// grid = DO62QC <-> lat = 52.104164 lon = -106.625000
// grid = JO62MM <-> lat = 52.520832 lon = 13.041667
// From: http://en.wikipedia.org/wiki/Maidenhead_Locator_System
void grid2deg(char *grid0,double *dlong,double *dlat)
{
char grid[8];
// Initialize the grid with a default string
strncpy(grid,"AA00MM",6);
// copy in the grid
strncpy(grid,grid0,6);
// Convert the grid to upper case
for(int i = 0;i < 6;i++)grid[i] = toupper(grid[i]);
// Fix any errors
if(!isalpha(grid[0]))grid[0] = 'A';
if(!isalpha(grid[1]))grid[1] = 'A';
if(!isdigit(grid[2]))grid[2] = '0';
if(!isdigit(grid[3]))grid[3] = '0';
if(!isalpha(grid[4]))grid[4] = 'M';
if(!isalpha(grid[5]))grid[5] = 'M';
*dlong = 20*(grid[0] - 'A') - 180;
*dlat = 10*(grid[1] - 'A') - 90;
*dlong += (grid[2] - '0') * 2;
*dlat += (grid[3] - '0');
// subsquares
*dlong += (grid[4] - 'A') * 5/60.;
*dlat += (grid[5] - 'A') * 2.5/60.;
*dlong += 2.5/60.;
*dlat += 1.25/60;
}
#endif
/////////////////////////////////////////////////////////
////////////// D C O O R D ///////////////
/////////////////////////////////////////////////////////
// In WSJT this is used in various places to do coordinate
// system conversions but moon2 only uses it once.
void DCOORD(double xA0,double xB0,double AP,double BP,
double xA1,double xB1,double *xA2,double *B2)
{
double TA2O2;
double SB0,CB0,SBP,CBP,SB1,CB1,SB2,CB2;
double SAA,CAA,SBB,CBB,CA2,SA2;
SB0 = sin(xB0);
CB0 = cos(xB0);
SBP = sin(BP);
CBP = cos(BP);
SB1 = sin(xB1);
CB1 = cos(xB1);
SB2 = SBP*SB1 + CBP*CB1*cos(AP-xA1);
CB2 = sqrt(1.-(SB2*SB2));
*B2 = atan(SB2/CB2);
SAA = sin(AP-xA1)*CB1/CB2;
CAA = (SB1-SB2*SBP)/(CB2*CBP);
CBB = SB0/CBP;
SBB = sin(AP-xA0)*CB0;
SA2 = SAA*CBB-CAA*SBB;
CA2 = CAA*CBB+SAA*SBB;
TA2O2 = 0.0;
if(CA2 <= 0.) TA2O2 = (1.-CA2)/SA2;
if(CA2 > 0.) TA2O2 = SA2/(1.+CA2);
*xA2=2.*atan(TA2O2);
if(*xA2 < 0.) *xA2 = *xA2+6.2831853071795864;
}
/////////////////////////////////////////////////////////
//////////////// M O O N 2 ////////////////
/////////////////////////////////////////////////////////
// You can derive the lat/long from the grid square using
// the grid2deg function to translate from grid to lat/long
// Example call to this function for 2014/01/04 1709Z:
// moon2(2014,1,4,17+9/60.,-106.625,52.104168,
// &RA, &Dec, &topRA, &topDec, &LST, &HA, &Az, &El, &dist);
// I have not used or checked any of the outputs other than Az and El
void moon2(int y,int m,int Day,
double UT,
double lon,double lat,
double *RA,double *Dec,
double *topRA,double *topDec,
double *LST,double *HA,
double *Az,double *El,double *dist)
{
// The strange position of some of the semicolons is because some
// of this was translated using a TCL script that I wrote - it isn't
// too smart but it saved some typing
double NN ;//Longitude of ascending node
double i ;//Inclination to the ecliptic
double w ;//Argument of perigee
double a ;//Semi-major axis
double e ;//Eccentricity
double MM ;//Mean anomaly
double v ;//True anomaly
double EE ;//Eccentric anomaly
double ecl ;//Obliquity of the ecliptic
double d ;//Ephemeris time argument in days
double r ;//Distance to sun, AU
double xv,yv ;//x and y coords in ecliptic
double lonecl,latecl ;//Ecliptic long and lat of moon
double xg,yg,zg ;//Ecliptic rectangular coords
double Ms ;//Mean anomaly of sun
double ws ;//Argument of perihelion of sun
double Ls ;//Mean longitude of sun (Ns=0)
double Lm ;//Mean longitude of moon
double DD ;//Mean elongation of moon
double FF ;//Argument of latitude for moon
double xe,ye,ze ;//Equatorial geocentric coords of moon
double mpar ;//Parallax of moon (r_E / d)
// double lat,lon ;//Station coordinates on earth
double gclat ;//Geocentric latitude
double rho ;//Earth radius factor
double GMST0; //,LST,HA;
double g;
// double topRA,topDec ;//Topocentric coordinates of Moon
// double Az,El;
// double dist;
double rad = 57.2957795131,twopi = 6.283185307,pi,pio2;
// data rad/57.2957795131d0/,twopi/6.283185307d0/
//Note the use of 'L' to force 32-bit integer arithmetic here.
d=367L*y - 7L*(y+(m+9L)/12L)/4L + 275L*m/9L + Day - 730530L + UT/24.;
ecl = 23.4393 - 3.563e-7 * d;
//Serial.print("d = ");
//Serial.println(d,3);
// Orbital elements for Moon:
NN = 125.1228 - 0.0529538083 * d;
i = 5.1454;
w = fmod(318.0634 + 0.1643573223 * d + 360000.,360.);
a = 60.2666;
e = 0.054900;
MM = fmod(115.3654 + 13.0649929509 * d + 360000.,360.);
// Orbital elements for Sun:
/*
NN = 0.0;
i = 0.0;
w = fmod(282.9404 + 4.70935e-5 * d + 360000.,360.);
a = 1.000000;
e = 0.016709 - 1.151e-9 * d;
MM = fmod(356.0470 + 0.99856002585 * d + 360000.,360.);
*/
/*
Serial.print("\nmoon2: w=");
Serial.print(w,3);
Serial.print(" e=");
Serial.print(e,3);
Serial.print(" MM=");
Serial.println(MM,3);
*/
EE = MM + e*rad*sin(MM/rad) * (1. + e*cos(MM/rad));
EE = EE - (EE - e*rad*sin(EE/rad)-MM) / (1. - e*cos(EE/rad));
EE = EE - (EE - e*rad*sin(EE/rad)-MM) / (1. - e*cos(EE/rad));
xv = a * (cos(EE/rad) - e);
yv = a * (sqrt(1.-e*e) * sin(EE/rad));
v = fmod(rad*atan2(yv,xv)+720.,360.);
r = sqrt(xv*xv + yv*yv);
// Get geocentric position in ecliptic rectangular coordinates:
xg = r * (cos(NN/rad)*cos((v+w)/rad) - sin(NN/rad)*sin((v+w)/rad)*cos(i/rad));
yg = r * (sin(NN/rad)*cos((v+w)/rad) + cos(NN/rad)*sin((v+w)/rad)*cos(i/rad));
zg = r * (sin((v+w)/rad)*sin(i/rad));
// Ecliptic longitude and latitude of moon:
lonecl = fmod(rad*atan2(yg/rad,xg/rad)+720.,360.);
latecl = rad * atan2(zg/rad,sqrt(xg*xg + yg*yg)/rad);
// Now include orbital perturbations:
Ms = fmod(356.0470 + 0.9856002585 * d + 3600000.,360.);
ws = 282.9404 + 4.70935e-5*d;
Ls = fmod(Ms + ws + 720.,360.);
Lm = fmod(MM + w + NN+720.,360.);
DD = fmod(Lm - Ls + 360.,360.);
FF = fmod(Lm - NN + 360.,360.);
lonecl = lonecl
-1.274 * sin((MM-2.*DD)/rad)
+0.658 * sin(2.*DD/rad)
-0.186 * sin(Ms/rad)
-0.059 * sin((2.*MM-2.*DD)/rad)
-0.057 * sin((MM-2.*DD+Ms)/rad)
+0.053 * sin((MM+2.*DD)/rad)
+0.046 * sin((2.*DD-Ms)/rad)
+0.041 * sin((MM-Ms)/rad)
-0.035 * sin(DD/rad)
-0.031 * sin((MM+Ms)/rad)
-0.015 * sin((2.*FF-2.*DD)/rad)
+0.011 * sin((MM-4.*DD)/rad);
latecl = latecl
-0.173 * sin((FF-2.*DD)/rad)
-0.055 * sin((MM-FF-2.*DD)/rad)
-0.046 * sin((MM+FF-2.*DD)/rad)
+0.033 * sin((FF+2.*DD)/rad)
+0.017 * sin((2.*MM+FF)/rad);
r = 60.36298
- 3.27746*cos(MM/rad)
- 0.57994*cos((MM-2.*DD)/rad)
- 0.46357*cos(2.*DD/rad)
- 0.08904*cos(2.*MM/rad)
+ 0.03865*cos((2.*MM-2.*DD)/rad)
- 0.03237*cos((2.*DD-Ms)/rad)
- 0.02688*cos((MM+2.*DD)/rad)
- 0.02358*cos((MM-2.*DD+Ms)/rad)
- 0.02030*cos((MM-Ms)/rad)
+ 0.01719*cos(DD/rad)
+ 0.01671*cos((MM+Ms)/rad);
*dist = r * 6378.140;
// Geocentric coordinates:
// Rectangular ecliptic coordinates of the moon:
xg = r * cos(lonecl/rad)*cos(latecl/rad);
yg = r * sin(lonecl/rad)*cos(latecl/rad);
zg = r * sin(latecl/rad);
// Rectangular equatorial coordinates of the moon:
xe = xg;
ye = yg * cos(ecl/rad) - zg*sin(ecl/rad);
ze = yg * sin(ecl/rad) + zg*cos(ecl/rad);
// Right Ascension, Declination:
*RA = fmod(rad*atan2(ye,xe)+360.,360.);
*Dec = rad * atan2(ze,sqrt(xe*xe + ye*ye));
// Now convert to topocentric system:
mpar=rad * asin(1./r);
// alt_topoc = alt_geoc - mpar*cos(alt_geoc);
gclat = lat - 0.1924 * sin(2.*lat/rad);
rho = 0.99883 + 0.00167 * cos(2.*lat/rad);
GMST0 = (Ls + 180.)/15.;
*LST = fmod(GMST0+UT+lon/15.+48.,24.) ;//LST in hours
*HA = 15. * *LST - *RA ;//HA in degrees
g = rad*atan(tan(gclat/rad)/cos(*HA/rad));
*topRA = *RA - mpar*rho*cos(gclat/rad)*sin(*HA/rad)/cos(*Dec/rad);
*topDec = *Dec - mpar*rho*sin(gclat/rad)*sin((g-*Dec)/rad)/sin(g/rad);
*HA = 15. * *LST - *topRA ;//HA in degrees
if(*HA > 180.) *HA=*HA-360.;
if(*HA < -180.) *HA=*HA+360.;
pi = 0.5 * twopi;
pio2 = 0.5 * pi;
DCOORD(pi,pio2-lat/rad,0.,lat/rad,*HA*twopi/360,*topDec/rad,Az,El);
*Az = *Az * rad;
*El = *El * rad;
return;
}

9
moon2.h Executable file
View File

@ -0,0 +1,9 @@
void grid2deg(char *grid0,double *dlong,double *dlat);
void moon2(int y,int m,int Day,
double UT,
double lon,double lat,
double *RA,double *Dec,
double *topRA,double *topDec,
double *LST,double *HA,
double *Az,double *El,double *dist);

181
pins_m0upu.h Executable file
View File

@ -0,0 +1,181 @@
/* LEDs left to right
6 - PWM
7 - NO PWM
8 - NO PWM
9 - PWM
*/
#define pins_h
#define rotate_cw 7 //0//6 // goes high to activate rotator R (CW) rotation - pin 1 on Yaesu connector
#define rotate_ccw 6//7 // goes high to activate rotator L (CCW) rotation - pin 2 on Yaesu connector
#define rotate_cw_ccw 0 // goes high for both CW and CCW rotation
#define rotate_cw_pwm 0 // 6 // optional - PWM CW output - set to 0 to disable (must be PWM capable pin)
#define rotate_ccw_pwm 0 //7 // optional - PWM CCW output - set to 0 to disable (must be PWM capable pin)
#define rotate_cw_ccw_pwm 0
#define rotate_cw_freq 0 // UNDER DEVELOPMENT
#define rotate_ccw_freq 0 // UNDER DEVELOPMENT
#define button_cw 0 //A1 // normally open button to ground for manual CW rotation
#define button_ccw 0 //A2 // normally open button to ground for manual CCW rotation
#define serial_led 13 //0 // LED blinks when command is received on serial port (set to 0 to disable)
#define rotator_analog_az A0 // reads analog azimuth voltage from rotator - pin 4 on Yaesu connector
#define azimuth_speed_voltage 0 // optional - PWM output for speed control voltage feed into rotator (on continually unlike rotate_cw_pwm and rotate_ccw_pwm)
#define overlap_led 0 // line goes high when azimuth rotator is in overlap (> 360 rotators)
#define brake_az 13 //0 // goes high to disengage azimuth brake (set to 0 to disable)
#define az_speed_pot 0 //A4 // connect to wiper of 1K to 10K potentiometer for speed control (set to 0 to disable)
#define az_preset_pot 0 // connect to wiper of 1K to 10K potentiometer for preset control (set to 0 to disable)
#define preset_start_button 0 //10 // connect to momentary switch (ground on button press) for preset start (set to 0 to disable or for preset automatic start)
#define button_stop 0 // connect to momentary switch (ground on button press) for preset stop (set to 0 to disable or for preset automatic start)
#define rotation_indication_pin 0
#define az_stepper_motor_pulse 0
#define az_stepper_motor_direction 0
// elevation pins
#ifdef FEATURE_ELEVATION_CONTROL
#define elevation_speed_voltage 0 // optional - PWM output for speed control voltage feed into rotator (on continually unlike rotate_up_pwm and rotate_down_pwm)
#define rotate_up 9//9 // goes high to activate rotator elevation up
#define rotate_down 8 // goes high to activate rotator elevation down
#define rotate_up_or_down 0
#define rotate_up_pwm 0 // UNDER DEVELOPMENT
#define rotate_down_pwm 0 // UNDER DEVELOPMENT
#define rotate_up_down_pwm 0
#define rotate_up_freq 0 // UNDER DEVELOPMENT
#define rotate_down_freq 0 // UNDER DEVELOPMENT
#define rotator_analog_el A1 // reads analog elevation voltage from rotator
#define button_up 0 // normally open button to ground for manual up elevation
#define button_down 0 // normally open button to ground for manual down rotation
#define brake_el 0 // goes high to disengage elevation brake (set to 0 to disable)
#define el_stepper_motor_pulse 0
#define el_stepper_motor_direction 0
#endif //FEATURE_ELEVATION_CONTROL
// rotary encoder pins and options
#ifdef FEATURE_AZ_PRESET_ENCODER
#define az_rotary_preset_pin1 A3 //6 // CW Encoder Pin
#define az_rotary_preset_pin2 A2 //7 // CCW Encoder Pin
#endif //FEATURE_AZ_PRESET_ENCODER
#ifdef FEATURE_EL_PRESET_ENCODER
#define el_rotary_preset_pin1 0 // A3 //6 // UP Encoder Pin
#define el_rotary_preset_pin2 0 // A2 //7 // DOWN Encoder Pin
#endif //FEATURE_EL_PRESET_ENCODER
#ifdef FEATURE_AZ_POSITION_ROTARY_ENCODER
#define az_rotary_position_pin1 A3 // CW Encoder Pin
#define az_rotary_position_pin2 A2 // CCW Encoder Pin
#endif //FEATURE_AZ_POSITION_ROTARY_ENCODER
#ifdef FEATURE_EL_POSITION_ROTARY_ENCODER
#define el_rotary_position_pin1 0 // CW Encoder Pin
#define el_rotary_position_pin2 0 // CCW Encoder Pin
#endif //FEATURE_EL_POSITION_ROTARY_ENCODER
#ifdef FEATURE_AZ_POSITION_PULSE_INPUT
#define az_position_pulse_pin 0 // must be an interrupt capable pin!
#define AZ_POSITION_PULSE_PIN_INTERRUPT 0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
#endif // read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
#ifdef FEATURE_EL_POSITION_PULSE_INPUT
#define el_position_pulse_pin 0 // must be an interrupt capable pin!
#define EL_POSITION_PULSE_PIN_INTERRUPT 1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
#endif // read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
#ifdef FEATURE_PARK
#define button_park 0
#endif
#define lcd_4_bit_rs_pin 12
#define lcd_4_bit_enable_pin 11
#define lcd_4_bit_d4_pin 5
#define lcd_4_bit_d5_pin 4
#define lcd_4_bit_d6_pin 3
#define lcd_4_bit_d7_pin 2
#ifdef FEATURE_JOYSTICK_CONTROL
#define pin_joystick_x A2
#define pin_joystick_y A3
#endif //FEATURE_JOYSTICK_CONTROL
#define blink_led 0 //13
#ifdef FEATURE_AZ_POSITION_HH12_AS5045_SSI
#define az_hh12_clock_pin 11
#define az_hh12_cs_pin 12
#define az_hh12_data_pin 13
#endif //FEATURE_AZ_POSITION_HH_12
#ifdef FEATURE_EL_POSITION_HH12_AS5045_SSI
#define el_hh12_clock_pin 11
#define el_hh12_cs_pin 12
#define el_hh12_data_pin 13
#endif //FEATURE_EL_POSITION_HH_12
#ifdef FEATURE_PARK
#define park_in_progress_pin 0 // goes high when a park has been initiated and rotation is in progress
#define parked_pin 0 // goes high when in a parked position
#endif //FEATURE_PARK
#define heading_reading_inhibit_pin 0 // input - a high will cause the controller to suspend taking azimuth (and elevation) readings; use when RF interferes with sensors
#ifdef FEATURE_LIMIT_SENSE
#define az_limit_sense_pin 0 // input - low stops azimuthal rotation
#define el_limit_sense_pin 0 // input - low stops elevation rotation
#endif //FEATURE_LIMIT_SENSE
#ifdef FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
#define az_3_phase_encoder_pin_phase_a 2 // must be an interrupt capable pin
#define az_3_phase_encoder_pin_phase_b 3 // must be an interrupt capable pin
#define az_3_phase_encoder_pin_phase_z 4
#define AZ_POSITION_3_PHASE_INCREMENTAL_ENCODER_A_PIN_INTERRUPT 0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
#define AZ_POSITION_3_PHASE_INCREMENTAL_ENCODER_B_PIN_INTERRUPT 1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
// read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
#endif //FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
#ifdef FEATURE_EL_POSITION_INCREMENTAL_ENCODER
#define el_3_phase_encoder_pin_phase_a 2 // must be an interrupt capable pin
#define el_3_phase_encoder_pin_phase_b 3 // must be an interrupt capable pin
#define el_3_phase_encoder_pin_phase_z 4
#define EL_POSITION_3_PHASE_INCREMENTAL_ENCODER_A_PIN_INTERRUPT 0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
#define EL_POSITION_3_PHASE_INCREMENTAL_ENCODER_B_PIN_INTERRUPT 1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
// read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
#endif //FEATURE_EL_POSITION_INCREMENTAL_ENCODER
#ifdef FEATURE_YOURDUINO_I2C_LCD
#define En_pin 2
#define Rw_pin 1
#define Rs_pin 0
#define D4_pin 4
#define D5_pin 5
#define D6_pin 6
#define D7_pin 7
#endif //FEATURE_YOURDUINO_I2C_LCD
#ifdef FEATURE_MOON_TRACKING
#define moon_tracking_active_pin 0 // goes high when moon tracking is active
#define moon_tracking_activate_line 0 // ground this pin to activate moon tracking (not for use with a button)
#define moon_tracking_button 0 // use with a normally open momentary switch to ground
#endif //FEATURE_MOON_TRACKING
#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
#endif //FEATURE_SUN_TRACKING
#ifdef FEATURE_GPS
#define gps_sync 0
#endif //FEATURE_GPS
#ifdef FEATURE_POWER_SWITCH
#define power_switch 0 // use with FEATURE_POWER_SWITCH
#endif //FEATURE_POWER_SWITCH
#ifdef FEATURE_EL_POSITION_MEMSIC_2125
#define pin_memsic_2125_x 0
#define pin_memsic_2125_y 0
#endif //FEATURE_EL_POSITION_MEMSIC_2125

157
rotator.h Executable file
View File

@ -0,0 +1,157 @@
/*---------------------- macros - don't touch these unless you know what you are doing ---------------------*/
#define AZ 1
#define EL 2
#define DIR_CCW 0x10 // CW Encoder Code (Do not change)
#define DIR_CW 0x20 // CCW Encoder Code (Do not change)
#define BRAKE_RELEASE_OFF 0
#define BRAKE_RELEASE_ON 1
//az_state
#define IDLE 0
#define SLOW_START_CW 1
#define SLOW_START_CCW 2
#define NORMAL_CW 3
#define NORMAL_CCW 4
#define SLOW_DOWN_CW 5
#define SLOW_DOWN_CCW 6
#define INITIALIZE_SLOW_START_CW 7
#define INITIALIZE_SLOW_START_CCW 8
#define INITIALIZE_TIMED_SLOW_DOWN_CW 9
#define INITIALIZE_TIMED_SLOW_DOWN_CCW 10
#define TIMED_SLOW_DOWN_CW 11
#define TIMED_SLOW_DOWN_CCW 12
#define INITIALIZE_DIR_CHANGE_TO_CW 13
#define INITIALIZE_DIR_CHANGE_TO_CCW 14
#define INITIALIZE_NORMAL_CW 15
#define INITIALIZE_NORMAL_CCW 16
//el_state
#define SLOW_START_UP 1
#define SLOW_START_DOWN 2
#define NORMAL_UP 3
#define NORMAL_DOWN 4
#define SLOW_DOWN_DOWN 5
#define SLOW_DOWN_UP 6
#define INITIALIZE_SLOW_START_UP 7
#define INITIALIZE_SLOW_START_DOWN 8
#define INITIALIZE_TIMED_SLOW_DOWN_UP 9
#define INITIALIZE_TIMED_SLOW_DOWN_DOWN 10
#define TIMED_SLOW_DOWN_UP 11
#define TIMED_SLOW_DOWN_DOWN 12
#define INITIALIZE_DIR_CHANGE_TO_UP 13
#define INITIALIZE_DIR_CHANGE_TO_DOWN 14
#define INITIALIZE_NORMAL_UP 15
#define INITIALIZE_NORMAL_DOWN 16
//az_request & el_request
#define REQUEST_STOP 0
#define REQUEST_AZIMUTH 1
#define REQUEST_AZIMUTH_RAW 2
#define REQUEST_CW 3
#define REQUEST_CCW 4
#define REQUEST_UP 5
#define REQUEST_DOWN 6
#define REQUEST_ELEVATION 7
#define REQUEST_KILL 8
#define DEACTIVATE 0
#define ACTIVATE 1
#define CW 1
#define CCW 2
#define STOP_AZ 3
#define STOP_EL 4
#define UP 5
#define DOWN 6
#define STOP 7
//az_request_queue_state & el_request_queue_state
#define NONE 0
#define IN_QUEUE 1
#define IN_PROGRESS_TIMED 2
#define IN_PROGRESS_TO_TARGET 3
#define EMPTY 0
#define LOADED_AZIMUTHS 1
#define RUNNING_AZIMUTHS 2
#define LOADED_AZIMUTHS_ELEVATIONS 3
#define RUNNING_AZIMUTHS_ELEVATIONS 4
#define RED 0x1
#define YELLOW 0x3
#define GREEN 0x2
#define TEAL 0x6
#define BLUE 0x4
#define VIOLET 0x5
#define WHITE 0x7
#define LCD_UNDEF 0
#define LCD_HEADING 1
#define LCD_IDLE_STATUS 2
#define LCD_TARGET_AZ 3
#define LCD_TARGET_EL 4
#define LCD_TARGET_AZ_EL 5
#define LCD_ROTATING_CW 6
#define LCD_ROTATING_CCW 7
#define LCD_ROTATING_TO 8
#define LCD_ELEVATING_TO 9
#define LCD_ELEVATING_UP 10
#define LCD_ELEVATING_DOWN 11
#define LCD_ROTATING_AZ_EL 12
#define LCD_PARKED 13
#define ENCODER_IDLE 0
#define ENCODER_AZ_PENDING 1
#define ENCODER_EL_PENDING 2
#define ENCODER_AZ_EL_PENDING 3
#define NOT_DOING_ANYTHING 0
#define ROTATING_CW 1
#define ROTATING_CCW 2
#define ROTATING_UP 3
#define ROTATING_DOWN 4
#define REMOTE_UNIT_NO_COMMAND 0
#define REMOTE_UNIT_AZ_COMMAND 1
#define REMOTE_UNIT_EL_COMMAND 2
#define REMOTE_UNIT_OTHER_COMMAND 3
#define REMOTE_UNIT_AW_COMMAND 4
#define REMOTE_UNIT_DHL_COMMAND 5
#define REMOTE_UNIT_DOI_COMMAND 6
#define REMOTE_UNIT_CL_COMMAND 7
#define NOT_PARKED 0
#define PARK_INITIATED 1
#define PARKED 2
#define COORDINATES 1
#define MAIDENHEAD 2
#define FREE_RUNNING 0
#define GPS_SYNC 1
#define RTC_SYNC 2
#define SLAVE_SYNC 3
#define CONTROL_PORT0 1
#define ETHERNET_PORT0 2
#define ETHERNET_PORT1 4
#define CLIENT_INACTIVE 0
#define CLIENT_ACTIVE 1
#define LEFT 1
#define RIGHT 2
#define STEPPER_UNDEF 0
#define STEPPER_CW 1
#define STEPPER_CCW 2
#define STEPPER_UP 3
#define STEPPER_DOWN 4
#define ETHERNET_SLAVE_DISCONNECTED 0
#define ETHERNET_SLAVE_CONNECTED 1
/* ------end of macros ------- */

118
rotator_dependencies.h Executable file
View File

@ -0,0 +1,118 @@
/* ---------------------- dependency checking - don't touch this unless you know what you are doing ---------------------*/
#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"
#endif
#if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) && defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
#error "You cannot active both FEATURE_MASTER_WITH_SERIAL_SLAVE and FEATURE_MASTER_WITH_ETHERNET_SLAVE"
#endif
#if defined(FEATURE_EL_POSITION_PULSE_INPUT) && !defined(FEATURE_ELEVATION_CONTROL)
#undef FEATURE_EL_POSITION_PULSE_INPUT
#endif
#if defined(FEATURE_REMOTE_UNIT_SLAVE) && (defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE))
#error "You cannot make this unit be both a master and a slave"
#endif
#if defined(FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT) && (defined(FEATURE_AZ_POSITION_POTENTIOMETER)||defined(FEATURE_AZ_POSITION_ROTARY_ENCODER)||defined(FEATURE_AZ_POSITION_PULSE_INPUT)||defined(FEATURE_AZ_POSITION_HMC5883L)||defined(FEATURE_AZ_POSITION_INCREMENTAL_ENCODER))
#error "You cannot get AZ position from remote unit and have a local azimuth sensor defined"
#endif
#if defined(FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT) && (defined(FEATURE_EL_POSITION_POTENTIOMETER)||defined(FEATURE_EL_POSITION_ROTARY_ENCODER)||defined(FEATURE_EL_POSITION_PULSE_INPUT)||defined(FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB)||defined(FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB)||defined(FEATURE_EL_POSITION_INCREMENTAL_ENCODER))
#error "You cannot get EL position from remote unit and have a local elevation sensor defined"
#endif
#if (defined(FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB) && defined(FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB))
#error "You must select only one one library for the ADXL345"
#endif
#if defined(FEATURE_REMOTE_UNIT_SLAVE) && defined(FEATURE_YAESU_EMULATION)
#error "You must turn off FEATURE_YAESU_EMULATION if using FEATURE_REMOTE_UNIT_SLAVE"
#endif
#if defined(FEATURE_REMOTE_UNIT_SLAVE) && defined(FEATURE_EASYCOM_EMULATION)
#error "You must turn off FEATURE_EASYCOM_EMULATION if using FEATURE_REMOTE_UNIT_SLAVE"
#endif
#if !defined(FEATURE_ELEVATION_CONTROL) && defined(FEATURE_EL_PRESET_ENCODER)
#undef FEATURE_EL_PRESET_ENCODER
#endif
#if !defined(FEATURE_AZ_POSITION_POTENTIOMETER) && !defined(FEATURE_AZ_POSITION_ROTARY_ENCODER) && !defined(FEATURE_AZ_POSITION_PULSE_INPUT) && !defined(FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT) && !defined(FEATURE_AZ_POSITION_HMC5883L) && !defined(FEATURE_AZ_POSITION_LSM303) && !defined(FEATURE_AZ_POSITION_HH12_AS5045_SSI) &&!defined(FEATURE_AZ_POSITION_INCREMENTAL_ENCODER)
#error "You must specify one AZ position sensor feature"
#endif
#if defined(FEATURE_ELEVATION_CONTROL) && !defined(FEATURE_EL_POSITION_POTENTIOMETER) && !defined(FEATURE_EL_POSITION_ROTARY_ENCODER) && !defined(FEATURE_EL_POSITION_PULSE_INPUT) && !defined(FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB) && !defined(FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB) && !defined(FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT) && !defined(FEATURE_EL_POSITION_LSM303) && !defined(FEATURE_EL_POSITION_HH12_AS5045_SSI) && !defined(FEATURE_EL_POSITION_INCREMENTAL_ENCODER) && !defined(FEATURE_EL_POSITION_MEMSIC_2125)
#error "You must specify one EL position sensor feature"
#endif
#if (defined(FEATURE_AZ_PRESET_ENCODER) || defined(FEATURE_EL_PRESET_ENCODER) || defined(FEATURE_AZ_POSITION_ROTARY_ENCODER) || defined(FEATURE_EL_POSITION_ROTARY_ENCODER)) && !defined(FEATURE_ROTARY_ENCODER_SUPPORT)
#define FEATURE_ROTARY_ENCODER_SUPPORT
#endif
#if defined(FEATURE_REMOTE_UNIT_SLAVE) && !defined(FEATURE_ONE_DECIMAL_PLACE_HEADINGS)
#define FEATURE_ONE_DECIMAL_PLACE_HEADINGS
#endif
#if defined(FEATURE_4_BIT_LCD_DISPLAY) || defined(FEATURE_I2C_LCD) || defined(FEATURE_ADAFRUIT_I2C_LCD) || defined(FEATURE_YOURDUINO_I2C_LCD) || defined(FEATURE_RFROBOT_I2C_DISPLAY)
#define FEATURE_LCD_DISPLAY
#endif
#if defined(FEATURE_ADAFRUIT_I2C_LCD) || defined(FEATURE_YOURDUINO_I2C_LCD) || defined(FEATURE_RFROBOT_I2C_DISPLAY)
#define FEATURE_I2C_LCD
#endif
#if defined(FEATURE_MOON_TRACKING) && !defined(FEATURE_ELEVATION_CONTROL)
#error "FEATURE_MOON_TRACKING requires FEATURE_ELEVATION_CONTROL"
#endif
#if (defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)) && !defined(FEATURE_CLOCK)
#error "FEATURE_MOON_TRACKING and FEATURE_SUN_TRACKING requires a clock feature to be activated"
#endif
#if defined(FEATURE_GPS) && !defined(FEATURE_CLOCK)
#define FEATURE_CLOCK
#endif
#if defined(FEATURE_ONE_DECIMAL_PLACE_HEADINGS) && defined(FEATURE_TWO_DECIMAL_PLACE_HEADINGS)
#error "You need to pick either FEATURE_ONE_DECIMAL_PLACE_HEADINGS or FEATURE_TWO_DECIMAL_PLACE_HEADINGS (or turn both off)"
#endif
#if defined(FEATURE_RTC_DS1307)|| defined(FEATURE_RTC_PCF8583)
#define FEATURE_RTC
#endif
#if defined(FEATURE_RTC_DS1307) || defined(FEATURE_RTC_PCF8583) || defined(FEATURE_I2C_LCD) || defined(FEATURE_AZ_POSITION_HMC5883L) || defined(FEATURE_EL_POSITION_LSM303) || defined(FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB) || defined(FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB)
#define FEATURE_WIRE_SUPPORT
#endif
#if defined(FEATURE_RTC_DS1307) && defined(FEATURE_RTC_PCF8583)
#error "You can't have two RTC features enabled!"
#endif
#if defined(FEATURE_REMOTE_UNIT_SLAVE) && defined(OPTION_SYNC_MASTER_CLOCK_TO_SLAVE)
#error "You can't define both FEATURE_REMOTE_UNIT_SLAVE and OPTION_SYNC_MASTER_CLOCK_TO_SLAVE - use OPTION_SYNC_MASTER_CLOCK_TO_SLAVE on the master unit"
#endif
#if defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE) && !defined(FEATURE_ETHERNET)
#error "FEATURE_MASTER_WITH_ETHERNET_SLAVE requires FEATURE_ETHERNET"
#endif
#if defined(HARDWARE_EA4TX_ARS_USB) && !defined(FEATURE_4_BIT_LCD_DISPLAY)
#define FEATURE_4_BIT_LCD_DISPLAY
#endif
#if defined(HARDWARE_EA4TX_ARS_USB) && defined(FEATURE_ELEVATION_CONTROL)
#define HACK_REDUCED_DEBUG
#endif

View File

@ -1,38 +1,72 @@
/* ---------------------- Features and Options - you must configure this !! ------------------------------------------------*/
/* ---------------------- Features and Options - you must configure this !! ------------------------------------------------
If you are using EA4TX ARS USB, edit rotator_features_ea4tx_ars_usb.h, not this file.
*/
/* main features */
//#define FEATURE_ELEVATION_CONTROL // uncomment this for AZ/EL rotators
#define FEATURE_YAESU_EMULATION // uncomment this for Yaesu GS-232A emulation
#define OPTION_GS_232B_EMULATION // uncomment this for GS-232B emulation (also uncomment FEATURE_YAESU_EMULATION above)
//#define FEATURE_EASYCOM_EMULATION // Easycom protocol emulation (undefine FEATURE_YAESU_EMULATION above)
//#define FEATURE_ROTATION_INDICATOR_PIN // activate pin (defined below) to indicate rotation
#define FEATURE_YAESU_EMULATION // uncomment this for Yaesu GS-232 emulation on control port
//#define FEATURE_EASYCOM_EMULATION // Easycom protocol emulation on control port (undefine FEATURE_YAESU_EMULATION above)
/* host and remote unit functionality */
//#define FEATURE_REMOTE_UNIT_SLAVE //uncomment this to make this unit a remote unit controlled by a host unit
//#define FEATURE_MOON_TRACKING
//#define FEATURE_SUN_TRACKING
//#define FEATURE_CLOCK
//#define FEATURE_GPS
//#define FEATURE_RTC_DS1307
//#define FEATURE_RTC_PCF8583
//#define FEATURE_ETHERNET
//#define FEATURE_STEPPER_MOTOR
//#define FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
#define LANGUAGE_ENGLISH
//#define LANGUAGE_SPANISH
/* master and remote slave unit functionality */
//#define FEATURE_REMOTE_UNIT_SLAVE // uncomment this to make this unit a remote unit controlled by a host unit
//#define FEATURE_MASTER_WITH_SERIAL_SLAVE // [master]{remote_port}<-------serial-------->{control_port}[slave]
//#define FEATURE_MASTER_WITH_ETHERNET_SLAVE // [master]<-------------------ethernet--------------------->[slave]
/* position sensors - pick one for azimuth and one for elevation if using an az/el rotator */
#define FEATURE_AZ_POSITION_POTENTIOMETER //this is used for both a voltage from a rotator control or a homebrew rotator with a potentiometer
//#define FEATURE_AZ_POSITION_ROTARY_ENCODER
//#define FEATURE_AZ_POSITION_PULSE_INPUT
//#define FEATURE_AZ_POSITION_HMC5883L // HMC5883L digital compass support (also uncomment object declaration below)
//#define FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT // requires an Arduino with Serial1 suppport (i.e. Arduino Mega); makes this unit a master
//#define FEATURE_AZ_POSITION_LSM303 // Uncomment for elevation using LSM303 magnetometer and Adafruit library (https://github.com/adafruit/Adafruit_LSM303) (also uncomment object declaration below)
//#define FEATURE_AZ_POSITION_HMC5883L // HMC5883L digital compass support
//#define FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT // requires FEATURE_MASTER_WITH_SERIAL_SLAVE or FEATURE_MASTER_WITH_ETHERNET_SLAVE
//#define FEATURE_AZ_POSITION_LSM303 // Uncomment for elevation using LSM303 magnetometer and Adafruit library (https://github.com/adafruit/Adafruit_LSM303) (also uncomment object declaration below)
//#define FEATURE_AZ_POSITION_HH12_AS5045_SSI
//#define FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
//#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 (also uncomment object declaration below)
//#define FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB // Uncomment for elevation ADXL345 accelerometer support using Adafruit library (also uncomment object declaration below)
//#define FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT // requires an Arduino with Serial1 suppport (i.e. Arduino Mega); makes this unit a master
//#define FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB // Uncomment for elevation ADXL345 accelerometer support using ADXL345 library
//#define FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB // Uncomment for elevation ADXL345 accelerometer support using Adafruit library
//#define FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT // requires FEATURE_MASTER_WITH_SERIAL_SLAVE or FEATURE_MASTER_WITH_ETHERNET_SLAVE
//#define FEATURE_EL_POSITION_LSM303 // Uncomment for elevation using LSM303 accelerometer and Adafruit library (https://github.com/adafruit/Adafruit_LSM303) (also uncomment object declaration below)
//#define FEATURE_EL_POSITION_HH12_AS5045_SSI
//#define FEATURE_EL_POSITION_INCREMENTAL_ENCODER
//#define FEATURE_EL_POSITION_MEMSIC_2125
//#define FEATURE_4_BIT_LCD_DISPLAY //Uncomment for classic 4 bit LCD display (most common)
//#define FEATURE_ADAFRUIT_I2C_LCD
//#define FEATURE_ADAFRUIT_BUTTONS // Uncomment this to use Adafruit I2C LCD buttons for manual AZ/EL instead of normal buttons
//#define FEATURE_YOURDUINO_I2C_LCD
//#define FEATURE_RFROBOT_I2C_DISPLAY
/* preset rotary encoder features and options */
//#define FEATURE_AZ_PRESET_ENCODER // Uncomment for Rotary Encoder Azimuth Preset support
//#define FEATURE_EL_PRESET_ENCODER // Uncomment for Rotary Encoder Elevation Preset support (requires FEATURE_AZ_PRESET_ENCODER above)
#define OPTION_ENCODER_HALF_STEP_MODE
#define OPTION_ENCODER_ENABLE_PULLUPS // define to enable weak pullups on rotary encoder pins
#define OPTION_INCREMENTAL_ENCODER_PULLUPS // define to enable weak pullups on 3 phase incremental rotary encoder pins
//#define OPTION_PRESET_ENCODER_RELATIVE_CHANGE // this makes the encoder(s) change the az or el in a relative fashion rather then store an absolute setting
#define OPTION_PRESET_ENCODER_0_360_DEGREES
/* position sensor options */
#define OPTION_AZ_POSITION_ROTARY_ENCODER_HARD_LIMIT // stop azimuth at lower and upper limit rather than rolling over
@ -42,16 +76,20 @@
#define OPTION_POSITION_PULSE_INPUT_PULLUPS // define to enable weak pullups on position pulse inputs
/* less often used features and options */
#define OPTION_GS_232B_EMULATION // comment this out to default to Yaesu GS-232A emulation when using FEATURE_YAESU_EMULATION above
//#define FEATURE_ROTATION_INDICATOR_PIN // activate rotation_indication_pin to indicate rotation
//#define FEATURE_LIMIT_SENSE
//#define FEATURE_TIMED_BUFFER // Support for Yaesu timed buffer commands
//#define OPTION_SERIAL_HELP_TEXT // Yaesu help command prints help
//#define FEATURE_PARK
//#define OPTION_AZ_MANUAL_ROTATE_LIMITS // this option will automatically stop the L and R commands when hitting a CCW or CW limit (settings below - AZ_MANUAL_ROTATE_*_LIMIT)
//#define OPTION_EL_MANUAL_ROTATE_LIMITS
//#define OPTION_EASYCOM_AZ_QUERY_COMMAND // Adds non-standard Easycom command: AZ with no parm returns current azimuth
//#define OPTION_EASYCOM_EL_QUERY_COMMAND // Adds non-standard Easycom command: EL with no parm returns current elevation
#define OPTION_EASYCOM_AZ_QUERY_COMMAND // Adds non-standard Easycom command: AZ with no parm returns current azimuth
#define OPTION_EASYCOM_EL_QUERY_COMMAND // Adds non-standard Easycom command: EL with no parm returns current elevation
//#define OPTION_C_COMMAND_SENDS_AZ_AND_EL // uncomment this when using Yaesu emulation with Ham Radio Deluxe
//#define OPTION_DELAY_C_CMD_OUTPUT // uncomment this when using Yaesu emulation with Ham Radio Deluxe
#define FEATURE_ONE_DECIMAL_PLACE_HEADINGS
//#define FEATURE_TWO_DECIMAL_PLACE_HEADINGS // under development - not working yet!
//#define FEATURE_AZIMUTH_CORRECTION // correct the azimuth using a calibration table below
//#define FEATURE_ELEVATION_CORRECTION // correct the elevation using a calibration table below
//#define FEATURE_ANCILLARY_PIN_CONTROL // control I/O pins with serial commands \F, \N, \P
@ -59,6 +97,27 @@
//#define OPTION_JOYSTICK_REVERSE_X_AXIS
//#define OPTION_JOYSTICK_REVERSE_Y_AXIS
#define OPTION_EL_SPEED_FOLLOWS_AZ_SPEED // changing the azimith speed with Yaesu X commands or an azimuth speed pot will also change elevation speed
//#define OPTION_PULSE_IGNORE_AMBIGUOUS_PULSES // for azimuth and elevation position pulse input feature, ignore pulses that arrive when no rotation is active
//#define OPTION_BUTTON_RELEASE_NO_SLOWDOWN // disables slowdown when CW or CCW button is released, or stop button is depressed
//#define OPTION_SYNC_RTC_TO_GPS // if both realtime clock and GPS are present, syncronize realtime clock to GPS
//#define OPTION_DISPLAY_HHMM_CLOCK // display HH:MM clock on LCD row 1 (set position with #define LCD_HHMM_CLOCK_POSITION)
//#define OPTION_DISPLAY_HHMMSS_CLOCK // display HH:MM:SS clock on LCD row 1 (set position with #define LCD_HHMMSS_CLOCK_POSITION)
//#define OPTION_DISPLAY_ALT_HHMM_CLOCK_AND_MAIDENHEAD // display alternating HH:MM clock and maidenhead on LCD row 1 (set position with #define LCD_HHMMCLOCK_POSITION)
//#define OPTION_DISPLAY_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD // display constant HH:MM:SS clock and maidenhead on LCD row 1 (set position with #define LCD_CONSTANT_HHMMSSCLOCK_MAIDENHEAD_POSITION)
//#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_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 FEATURE_POWER_SWITCH
//#define OPTION_EXTERNAL_ANALOG_REFERENCE //Activate external analog voltage reference (needed for RemoteQTH.com unit)
//#define OPTION_SYNC_MASTER_CLOCK_TO_SLAVE
//#define OPTION_DISABLE_HMC5883L_ERROR_CHECKING
/*
@ -74,33 +133,58 @@
#define DEFAULT_DEBUG_STATE 0 // this should be set to zero unless you're debugging something at startup
#define DEFAULT_DEBUG_STATE 0// this should be set to zero unless you're debugging something at startup
#define DEBUG_DUMP
// #define DEBUG_MEMORY
// #define DEBUG_BUTTONS
// #define DEBUG_SERIAL
// #define DEBUG_SERVICE_REQUEST_QUEUE
// #define DEBUG_EEPROM
// #define DEBUG_AZ_SPEED_POT
// #define DEBUG_AZ_PRESET_POT
// #define DEBUG_PRESET_ENCODERS
// #define DEBUG_AZ_MANUAL_ROTATE_LIMITS
// #define DEBUG_EL_MANUAL_ROTATE_LIMITS
// #define DEBUG_BRAKE
// #define DEBUG_OVERLAP
// #define DEBUG_DISPLAY
// #define DEBUG_AZ_CHECK_OPERATION_TIMEOUT
// #define DEBUG_TIMED_BUFFER
// #define DEBUG_EL_CHECK_OPERATION_TIMEOUT
// #define DEBUG_VARIABLE_OUTPUTS
// #define DEBUG_ROTATOR
// #define DEBUG_SUBMIT_REQUEST
// #define DEBUG_SERVICE_ROTATION
// #define DEBUG_POSITION_ROTARY_ENCODER
// #define DEBUG_PROFILE_LOOP_TIME
// #define DEBUG_POSITION_PULSE_INPUT
// #define DEBUG_ACCEL
// #define DEBUG_SVC_REMOTE_COMM_INCOMING_BUFFER
// #define DEBUG_SVC_REMOTE_COMM_INCOMING_BUFFER_BAD_DATA
// #define DEBUG_HEADING_READING_TIME
// #define DEBUG_JOYSTICK
// #define DEBUG_ROTATION_INDICATION_PIN
// #define DEBUG_HH12
// #define DEBUG_PARK
// #define DEBUG_LIMIT_SENSE
// #define DEBUG_AZ_POSITION_INCREMENTAL_ENCODER
// #define DEBUG_EL_POSITION_INCREMENTAL_ENCODER
// #define DEBUG_MOON_TRACKING
// #define DEBUG_SUN_TRACKING
// #define DEBUG_GPS
// #define DEBUG_GPS_SERIAL
// #define DEBUG_OFFSET
// #define DEBUG_RTC
// #define DEBUG_PROCESS_YAESU
// #define DEBUG_ETHERNET
// #define DEBUG_PROCESS_SLAVE
// #define DEBUG_MEMSIC_2125
// #define DEBUG_SYNC_MASTER_CLOCK_TO_SLAVE
// #define DEBUG_HMC5883L
//#define DEBUG_MEMORY
//#define DEBUG_BUTTONS
//#define DEBUG_SERIAL
//#define DEBUG_SERVICE_REQUEST_QUEUE
//#define DEBUG_EEPROM
//#define DEBUG_AZ_SPEED_POT
//#define DEBUG_AZ_PRESET_POT
//#define DEBUG_PRESET_ENCODERS
//#define DEBUG_AZ_MANUAL_ROTATE_LIMITS
//#define DEBUG_BRAKE
//#define DEBUG_OVERLAP
//#define DEBUG_DISPLAY
//#define DEBUG_AZ_CHECK_OPERATION_TIMEOUT
//#define DEBUG_TIMED_BUFFER
//#define DEBUG_EL_CHECK_OPERATION_TIMEOUT
//#define DEBUG_VARIABLE_OUTPUTS
//#define DEBUG_ROTATOR
//#define DEBUG_SUBMIT_REQUEST
//#define DEBUG_SERVICE_ROTATION
//#define DEBUG_POSITION_ROTARY_ENCODER
//#define DEBUG_PROFILE_LOOP_TIME
//#define DEBUG_POSITION_PULSE_INPUT
//#define DEBUG_ACCEL
//#define DEBUG_SVC_REMOTE_COMM_INCOMING_BUFFER
//#define DEBUG_HEADING_READING_TIME
//#define DEBUG_JOYSTICK
//#define DEBUG_ROTATION_INDICATION_PIN

View File

@ -0,0 +1,112 @@
/* ---------------------- EA4TX ARS USB Features and Options - you must configure this if using HARDWARE_EA4TX_ARS_USB !! ------------------------------------------------*/
/* main features */
//#define FEATURE_ELEVATION_CONTROL // uncomment this for AZ/EL rotators
#define FEATURE_YAESU_EMULATION // uncomment this for Yaesu GS-232 emulation on control port
//#define FEATURE_EASYCOM_EMULATION // Easycom protocol emulation on control port (undefine FEATURE_YAESU_EMULATION above)
#define LANGUAGE_ENGLISH
//#define LANGUAGE_SPANISH
#define FEATURE_AZ_POSITION_POTENTIOMETER //this is used for both a voltage from a rotator control or a homebrew rotator with a potentiometer
#define FEATURE_EL_POSITION_POTENTIOMETER
#define FEATURE_4_BIT_LCD_DISPLAY //Uncomment for classic 4 bit LCD display (most common)
/* less often used features and options */
#define OPTION_GS_232B_EMULATION // comment this out to default to Yaesu GS-232A emulation when using FEATURE_YAESU_EMULATION above
//#define FEATURE_ROTATION_INDICATOR_PIN // activate rotation_indication_pin to indicate rotation
//#define FEATURE_LIMIT_SENSE
//#define FEATURE_TIMED_BUFFER // Support for Yaesu timed buffer commands
//#define OPTION_SERIAL_HELP_TEXT // Yaesu help command prints help
//#define FEATURE_PARK
//#define OPTION_AZ_MANUAL_ROTATE_LIMITS // this option will automatically stop the L and R commands when hitting a CCW or CW limit (settings below - AZ_MANUAL_ROTATE_*_LIMIT)
//#define OPTION_EL_MANUAL_ROTATE_LIMITS
#define OPTION_EASYCOM_AZ_QUERY_COMMAND // Adds non-standard Easycom command: AZ with no parm returns current azimuth
#define OPTION_EASYCOM_EL_QUERY_COMMAND // Adds non-standard Easycom command: EL with no parm returns current elevation
//#define OPTION_C_COMMAND_SENDS_AZ_AND_EL // uncomment this when using Yaesu emulation with Ham Radio Deluxe
//#define OPTION_DELAY_C_CMD_OUTPUT // uncomment this when using Yaesu emulation with Ham Radio Deluxe
//#define FEATURE_ONE_DECIMAL_PLACE_HEADINGS
//#define FEATURE_AZIMUTH_CORRECTION // correct the azimuth using a calibration table below
//#define FEATURE_ELEVATION_CORRECTION // correct the elevation using a calibration table below
//#define FEATURE_ANCILLARY_PIN_CONTROL // control I/O pins with serial commands \F, \N, \P
//#define OPTION_EL_SPEED_FOLLOWS_AZ_SPEED // changing the azimith speed with Yaesu X commands or an azimuth speed pot will also change elevation speed
//#define OPTION_BUTTON_RELEASE_NO_SLOWDOWN // disables slowdown when CW or CCW button is released, or stop button is depressed
//#define FEATURE_POWER_SWITCH
//#define OPTION_EXTERNAL_ANALOG_REFERENCE //Activate external analog voltage reference (needed for RemoteQTH.com unit)
#define OPTION_DISPLAY_DIRECTION_STATUS
/*
Note:
Ham Radio Deluxe expects AZ and EL in output for Yaesu C command in AZ/EL mode. I'm not sure if this is default behavior for
the Yaesu interface since the C2 command is supposed to be for AZ and EL. If you have problems with other software with this code in AZ/EL mode,
uncomment #define OPTION_C_COMMAND_SENDS_AZ_AND_EL.
*/
/* ---------------------- debug stuff - don't touch unless you know what you are doing --------------------------- */
#define DEFAULT_DEBUG_STATE 0// this should be set to zero unless you're debugging something at startup
#define DEBUG_DUMP
#define DEBUG_MEMORY
// #define DEBUG_BUTTONS
// #define DEBUG_SERIAL
// #define DEBUG_SERVICE_REQUEST_QUEUE
// #define DEBUG_EEPROM
// #define DEBUG_AZ_SPEED_POT
// #define DEBUG_AZ_PRESET_POT
// #define DEBUG_PRESET_ENCODERS
// #define DEBUG_AZ_MANUAL_ROTATE_LIMITS
// #define DEBUG_EL_MANUAL_ROTATE_LIMITS
// #define DEBUG_BRAKE
// #define DEBUG_OVERLAP
// #define DEBUG_DISPLAY
// #define DEBUG_AZ_CHECK_OPERATION_TIMEOUT
// #define DEBUG_TIMED_BUFFER
// #define DEBUG_EL_CHECK_OPERATION_TIMEOUT
// #define DEBUG_VARIABLE_OUTPUTS
// #define DEBUG_ROTATOR
// #define DEBUG_SUBMIT_REQUEST
// #define DEBUG_SERVICE_ROTATION
// #define DEBUG_POSITION_ROTARY_ENCODER
// #define DEBUG_PROFILE_LOOP_TIME
// #define DEBUG_POSITION_PULSE_INPUT
// #define DEBUG_ACCEL
// #define DEBUG_SVC_REMOTE_COMM_INCOMING_BUFFER
// #define DEBUG_SVC_REMOTE_COMM_INCOMING_BUFFER_BAD_DATA
// #define DEBUG_HEADING_READING_TIME
// #define DEBUG_JOYSTICK
// #define DEBUG_ROTATION_INDICATION_PIN
// #define DEBUG_HH12
// #define DEBUG_PARK
// #define DEBUG_LIMIT_SENSE
// #define DEBUG_AZ_POSITION_INCREMENTAL_ENCODER
// #define DEBUG_EL_POSITION_INCREMENTAL_ENCODER
// #define DEBUG_MOON_TRACKING
// #define DEBUG_SUN_TRACKING
// #define DEBUG_GPS
// #define DEBUG_GPS_SERIAL
// #define DEBUG_OFFSET
// #define DEBUG_RTC
// #define DEBUG_PROCESS_YAESU
// #define DEBUG_ETHERNET
// #define DEBUG_PROCESS_SLAVE
// #define DEBUG_MEMSIC_2125
// #define DEBUG_SYNC_MASTER_CLOCK_TO_SLAVE

8
rotator_hardware.h Normal file
View File

@ -0,0 +1,8 @@
/* rotator_hardware.h
Uncomment defines below if you're specifically using any of this hardware
*/
//#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)

View File

@ -4,12 +4,15 @@
Most pins can be disabled by setting them to 0 (zero). If you're not using a pin or function, set it to 0.
Pins > 99 = remote unit pin, for example: pin 109 = pin 9 on remote unit, pin A0+100 = pin A0 on remote unit
*/
/* azimuth pins --------------------- (use just the azimuth pins for an azimuth-only rotator) */
#define rotate_cw 6 // goes high to activate rotator R (CW) rotation - pin 1 on Yaesu connector
#define rotate_ccw 7 // goes high to activate rotator L (CCW) rotation - pin 2 on Yaesu connector
#define rotate_ccw 7 // goes high to activate rotator L (CCW) rotation - pin 2 on Yaesu connector
#define rotate_cw_ccw 0 // goes high for both CW and CCW rotation
#define rotate_cw_pwm 0 // optional - PWM CW output - set to 0 to disable (must be PWM capable pin)
#define rotate_ccw_pwm 0 // optional - PWM CCW output - set to 0 to disable (must be PWM capable pin)
#define rotate_cw_ccw_pwm 0 // optional - PWM on CW and CCW output - set to 0 to disable (must be PWM capable pin)
@ -24,10 +27,13 @@
#define brake_az 0 // goes high to disengage azimuth brake (set to 0 to disable)
#define az_speed_pot 0 // connect to wiper of 1K to 10K potentiometer for speed control (set to 0 to disable)
#define az_preset_pot 0 // connect to wiper of 1K to 10K potentiometer for preset control (set to 0 to disable)
#define preset_start_button 0 // connect to momentary switch (ground on button press) for preset start (set to 0 to disable or for preset automatic start)
#define preset_start_button 0 // connect to momentary switch (ground on button press) for preset start (set to 0 to disable or for preset automatic start)
#define button_stop 0 // connect to momentary switch (ground on button press) for preset stop (set to 0 to disable or for preset automatic start)
#define rotation_indication_pin 0
#define blink_led 0
#define az_stepper_motor_pulse 44 //0
#define az_stepper_motor_direction 0
/*----------- elevation pins --------------*/
#ifdef FEATURE_ELEVATION_CONTROL
@ -36,14 +42,16 @@
#define rotate_up_or_down 0 // goes high when elevation up or down is activated
#define rotate_up_pwm 0 // optional - PWM UP output - set to 0 to disable (must be PWM capable pin)
#define rotate_down_pwm 0 // optional - PWM DOWN output - set to 0 to disable (must be PWM capable pin)
#define rotate_up_down_pwm 0 // optional - PWM on both UP and DOWN (must be PWM capable pin)
#define rotate_up_down_pwm 0 // optional - PWM on both UP and DOWN (must be PWM capable pin)
#define rotate_up_freq 0 // optional - UP variable frequency output
#define rotate_down_freq 0 // optional - UP variable frequency output
#define rotator_analog_el 0 //A1 // reads analog elevation voltage from rotator
#define rotator_analog_el A1 // reads analog elevation voltage from rotator
#define button_up 0 // normally open button to ground for manual up elevation
#define button_down 0 // normally open button to ground for manual down rotation
#define brake_el 0 // goes high to disengage elevation brake (set to 0 to disable)
#define elevation_speed_voltage 0 // optional - PWM output for speed control voltage feed into rotator (on continually unlike rotate_up_pwm and rotate_down_pwm)
#define el_stepper_motor_pulse 0
#define el_stepper_motor_direction 0
#endif //FEATURE_ELEVATION_CONTROL
// rotary encoder pins and options
@ -69,12 +77,12 @@
#ifdef FEATURE_AZ_POSITION_PULSE_INPUT
#define az_position_pulse_pin 0 // must be an interrupt capable pin!
#define AZ_POSITION_PULSE_PIN_INTERRUPT 0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
#define AZ_POSITION_PULSE_PIN_INTERRUPT 0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 ; Mega: pin 2 = interrupt 0, pin 3 = interrupt 1, pin 21 = interrupt 2, pin 20 = interrupt 3, pin 19 = interrupt 4, pin 18 = interrupt 5
#endif // read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
#ifdef FEATURE_EL_POSITION_PULSE_INPUT
#define el_position_pulse_pin 1 // must be an interrupt capable pin!
#define EL_POSITION_PULSE_PIN_INTERRUPT 1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
#define EL_POSITION_PULSE_PIN_INTERRUPT 1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 ; Mega: pin 2 = interrupt 0, pin 3 = interrupt 1, pin 21 = interrupt 2, pin 20 = interrupt 3, pin 19 = interrupt 4, pin 18 = interrupt 5
#endif // read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
#ifdef FEATURE_PARK
@ -95,4 +103,79 @@
#define pin_joystick_y A1
#endif //FEATURE_JOYSTICK_CONTROL
#ifdef FEATURE_AZ_POSITION_HH12_AS5045_SSI
#define az_hh12_clock_pin 11
#define az_hh12_cs_pin 12
#define az_hh12_data_pin 13
#endif //FEATURE_AZ_POSITION_HH_12
#ifdef FEATURE_EL_POSITION_HH12_AS5045_SSI
#define el_hh12_clock_pin 11
#define el_hh12_cs_pin 12
#define el_hh12_data_pin 13
#endif //FEATURE_EL_POSITION_HH_12
#ifdef FEATURE_PARK
#define park_in_progress_pin 0 // goes high when a park has been initiated and rotation is in progress
#define parked_pin 0 // goes high when in a parked position
#endif //FEATURE_PARK
#define heading_reading_inhibit_pin 0 // input - a high will cause the controller to suspend taking azimuth (and elevation) readings; use when RF interferes with sensors
#ifdef FEATURE_LIMIT_SENSE
#define az_limit_sense_pin 0 // input - low stops azimuthal rotation
#define el_limit_sense_pin 0 // input - low stops elevation rotation
#endif //FEATURE_LIMIT_SENSE
#ifdef FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
#define az_incremental_encoder_pin_phase_a 18 //3 must be an interrupt capable pin
#define az_incremental_encoder_pin_phase_b 19 //3 // must be an interrupt capable pin
#define az_incremental_encoder_pin_phase_z 22 //4
#define AZ_POSITION_INCREMENTAL_ENCODER_A_PIN_INTERRUPT 5 //0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 ; Mega: pin 2 = interrupt 0, pin 3 = interrupt 1, pin 21 = interrupt 2, pin 20 = interrupt 3, pin 19 = interrupt 4, pin 18 = interrupt 5
#define AZ_POSITION_INCREMENTAL_ENCODER_B_PIN_INTERRUPT 4 //1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 ; Mega: pin 2 = interrupt 0, pin 3 = interrupt 1, pin 21 = interrupt 2, pin 20 = interrupt 3, pin 19 = interrupt 4, pin 18 = interrupt 5
// read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
#endif //FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
#ifdef FEATURE_EL_POSITION_INCREMENTAL_ENCODER
#define el_incremental_encoder_pin_phase_a 18 //2 // must be an interrupt capable pin
#define el_incremental_encoder_pin_phase_b 19 //3 // must be an interrupt capable pin
#define el_incremental_encoder_pin_phase_z 22 //4
#define EL_POSITION_INCREMENTAL_ENCODER_A_PIN_INTERRUPT 5 //0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 ; Mega: pin 2 = interrupt 0, pin 3 = interrupt 1, pin 21 = interrupt 2, pin 20 = interrupt 3, pin 19 = interrupt 4, pin 18 = interrupt 5
#define EL_POSITION_INCREMENTAL_ENCODER_B_PIN_INTERRUPT 4 //1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 ; Mega: pin 2 = interrupt 0, pin 3 = interrupt 1, pin 21 = interrupt 2, pin 20 = interrupt 3, pin 19 = interrupt 4, pin 18 = interrupt 5
// read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
#endif //FEATURE_EL_POSITION_INCREMENTAL_ENCODER
#ifdef FEATURE_YOURDUINO_I2C_LCD
#define En_pin 2
#define Rw_pin 1
#define Rs_pin 0
#define D4_pin 4
#define D5_pin 5
#define D6_pin 6
#define D7_pin 7
#endif //FEATURE_YOURDUINO_I2C_LCD
#ifdef FEATURE_MOON_TRACKING
#define moon_tracking_active_pin 0 // goes high when moon tracking is active
#define moon_tracking_activate_line 0 // ground this pin to activate moon tracking (not for use with a button)
#define moon_tracking_button 0 // use with a normally open momentary switch to ground
#endif //FEATURE_MOON_TRACKING
#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
#endif //FEATURE_SUN_TRACKING
#ifdef FEATURE_GPS
#define gps_sync 0
#endif //FEATURE_GPS
#ifdef FEATURE_POWER_SWITCH
#define power_switch 0 // use with FEATURE_POWER_SWITCH
#endif //FEATURE_POWER_SWITCH
#ifdef FEATURE_EL_POSITION_MEMSIC_2125
#define pin_memsic_2125_x 0
#define pin_memsic_2125_y 0
#endif //FEATURE_EL_POSITION_MEMSIC_2125

View File

@ -0,0 +1,87 @@
/*
EA4TX ARS-USB Pin Definitions
*/
/* azimuth pins --------------------- (use just the azimuth pins for an azimuth-only rotator) */
#define rotate_cw 6 // goes high to activate rotator R (CW) rotation - pin 1 on Yaesu connector
#define rotate_ccw 7 // goes high to activate rotator L (CCW) rotation - pin 2 on Yaesu connector
#define button_cw A2 // normally open button to ground for manual CW rotation (schematic pin: A1)
#define button_ccw A3 // normally open button to ground for manual CCW rotation (schematic pin: A2)
#define serial_led 0 // LED blinks when command is received on serial port (set to 0 to disable)
#define rotator_analog_az A0 // reads analog azimuth voltage from rotator - pin 4 on Yaesu connector
#define brake_az 0 // goes high to disengage azimuth brake (set to 0 to disable)
#define button_stop 0 // connect to momentary switch (ground on button press) for preset stop (set to 0 to disable or for preset automatic start)
/*----------- elevation pins --------------*/
#ifdef FEATURE_ELEVATION_CONTROL
#define rotate_up 8 // goes high to activate rotator elevation up
#define rotate_down 9 // goes high to activate rotator elevation down
#define rotator_analog_el A1 // reads analog elevation voltage from rotator
#define button_up A4 // normally open button to ground for manual up elevation
#define button_down A5 // normally open button to ground for manual down rotation
#define brake_el 0 // goes high to disengage elevation brake (set to 0 to disable)
#endif //FEATURE_ELEVATION_CONTROL
//classic 4 bit LCD pins
#define lcd_4_bit_rs_pin 12
#define lcd_4_bit_enable_pin 11
#define lcd_4_bit_d4_pin 5
#define lcd_4_bit_d5_pin 4
#define lcd_4_bit_d6_pin 3
#define lcd_4_bit_d7_pin 2
// everything below this line is unused
#ifdef FEATURE_PARK
#define button_park 0
#endif
#ifdef FEATURE_PARK
#define park_in_progress_pin 0 // goes high when a park has been initiated and rotation is in progress
#define parked_pin 0 // goes high when in a parked position
#endif //FEATURE_PARK
#define heading_reading_inhibit_pin 0 // input - a high will cause the controller to suspend taking azimuth (and elevation) readings; use when RF interferes with sensors
#ifdef FEATURE_LIMIT_SENSE
#define az_limit_sense_pin 0 // input - low stops azimuthal rotation
#define el_limit_sense_pin 0 // input - low stops elevation rotation
#endif //FEATURE_LIMIT_SENSE
#ifdef FEATURE_POWER_SWITCH
#define power_switch 0 // use with FEATURE_POWER_SWITCH
#endif //FEATURE_POWER_SWITCH
#define rotate_cw_ccw 0 // goes high for both CW and CCW rotation
#define rotate_cw_pwm 0 // optional - PWM CW output - set to 0 to disable (must be PWM capable pin)
#define rotate_ccw_pwm 0 // optional - PWM CCW output - set to 0 to disable (must be PWM capable pin)
#define rotate_cw_ccw_pwm 0 // optional - PWM on CW and CCW output - set to 0 to disable (must be PWM capable pin)
#define rotate_cw_freq 0 // optional - CW variable frequency output
#define rotate_ccw_freq 0 // optional - CCW variable frequency output
#define az_speed_pot 0 // connect to wiper of 1K to 10K potentiometer for speed control (set to 0 to disable)
#define az_preset_pot 0 // connect to wiper of 1K to 10K potentiometer for preset control (set to 0 to disable)
#define rotate_up_or_down 0 // goes high when elevation up or down is activated
#define rotate_up_pwm 0 // optional - PWM UP output - set to 0 to disable (must be PWM capable pin)
#define rotate_down_pwm 0 // optional - PWM DOWN output - set to 0 to disable (must be PWM capable pin)
#define rotate_up_down_pwm 0 // optional - PWM on both UP and DOWN (must be PWM capable pin)
#define rotate_up_freq 0 // optional - UP variable frequency output
#define rotate_down_freq 0 // optional - UP variable frequency output
#define az_stepper_motor_pulse 0
#define az_stepper_motor_direction 0
#define rotation_indication_pin 0
#define blink_led 0
#define elevation_speed_voltage 0 // optional - PWM output for speed control voltage feed into rotator (on continually unlike rotate_up_pwm and rotate_down_pwm)
#define el_stepper_motor_pulse 0
#define el_stepper_motor_direction 0
#define azimuth_speed_voltage 0 // optional - PWM output for speed control voltage feed into rotator (on continually unlike rotate_cw_pwm and rotate_ccw_pwm)
#define overlap_led 0 // line goes high when azimuth rotator is in overlap (> 360 rotators)
#define preset_start_button 0 // connect to momentary switch (ground on button press) for preset start (set to 0 to disable or for preset automatic start)

169
rotator_pins_k3ng_g1000.h Executable file
View File

@ -0,0 +1,169 @@
/* ------------------------------------- Pin Definitions ------------------------------------------
You need to look at these and set them appropriately !
Most pins can be disabled by setting them to 0 (zero). If you're not using a pin or function, set it to 0.
Pins > 99 = remote unit pin, for example: pin 109 = pin 9 on remote unit, pin A0+100 = pin A0 on remote unit
*/
/* azimuth pins --------------------- (use just the azimuth pins for an azimuth-only rotator) */
// alternate pinouts for K3NG's personal setup
#define rotate_cw A2 // goes high to activate rotator R (CW) rotation - pin 1 on Yaesu connector
#define rotate_ccw A1 // goes high to activate rotator L (CCW) rotation - pin 2 on Yaesu connector
#define button_cw 0
#define button_ccw 0
#define rotate_cw_pwm 0 // optional - PWM CW output - set to 0 to disable (must be PWM capable pin)
#define rotate_ccw_pwm 0 // optional - PWM CCW output - set to 0 to disable (must be PWM capable pin)
#define rotate_cw_ccw_pwm 0 // optional - PWM on CW and CCW output - set to 0 to disable (must be PWM capable pin)
#define rotate_cw_freq 0 // optional - CW variable frequency output
#define rotate_ccw_freq 0 // optional - CCW variable frequency output
#define button_cw 0 // normally open button to ground for manual CW rotation (schematic pin: A1)
#define button_ccw 0 // normally open button to ground for manual CCW rotation (schematic pin: A2)
#define serial_led 0 // LED blinks when command is received on serial port (set to 0 to disable)
#define rotator_analog_az A0 // reads analog azimuth voltage from rotator - pin 4 on Yaesu connector
#define azimuth_speed_voltage 0 // optional - PWM output for speed control voltage feed into rotator (on continually unlike rotate_cw_pwm and rotate_ccw_pwm)
#define overlap_led 0 // line goes high when azimuth rotator is in overlap (> 360 rotators)
#define brake_az 0 // goes high to disengage azimuth brake (set to 0 to disable)
#define az_speed_pot 0 // connect to wiper of 1K to 10K potentiometer for speed control (set to 0 to disable)
#define az_preset_pot 0 // connect to wiper of 1K to 10K potentiometer for preset control (set to 0 to disable)
#define preset_start_button 0 // connect to momentary switch (ground on button press) for preset start (set to 0 to disable or for preset automatic start)
#define button_stop 0 // connect to momentary switch (ground on button press) for preset stop (set to 0 to disable or for preset automatic start)
#define rotation_indication_pin 0
#define blink_led 0
/*----------- elevation pins --------------*/
#ifdef FEATURE_ELEVATION_CONTROL
#define rotate_up 8 // goes high to activate rotator elevation up
#define rotate_down 9 // goes high to activate rotator elevation down
#define rotate_up_or_down 0 // goes high when elevation up or down is activated
#define rotate_up_pwm 0 // optional - PWM UP output - set to 0 to disable (must be PWM capable pin)
#define rotate_down_pwm 0 // optional - PWM DOWN output - set to 0 to disable (must be PWM capable pin)
#define rotate_up_down_pwm 0 // optional - PWM on both UP and DOWN (must be PWM capable pin)
#define rotate_up_freq 0 // optional - UP variable frequency output
#define rotate_down_freq 0 // optional - UP variable frequency output
#define rotator_analog_el 0 //A1 // reads analog elevation voltage from rotator
#define button_up 0 // normally open button to ground for manual up elevation
#define button_down 0 // normally open button to ground for manual down rotation
#define brake_el 0 // goes high to disengage elevation brake (set to 0 to disable)
#define elevation_speed_voltage 0 // optional - PWM output for speed control voltage feed into rotator (on continually unlike rotate_up_pwm and rotate_down_pwm)
#endif //FEATURE_ELEVATION_CONTROL
// rotary encoder pins and options
#ifdef FEATURE_AZ_PRESET_ENCODER
#define az_rotary_preset_pin1 0 // CW Encoder Pin
#define az_rotary_preset_pin2 0 // CCW Encoder Pin
#endif //FEATURE_AZ_PRESET_ENCODER
#ifdef FEATURE_EL_PRESET_ENCODER
#define el_rotary_preset_pin1 0 // UP Encoder Pin
#define el_rotary_preset_pin2 0 // DOWN Encoder Pin
#endif //FEATURE_EL_PRESET_ENCODER
#ifdef FEATURE_AZ_POSITION_ROTARY_ENCODER
#define az_rotary_position_pin1 0 // CW Encoder Pin
#define az_rotary_position_pin2 0 // CCW Encoder Pin
#endif //FEATURE_AZ_POSITION_ROTARY_ENCODER
#ifdef FEATURE_EL_POSITION_ROTARY_ENCODER
#define el_rotary_position_pin1 0 // CW Encoder Pin
#define el_rotary_position_pin2 0 // CCW Encoder Pin
#endif //FEATURE_EL_POSITION_ROTARY_ENCODER
#ifdef FEATURE_AZ_POSITION_PULSE_INPUT
#define az_position_pulse_pin 0 // must be an interrupt capable pin!
#define AZ_POSITION_PULSE_PIN_INTERRUPT 0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
#endif // read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
#ifdef FEATURE_EL_POSITION_PULSE_INPUT
#define el_position_pulse_pin 1 // must be an interrupt capable pin!
#define EL_POSITION_PULSE_PIN_INTERRUPT 1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
#endif // read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
#ifdef FEATURE_PARK
#define button_park 0
#endif
//classic 4 bit LCD pins
#define lcd_4_bit_rs_pin 12
#define lcd_4_bit_enable_pin 11
#define lcd_4_bit_d4_pin 5
#define lcd_4_bit_d5_pin 4
#define lcd_4_bit_d6_pin 3
#define lcd_4_bit_d7_pin 2
#ifdef FEATURE_JOYSTICK_CONTROL
#define pin_joystick_x A0
#define pin_joystick_y A1
#endif //FEATURE_JOYSTICK_CONTROL
#ifdef FEATURE_AZ_POSITION_HH12_AS5045_SSI
#define az_hh12_clock_pin 11
#define az_hh12_cs_pin 12
#define az_hh12_data_pin 13
#endif //FEATURE_AZ_POSITION_HH_12
#ifdef FEATURE_EL_POSITION_HH12_AS5045_SSI
#define el_hh12_clock_pin 11
#define el_hh12_cs_pin 12
#define el_hh12_data_pin 13
#endif //FEATURE_EL_POSITION_HH_12
#ifdef FEATURE_PARK
#define park_in_progress_pin 0 // goes high when a park has been initiated and rotation is in progress
#define parked_pin 0 // goes high when in a parked position
#endif //FEATURE_PARK
#define heading_reading_inhibit_pin 0 // input - a high will cause the controller to suspend taking azimuth (and elevation) readings; use when RF interferes with sensors
#ifdef FEATURE_LIMIT_SENSE
#define az_limit_sense_pin 0 // input - low stops azimuthal rotation
#define el_limit_sense_pin 0 // input - low stops elevation rotation
#endif //FEATURE_LIMIT_SENSE
#ifdef FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
#define az_incremental_encoder_pin_phase_a 2 // must be an interrupt capable pin
#define az_incremental_encoder_pin_phase_b 3 // must be an interrupt capable pin
#define az_incremental_encoder_pin_phase_z 4
#define AZ_POSITION_INCREMENTAL_ENCODER_A_PIN_INTERRUPT 0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
#define AZ_POSITION_INCREMENTAL_ENCODER_B_PIN_INTERRUPT 1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
// read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
#endif //FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
#ifdef FEATURE_EL_POSITION_INCREMENTAL_ENCODER
#define el_incremental_encoder_pin_phase_a 2 // must be an interrupt capable pin
#define el_incremental_encoder_pin_phase_b 3 // must be an interrupt capable pin
#define el_incremental_encoder_pin_phase_z 4
#define EL_POSITION_INCREMENTAL_ENCODER_A_PIN_INTERRUPT 0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
#define EL_POSITION_INCREMENTAL_ENCODER_B_PIN_INTERRUPT 1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
// read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
#endif //FEATURE_EL_POSITION_INCREMENTAL_ENCODER
#ifdef FEATURE_YOURDUINO_I2C_LCD
#define En_pin 2
#define Rw_pin 1
#define Rs_pin 0
#define D4_pin 4
#define D5_pin 5
#define D6_pin 6
#define D7_pin 7
#endif //FEATURE_YOURDUINO_I2C_LCD
#ifdef FEATURE_MOON_TRACKING
#define moon_tracking_active_pin 0 // goes high when moon tracking is active
#define moon_tracking_activate_line 0 // ground this pin to activate moon tracking (not for use with a button)
#define moon_tracking_button 0 // use with a normally open momentary switch to ground
#endif //FEATURE_MOON_TRACKING
#ifdef FEATURE_SUN_TRACKING
#define sun_tracking_active_pin 13 // 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 30 // use with a normally open momentary switch to ground
#endif //FEATURE_SUN_TRACKING
#ifdef FEATURE_GPS
#define gps_sync 0
#endif //FEATURE_GPS

182
rotator_pins_m0upu.h Normal file
View File

@ -0,0 +1,182 @@
/* LEDs left to right
6 - PWM
7 - NO PWM
8 - NO PWM
9 - PWM
*/
#define pins_h
#define rotate_cw 6 // goes high to activate rotator R (CW) rotation - pin 1 on Yaesu connector
#define rotate_ccw 7 // goes high to activate rotator L (CCW) rotation - pin 2 on Yaesu connector
#define rotate_cw_ccw 0 // goes high for both CW and CCW rotation
#define rotate_cw_pwm 0 // optional - PWM CW output - set to 0 to disable (must be PWM capable pin)
#define rotate_ccw_pwm 0 // optional - PWM CCW output - set to 0 to disable (must be PWM capable pin)
#define rotate_cw_ccw_pwm 0
#define rotate_cw_freq 0
#define rotate_ccw_freq 0
#define button_cw 0 //A1 // normally open button to ground for manual CW rotation
#define button_ccw 0 //A2 // normally open button to ground for manual CCW rotation
#define serial_led 13 //0 // LED blinks when command is received on serial port (set to 0 to disable)
#define rotator_analog_az A0 // reads analog azimuth voltage from rotator - pin 4 on Yaesu connector
#define azimuth_speed_voltage 0 // optional - PWM output for speed control voltage feed into rotator (on continually unlike rotate_cw_pwm and rotate_ccw_pwm)
#define overlap_led 0 // line goes high when azimuth rotator is in overlap (> 360 rotators)
#define brake_az 13 //0 // goes high to disengage azimuth brake (set to 0 to disable)
#define az_speed_pot 0 //A4 // connect to wiper of 1K to 10K potentiometer for speed control (set to 0 to disable)
#define az_preset_pot 0 // connect to wiper of 1K to 10K potentiometer for preset control (set to 0 to disable)
#define preset_start_button 0 //10 // connect to momentary switch (ground on button press) for preset start (set to 0 to disable or for preset automatic start)
#define button_stop 0 // connect to momentary switch (ground on button press) for preset stop (set to 0 to disable or for preset automatic start)
#define rotation_indication_pin 0
#define az_stepper_motor_pulse 0
#define az_stepper_motor_direction 0
// elevation pins
#ifdef FEATURE_ELEVATION_CONTROL
#define elevation_speed_voltage 0 // optional - PWM output for speed control voltage feed into rotator (on continually unlike rotate_up_pwm and rotate_down_pwm)
#define rotate_up 9//9 // goes high to activate rotator elevation up
#define rotate_down 8 // goes high to activate rotator elevation down
#define rotate_up_or_down 0
#define rotate_up_pwm 0
#define rotate_down_pwm 0
#define rotate_up_down_pwm 0
#define rotate_up_freq 0
#define rotate_down_freq 0
#define rotator_analog_el A1 // reads analog elevation voltage from rotator
#define button_up 0 // normally open button to ground for manual up elevation
#define button_down 0 // normally open button to ground for manual down rotation
#define brake_el 0 // goes high to disengage elevation brake (set to 0 to disable)
#define el_stepper_motor_pulse 0
#define el_stepper_motor_direction 0
#endif //FEATURE_ELEVATION_CONTROL
// rotary encoder pins and options
#ifdef FEATURE_AZ_PRESET_ENCODER
#define az_rotary_preset_pin1 A3 //6 // CW Encoder Pin
#define az_rotary_preset_pin2 A2 //7 // CCW Encoder Pin
#endif //FEATURE_AZ_PRESET_ENCODER
#ifdef FEATURE_EL_PRESET_ENCODER
#define el_rotary_preset_pin1 0 // A3 //6 // UP Encoder Pin
#define el_rotary_preset_pin2 0 // A2 //7 // DOWN Encoder Pin
#endif //FEATURE_EL_PRESET_ENCODER
#ifdef FEATURE_AZ_POSITION_ROTARY_ENCODER
#define az_rotary_position_pin1 A3 // CW Encoder Pin
#define az_rotary_position_pin2 A2 // CCW Encoder Pin
#endif //FEATURE_AZ_POSITION_ROTARY_ENCODER
#ifdef FEATURE_EL_POSITION_ROTARY_ENCODER
#define el_rotary_position_pin1 0 // CW Encoder Pin
#define el_rotary_position_pin2 0 // CCW Encoder Pin
#endif //FEATURE_EL_POSITION_ROTARY_ENCODER
#ifdef FEATURE_AZ_POSITION_PULSE_INPUT
#define az_position_pulse_pin 0 // must be an interrupt capable pin!
#define AZ_POSITION_PULSE_PIN_INTERRUPT 0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
#endif // read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
#ifdef FEATURE_EL_POSITION_PULSE_INPUT
#define el_position_pulse_pin 0 // must be an interrupt capable pin!
#define EL_POSITION_PULSE_PIN_INTERRUPT 1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
#endif // read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
#ifdef FEATURE_PARK
#define button_park 0
#endif
#define lcd_4_bit_rs_pin 12
#define lcd_4_bit_enable_pin 11
#define lcd_4_bit_d4_pin 5
#define lcd_4_bit_d5_pin 4
#define lcd_4_bit_d6_pin 3
#define lcd_4_bit_d7_pin 2
#ifdef FEATURE_JOYSTICK_CONTROL
#define pin_joystick_x A2
#define pin_joystick_y A3
#endif //FEATURE_JOYSTICK_CONTROL
#define blink_led 0 //13
#ifdef FEATURE_AZ_POSITION_HH12_AS5045_SSI
#define az_hh12_clock_pin 11
#define az_hh12_cs_pin 12
#define az_hh12_data_pin 13
#endif //FEATURE_AZ_POSITION_HH_12
#ifdef FEATURE_EL_POSITION_HH12_AS5045_SSI
#define el_hh12_clock_pin 11
#define el_hh12_cs_pin 12
#define el_hh12_data_pin 13
#endif //FEATURE_EL_POSITION_HH_12
#ifdef FEATURE_PARK
#define park_in_progress_pin 0 // goes high when a park has been initiated and rotation is in progress
#define parked_pin 0 // goes high when in a parked position
#endif //FEATURE_PARK
#define heading_reading_inhibit_pin 0 // input - a high will cause the controller to suspend taking azimuth (and elevation) readings; use when RF interferes with sensors
#ifdef FEATURE_LIMIT_SENSE
#define az_limit_sense_pin 0 // input - low stops azimuthal rotation
#define el_limit_sense_pin 0 // input - low stops elevation rotation
#endif //FEATURE_LIMIT_SENSE
#ifdef FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
#define az_3_phase_encoder_pin_phase_a 2 // must be an interrupt capable pin
#define az_3_phase_encoder_pin_phase_b 3 // must be an interrupt capable pin
#define az_3_phase_encoder_pin_phase_z 4
#define AZ_POSITION_3_PHASE_INCREMENTAL_ENCODER_A_PIN_INTERRUPT 0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
#define AZ_POSITION_3_PHASE_INCREMENTAL_ENCODER_B_PIN_INTERRUPT 1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
// read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
#endif //FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
#ifdef FEATURE_EL_POSITION_INCREMENTAL_ENCODER
#define el_3_phase_encoder_pin_phase_a 2 // must be an interrupt capable pin
#define el_3_phase_encoder_pin_phase_b 3 // must be an interrupt capable pin
#define el_3_phase_encoder_pin_phase_z 4
#define EL_POSITION_3_PHASE_INCREMENTAL_ENCODER_A_PIN_INTERRUPT 0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
#define EL_POSITION_3_PHASE_INCREMENTAL_ENCODER_B_PIN_INTERRUPT 1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1
// read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
#endif //FEATURE_EL_POSITION_INCREMENTAL_ENCODER
#ifdef FEATURE_YOURDUINO_I2C_LCD
#define En_pin 2
#define Rw_pin 1
#define Rs_pin 0
#define D4_pin 4
#define D5_pin 5
#define D6_pin 6
#define D7_pin 7
#endif //FEATURE_YOURDUINO_I2C_LCD
#ifdef FEATURE_MOON_TRACKING
#define moon_tracking_active_pin 0 // goes high when moon tracking is active
#define moon_tracking_activate_line 0 // ground this pin to activate moon tracking (not for use with a button)
#define moon_tracking_button 0 // use with a normally open momentary switch to ground
#endif //FEATURE_MOON_TRACKING
#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
#endif //FEATURE_SUN_TRACKING
#ifdef FEATURE_GPS
#define gps_sync 0
#endif //FEATURE_GPS
#ifdef FEATURE_POWER_SWITCH
#define power_switch 0 // use with FEATURE_POWER_SWITCH
#endif //FEATURE_POWER_SWITCH
#ifdef FEATURE_EL_POSITION_MEMSIC_2125
#define pin_memsic_2125_x 0
#define pin_memsic_2125_y 0
#endif //FEATURE_EL_POSITION_MEMSIC_2125

422
rotator_settings.h Executable file
View File

@ -0,0 +1,422 @@
/* -------------------------- rotation settings ---------------------------------------*/
#define AZIMUTH_STARTING_POINT_DEFAULT 180 // the starting point in degrees of the azimuthal rotator
#define AZIMUTH_ROTATION_CAPABILITY_DEFAULT 450 // the default rotation capability of the rotator in degrees
#define ELEVATION_MAXIMUM_DEGREES 180 // change this to set the maximum elevation in degrees
/* --------------------------- Settings ------------------------------------------------
You can tweak these, but read the online documentation!
*/
// analog voltage calibration - these are default values; you can either tweak these or set via the Yaesu O and F commands (and O2 and F2)....
#define ANALOG_AZ_FULL_CCW 4
#define ANALOG_AZ_FULL_CW 1009
#define ANALOG_EL_0_DEGREES 2
#define ANALOG_EL_MAX_ELEVATION 1018 // maximum elevation is normally 180 degrees unless change below for ELEVATION_MAXIMUM_DEGREES
#define ANALOG_AZ_OVERLAP_DEGREES 540 // if overlap_led above is enabled, turn on overlap led line if azimuth is greater than this setting
// you must use raw azimuth (if the azimuth on the rotator crosses over to 0 degrees, add 360
// for example, on a Yaesu 450 degree rotator with a starting point of 180 degrees, and an overlap LED
// turning on when going CW and crossing 180, ANALOG_AZ_OVERLAP_DEGREES should be set for 540 (180 + 360)
// PWM speed voltage settings
#define PWM_SPEED_VOLTAGE_X1 64
#define PWM_SPEED_VOLTAGE_X2 128
#define PWM_SPEED_VOLTAGE_X3 191
#define PWM_SPEED_VOLTAGE_X4 253
//AZ
#define AZ_SLOWSTART_DEFAULT 0 // 0 = off ; 1 = on
#define AZ_SLOWDOWN_DEFAULT 0 // 0 = off ; 1 = on
#define AZ_SLOW_START_UP_TIME 2000 // if slow start is enabled, the unit will ramp up speed for this many milliseconds
#define AZ_SLOW_START_STARTING_PWM 1 // PWM starting value for slow start (must be < 256)
#define AZ_SLOW_START_STEPS 20 // must be < 256
#define SLOW_DOWN_BEFORE_TARGET_AZ 10.0 // if slow down is enabled, slowdown will be activated within this many degrees of target azimuth
#define AZ_SLOW_DOWN_PWM_START 200 // starting PWM value for slow down (must be < 256)
#define AZ_SLOW_DOWN_PWM_STOP 20 // ending PWM value for slow down (must be < 256)
#define AZ_SLOW_DOWN_STEPS 200 //20 // must be < 256
#define AZ_INITIALLY_IN_SLOW_DOWN_PWM 50 // PWM value to start at if we're starting in the slow down zone (1 - 255)
//EL
#define EL_SLOWSTART_DEFAULT 0 // 0 = off ; 1 = on
#define EL_SLOWDOWN_DEFAULT 0 // 0 = off ; 1 = on
#define EL_SLOW_START_UP_TIME 2000 // if slow start is enabled, the unit will ramp up speed for this many milliseconds
#define EL_SLOW_START_STARTING_PWM 1 // PWM starting value for slow start (must be < 256)
#define EL_SLOW_START_STEPS 20 // must be < 256
#define SLOW_DOWN_BEFORE_TARGET_EL 10.0 // if slow down is enabled, slowdown will be activated within this many degrees of target azimuth
#define EL_SLOW_DOWN_PWM_START 200 // starting PWM value for slow down
#define EL_SLOW_DOWN_PWM_STOP 20 // ending PWM value for slow down
#define EL_SLOW_DOWN_STEPS 20
#define EL_INITIALLY_IN_SLOW_DOWN_PWM 50 // PWM value to start at if we're starting in the slow down zone (1 - 255)
#define TIMED_SLOW_DOWN_TIME 2000
//Variable frequency output settings - LOWEST FREQUENCY IS 31 HERTZ DUE TO ARDUINO tone() FUNCTION LIMITATIONS!
#define AZ_VARIABLE_FREQ_OUTPUT_LOW 31 // Frequency in hertz of minimum speed
#define AZ_VARIABLE_FREQ_OUTPUT_HIGH 5000 //100 // Frequency in hertz of maximum speed
#define EL_VARIABLE_FREQ_OUTPUT_LOW 31 // Frequency in hertz of minimum speed
#define EL_VARIABLE_FREQ_OUTPUT_HIGH 100 // Frequency in hertz of maximum speed
// Settings for OPTION_AZ_MANUAL_ROTATE_LIMITS
#define AZ_MANUAL_ROTATE_CCW_LIMIT 0 // if using a rotator that starts at 180 degrees, set this to something like 185
#define AZ_MANUAL_ROTATE_CW_LIMIT 535 // add 360 to this if you go past 0 degrees (i.e. 180 CW after 0 degrees = 540)
// Settings for OPTION_EL_MANUAL_ROTATE_LIMITS
#define EL_MANUAL_ROTATE_DOWN_LIMIT -1
#define EL_MANUAL_ROTATE_UP_LIMIT 181
// Speed pot settings
#define SPEED_POT_LOW 0
#define SPEED_POT_HIGH 1023
#define SPEED_POT_LOW_MAP 1
#define SPEED_POT_HIGH_MAP 255
// Azimuth preset pot settings
#define AZ_PRESET_POT_FULL_CW 0
#define AZ_PRESET_POT_FULL_CCW 1023
#define AZ_PRESET_POT_FULL_CW_MAP 180 // azimuth pot fully counter-clockwise degrees
#define AZ_PRESET_POT_FULL_CCW_MAP 630 // azimuth pot fully clockwise degrees
#define ENCODER_PRESET_TIMEOUT 5000
// various code settings
#define AZIMUTH_TOLERANCE 3.0 // rotator will stop within X degrees when doing autorotation
#define ELEVATION_TOLERANCE 0.1 //1.0
#define OPERATION_TIMEOUT 120000 // timeout for any rotation operation in mS ; 120 seconds is usually enough unless you have the speed turned down
#define TIMED_INTERVAL_ARRAY_SIZE 20
#define CONTROL_PORT_BAUD_RATE 9600
#define REMOTE_UNIT_PORT_BAUD_RATE 9600
#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 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 LCD_COLUMNS 20 //16
#define LCD_ROWS 4 //2
#define LCD_UPDATE_TIME 1000 // LCD update time in milliseconds
#define I2C_LCD_COLOR GREEN // default color of I2C LCD display, including Adafruit and Yourduino; some Yourduino may want this as LED_ON
#define LCD_HHMM_CLOCK_POSITION LEFT //LEFT or RIGHT
#define LCD_HHMMSS_CLOCK_POSITION LEFT //LEFT or RIGHT
#define LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_POSITION LEFT
#define LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_ROW 1
#define LCD_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD_POSITION LEFT
#define LCD_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD_ROW 1
#define LCD_BIG_CLOCK_ROW 4
#define LCD_GPS_INDICATOR_POSITION RIGHT //LEFT or RIGHT
#define LCD_GPS_INDICATOR_ROW 1
#define LCD_MOON_TRACKING_ROW 3 // LCD display row for OPTION_DISPLAY_MOON_TRACKING_CONTINUOUSLY
#define LCD_MOON_TRACKING_UPDATE_INTERVAL 5000
#define LCD_SUN_TRACKING_ROW 4 // LCD display row for OPTION_DISPLAY_SUN_TRACKING_CONTINUOUSLY
#define LCD_SUN_TRACKING_UPDATE_INTERVAL 5000
#define LCD_MOON_OR_SUN_TRACKING_CONDITIONAL_ROW 3 // LCD display row for OPTION_DISPLAY_MOON_OR_SUN_TRACKING_CONDITIONAL
#define SPLASH_SCREEN_TIME 3000
#define AZ_BRAKE_DELAY 3000 // in milliseconds
#define EL_BRAKE_DELAY 3000 // in milliseconds
#define EEPROM_MAGIC_NUMBER 103
#define EEPROM_WRITE_DIRTY_CONFIG_TIME 30 //time in seconds
#if defined(FEATURE_TWO_DECIMAL_PLACE_HEADINGS)
#define HEADING_MULTIPLIER 100L
#define LCD_HEADING_MULTIPLIER 100.0
#define LCD_DECIMAL_PLACES 2
#endif //FEATURE_TWO_DECIMAL_PLACE_HEADINGS
#if defined(FEATURE_ONE_DECIMAL_PLACE_HEADINGS)
#define HEADING_MULTIPLIER 10
#define LCD_HEADING_MULTIPLIER 10.0
#define LCD_DECIMAL_PLACES 1
#endif //FEATURE_ONE_DECIMAL_PLACE_HEADINGS
#if !defined(FEATURE_ONE_DECIMAL_PLACE_HEADINGS) && !defined(FEATURE_TWO_DECIMAL_PLACE_HEADINGS)
#define HEADING_MULTIPLIER 1
#define LCD_HEADING_MULTIPLIER 1.0
#define LCD_DECIMAL_PLACES 0
#endif //!defined(FEATURE_ONE_DECIMAL_PLACE_HEADINGS) && !defined(FEATURE_TWO_DECIMAL_PLACE_HEADINGS)
#define AZ_POSITION_ROTARY_ENCODER_DEG_PER_PULSE 0.5
#define EL_POSITION_ROTARY_ENCODER_DEG_PER_PULSE 0.5
#define AZ_POSITION_PULSE_DEG_PER_PULSE 0.5
#define EL_POSITION_PULSE_DEG_PER_PULSE 0.5
#define PARK_AZIMUTH 360.0 * HEADING_MULTIPLIER // replace the 0.0 with your park azimuth; azimuth is in raw degrees (i.e. on a 180 degree starting point rotator, 0 degrees = 360)
#define PARK_ELEVATION 0.0 * HEADING_MULTIPLIER // replace the 0.0 with your park elevation
#define COMMAND_BUFFER_SIZE 50
#define REMOTE_BUFFER_TIMEOUT_MS 250
#define REMOTE_UNIT_COMMAND_TIMEOUT_MS 2000
#define AZ_REMOTE_UNIT_QUERY_TIME_MS 150 // how often we query the remote remote for azimuth
#define EL_REMOTE_UNIT_QUERY_TIME_MS 150 // how often we query the remote remote for elevation
#define ROTATE_PIN_INACTIVE_VALUE LOW
#define ROTATE_PIN_ACTIVE_VALUE HIGH
#define AZIMUTH_SMOOTHING_FACTOR 0 // value = 0 to 99.9
#define ELEVATION_SMOOTHING_FACTOR 0 // value = 0 to 99.9
#define AZIMUTH_MEASUREMENT_FREQUENCY_MS 100 // this does not apply if using FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT
#define ELEVATION_MEASUREMENT_FREQUENCY_MS 100 // this does not apply if using FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT
#define JOYSTICK_WAIT_TIME_MS 100
#define ROTATION_INDICATOR_PIN_ACTIVE_STATE HIGH
#define ROTATION_INDICATOR_PIN_INACTIVE_STATE LOW
#define ROTATION_INDICATOR_PIN_TIME_DELAY_SECONDS 0
#define ROTATION_INDICATOR_PIN_TIME_DELAY_MINUTES 0
#define AZ_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV 2000.0
#define EL_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV 2000.0
#define SERIAL_LED_TIME_MS 250
#define DEFAULT_LATITUDE 40.889958
#define DEFAULT_LONGITUDE -75.585972
#define MOON_TRACKING_CHECK_INTERVAL 5000
#define MOON_AOS_AZIMUTH_MIN 0
#define MOON_AOS_AZIMUTH_MAX 360
#define MOON_AOS_ELEVATION_MIN 0
#define MOON_AOS_ELEVATION_MAX 180
#define SUN_TRACKING_CHECK_INTERVAL 5000
#define SUN_AOS_AZIMUTH_MIN 0
#define SUN_AOS_AZIMUTH_MAX 360
#define SUN_AOS_ELEVATION_MIN 0
#define SUN_AOS_ELEVATION_MAX 180
#ifdef LANGUAGE_ENGLISH // English language support (copy leading and trailing spaces when making your own language section)
#define MOON_STRING "moon "
#define SUN_STRING "sun "
#define AZ_TARGET_STRING "Az Target "
#define EL_TARGET_STRING "El Target "
#define TARGET_STRING "Target "
#define PARKED_STRING "Parked"
#define ROTATING_CW_STRING "Rotating CW"
#define ROTATING_CCW_STRING "Rotating CCW"
#define ROTATING_TO_STRING "Rotating to "
#define ELEVATING_TO_STRING "Elevating to "
#define ELEVATING_UP_STRING "Elevating Up"
#define ELEVATING_DOWN_STRING "Elevating Down"
#define ROTATING_STRING "Rotating "
#define CW_STRING "CW"
#define CCW_STRING "CCW"
#define UP_STRING "UP"
#define DOWN_STRING "DOWN"
#define AZIMUTH_STRING "Azimuth "
#define AZ_STRING "Az"
#define AZ_SPACE_STRING "Az "
#define SPACE_EL_STRING " El"
#define SPACE_EL_SPACE_STRING " El "
#define GPS_STRING "GPS"
#define N_STRING "N"
#define W_STRING "W"
#define S_STRING "S"
#define E_STRING "E"
#define NW_STRING "NW"
#define SW_STRING "SW"
#define SE_STRING "SE"
#define NE_STRING "NE"
#define NNW_STRING "NNW"
#define WNW_STRING "WNW"
#define WSW_STRING "WSW"
#define SSW_STRING "SSW"
#define SSE_STRING "SSE"
#define ESE_STRING "ESE"
#define ENE_STRING "ENE"
#define NNE_STRING "NNE"
#endif //LANGUAGE_ENGLISH
#ifdef LANGUAGE_SPANISH // Courtesy of Maximo, EA1DDO
#define MOON_STRING "Luna "
#define SUN_STRING "Sol "
#define AZ_TARGET_STRING "Az Objetivo "
#define EL_TARGET_STRING "El Objetivo "
#define TARGET_STRING "Objetivo "
#define PARKED_STRING "Aparcado"
#define ROTATING_CW_STRING "Girando Dcha"
#define ROTATING_CCW_STRING "Girando Izq"
#define ROTATING_TO_STRING "Girando a "
#define ELEVATING_TO_STRING "Elevando a "
#define ELEVATING_UP_STRING "Subiendo"
#define ELEVATING_DOWN_STRING "Bajando"
#define ROTATING_STRING "Girando "
#define CW_STRING "Dcha"
#define CCW_STRING "Izq"
#define UP_STRING "Arriba"
#define DOWN_STRING "Abajo"
#define AZIMUTH_STRING "Azimuth "
#define AZ_STRING "Az"
#define AZ_SPACE_STRING "Az "
#define SPACE_EL_STRING " El"
#define SPACE_EL_SPACE_STRING " El "
#define GPS_STRING "GPS"
#define N_STRING "N"
#define W_STRING "O"
#define S_STRING "S"
#define E_STRING "E"
#define NW_STRING "NO"
#define SW_STRING "SO"
#define SE_STRING "SE"
#define NE_STRING "NE"
#define NNW_STRING "NNO"
#define WNW_STRING "ONO"
#define WSW_STRING "OSO"
#define SSW_STRING "SSO"
#define SSE_STRING "SSE"
#define ESE_STRING "ESE"
#define ENE_STRING "ENE"
#define NNE_STRING "NNE"
#endif //LANGUAGE_SPANISH
#define TRACKING_ACTIVE_CHAR "*"
#define TRACKING_INACTIVE_CHAR "-"
#define INTERNAL_CLOCK_CORRECTION 0.00145
#define SYNC_TIME_WITH_GPS 1
#define SYNC_COORDINATES_WITH_GPS 1
#define GPS_SYNC_PERIOD_SECONDS 10 // how long to consider internal clock syncronized after a GPS reading
#define GPS_VALID_FIX_AGE_MS 10000 // consider a GPS reading valid if the fix age is less than this
#define GPS_UPDATE_LATENCY_COMPENSATION_MS 200
#define SYNC_WITH_RTC_SECONDS 59 // syncronize internal clock with realtime clock every x seconds
#define SYNC_RTC_TO_GPS_SECONDS 12 // synchronize realtime clock to GPS every x seconds
#define SYNC_MASTER_CLOCK_TO_SLAVE_CLOCK_SECS 10 // for OPTION_SYNC_MASTER_CLOCK_TO_SLAVE - use when GPS unit is connected to slave unit and you want to synchronize the master unit clock to the slave unit clock
#define ETHERNET_MAC_ADDRESS 0xDE,0xAD,0xBE,0xEF,0xFE,0xEE //<-DON'T FORGET TO USE DIFFERENT MAC ADDRESSES FOR MASTER AND SLAVE!!!
#define ETHERNET_IP_ADDRESS 192,168,1,172 //<-DON'T FORGET TO USE DIFFERENT IP ADDRESSES FOR MASTER AND SLAVE!!!
#define ETHERNET_IP_GATEWAY 192,168,1,1
#define ETHERNET_IP_SUBNET_MASK 255,255,255,0
#define ETHERNET_TCP_PORT_0 23
#define ETHERNET_TCP_PORT_1 24
#define ETHERNET_MESSAGE_TIMEOUT_MS 5000
#define ETHERNET_PREAMBLE "K3NG" // used only with Ethernet master/slave link
#define ETHERNET_SLAVE_IP_ADDRESS 192,168,1,173
#define ETHERNET_SLAVE_TCP_PORT 23
#define ETHERNET_SLAVE_RECONNECT_TIME_MS 250
#define POWER_SWITCH_IDLE_TIMEOUT 15 // use with FEATURE_POWER_SWITCH; units are minutes
#ifdef HARDWARE_EA4TX_ARS_USB
#define BUTTON_ACTIVE_STATE HIGH
#define BUTTON_INACTIVE_STATE LOW
#else
#define BUTTON_ACTIVE_STATE LOW
#define BUTTON_INACTIVE_STATE HIGH
#endif
/*
*
* Azimuth and Elevation calibraton tables - use with FEATURE_AZIMUTH_CORRECTION and/or FEATURE_ELEVATION_CORRECTION
*
* You must have the same number of entries in the _FROM_ and _TO_ arrays!
*
*/
#define AZIMUTH_CALIBRATION_FROM_ARRAY {180,630} /* these are in "raw" degrees, i.e. when going east past 360 degrees, add 360 degrees*/
#define AZIMUTH_CALIBRATION_TO_ARRAY {180,630}
// example: reverse rotation sensing
// #define AZIMUTH_CALIBRATION_FROM_ARRAY {0,359}
// #define AZIMUTH_CALIBRATION_TO_ARRAY {359,0}
#define ELEVATION_CALIBRATION_FROM_ARRAY {-180,0,180}
#define ELEVATION_CALIBRATION_TO_ARRAY {-180,0,180}
/* ---------------------------- object declarations ----------------------------------------------
Object declarations are required for several devices, including LCD displays, compass devices, and accelerometers
*/
#ifdef FEATURE_4_BIT_LCD_DISPLAY
LiquidCrystal lcd(lcd_4_bit_rs_pin, lcd_4_bit_enable_pin, lcd_4_bit_d4_pin, lcd_4_bit_d5_pin, lcd_4_bit_d6_pin, lcd_4_bit_d7_pin);
#endif //FEATURE_4_BIT_LCD_DISPLAY
#ifdef FEATURE_ADAFRUIT_I2C_LCD
Adafruit_RGBLCDShield lcd = Adafruit_RGBLCDShield();
#endif //FEATURE_ADAFRUIT_I2C_LCD
#ifdef FEATURE_YOURDUINO_I2C_LCD
#define I2C_ADDR 0x20
#define BACKLIGHT_PIN 3
#define LED_OFF 1
#define LED_ON 0
LiquidCrystal_I2C lcd(I2C_ADDR,En_pin,Rw_pin,Rs_pin,D4_pin,D5_pin,D6_pin,D7_pin);
#endif //FEATURE_YOURDUINO_I2C_LCD
#ifdef FEATURE_RFROBOT_I2C_DISPLAY
LiquidCrystal_I2C lcd(0x27,16,2);
#endif //FEATURE_RFROBOT_I2C_DISPLAY
#ifdef FEATURE_AZ_POSITION_HMC5883L
HMC5883L compass;
#endif //FEATURE_AZ_POSITION_HMC5883L
#ifdef FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB
ADXL345 accel;
#endif //FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB
#ifdef FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB
Adafruit_ADXL345_Unified accel = Adafruit_ADXL345_Unified(12345);
#endif //FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB
#if defined(FEATURE_EL_POSITION_LSM303) || defined(FEATURE_AZ_POSITION_LSM303)
Adafruit_LSM303 lsm;
#endif
#ifdef FEATURE_AZ_POSITION_HH12_AS5045_SSI
#include "hh12.h"
hh12 azimuth_hh12;
#endif //FEATURE_AZ_POSITION_HH12_AS5045_SSI
#ifdef FEATURE_EL_POSITION_HH12_AS5045_SSI
#include "hh12.h"
hh12 elevation_hh12;
#endif //FEATURE_EL_POSITION_HH12_AS5045_SSI
#ifdef FEATURE_GPS
TinyGPS gps;
#endif //FEATURE_GPS
#ifdef FEATURE_RTC_DS1307
RTC_DS1307 rtc;
#endif //FEATURE_RTC_DS1307
#ifdef FEATURE_RTC_PCF8583
PCF8583 rtc(0xA0);
#endif //FEATURE_RTC_PCF8583
#ifdef HARDWARE_EA4TX_ARS_USB
#undef LCD_COLUMNS
#undef LCD_ROWS
#define LCD_COLUMNS 16
#define LCD_ROWS 2
#endif //HARDWARE_EA4TX_ARS_USB

137
sunpos.cpp Executable file
View File

@ -0,0 +1,137 @@
// This file is available in electronic form at http://www.psa.es/sdg/sunpos.htm
#include "sunpos.h"
#include <math.h>
void sunpos(cTime udtTime,cLocation udtLocation, cSunCoordinates *udtSunCoordinates)
{
// Main variables
double dElapsedJulianDays;
double dDecimalHours;
double dEclipticLongitude;
double dEclipticObliquity;
double dRightAscension;
double dDeclination;
// Auxiliary variables
double dY;
double dX;
// Calculate difference in days between the current Julian Day
// and JD 2451545.0, which is noon 1 January 2000 Universal Time
{
double dJulianDate;
long int liAux1;
long int liAux2;
// Calculate time of the day in UT decimal hours
dDecimalHours = udtTime.dHours + (udtTime.dMinutes
+ udtTime.dSeconds / 60.0 ) / 60.0;
// Calculate current Julian Day
liAux1 =(udtTime.iMonth-14)/12;
liAux2=(1461*(udtTime.iYear + 4800 + liAux1))/4 + (367*(udtTime.iMonth
- 2-12*liAux1))/12- (3*((udtTime.iYear + 4900
+ liAux1)/100))/4+udtTime.iDay-32075;
// dJulianDate=(double)(liAux2)-0.5+dDecimalHours/24.0;
// Calculate difference between current Julian Day and JD 2451545.0
// dElapsedJulianDays = dJulianDate-2451545.0;
// 140113 VE5VA
// The original way of calculating elapsed Julian days required
// more precision than is possible in a 32-bit float, so change
// the order of the calculation to preserve the significant digits.
liAux2 -= 2451545L;
dElapsedJulianDays = (double)liAux2-0.5+dDecimalHours/24.0;
}
/* old Julian day calculation
// Calculate difference in days between the current Julian Day
// and JD 2451545.0, which is noon 1 January 2000 Universal Time
{
double dJulianDate;
long int liAux1;
long int liAux2;
// Calculate time of the day in UT decimal hours
dDecimalHours = udtTime.dHours + (udtTime.dMinutes
+ udtTime.dSeconds / 60.0 ) / 60.0;
// Calculate current Julian Day
liAux1 =(udtTime.iMonth-14)/12;
liAux2=(1461*(udtTime.iYear + 4800 + liAux1))/4 + (367*(udtTime.iMonth
- 2-12*liAux1))/12- (3*((udtTime.iYear + 4900
+ liAux1)/100))/4+udtTime.iDay-32075;
dJulianDate=(double)(liAux2)-0.5+dDecimalHours/24.0;
// Calculate difference between current Julian Day and JD 2451545.0
dElapsedJulianDays = dJulianDate-2451545.0;
}
*/
// Calculate ecliptic coordinates (ecliptic longitude and obliquity of the
// ecliptic in radians but without limiting the angle to be less than 2*Pi
// (i.e., the result may be greater than 2*Pi)
{
double dMeanLongitude;
double dMeanAnomaly;
double dOmega;
dOmega=2.1429-0.0010394594*dElapsedJulianDays;
dMeanLongitude = 4.8950630+ 0.017202791698*dElapsedJulianDays; // Radians
dMeanAnomaly = 6.2400600+ 0.0172019699*dElapsedJulianDays;
dEclipticLongitude = dMeanLongitude + 0.03341607*sin( dMeanAnomaly )
+ 0.00034894*sin( 2*dMeanAnomaly )-0.0001134
-0.0000203*sin(dOmega);
dEclipticObliquity = 0.4090928 - 6.2140e-9*dElapsedJulianDays
+0.0000396*cos(dOmega);
}
// Calculate celestial coordinates ( right ascension and declination ) in radians
// but without limiting the angle to be less than 2*Pi (i.e., the result may be
// greater than 2*Pi)
{
double dSin_EclipticLongitude;
dSin_EclipticLongitude= sin( dEclipticLongitude );
dY = cos( dEclipticObliquity ) * dSin_EclipticLongitude;
dX = cos( dEclipticLongitude );
dRightAscension = atan2( dY,dX );
if( dRightAscension < 0.0 ) dRightAscension = dRightAscension + twopi;
dDeclination = asin( sin( dEclipticObliquity )*dSin_EclipticLongitude );
}
// Calculate local coordinates ( azimuth and zenith angle ) in degrees
{
double dGreenwichMeanSiderealTime;
double dLocalMeanSiderealTime;
double dLatitudeInRadians;
double dHourAngle;
double dCos_Latitude;
double dSin_Latitude;
double dCos_HourAngle;
double dParallax;
dGreenwichMeanSiderealTime = 6.6974243242 +
0.0657098283*dElapsedJulianDays
+ dDecimalHours;
dLocalMeanSiderealTime = (dGreenwichMeanSiderealTime*15
+ udtLocation.dLongitude)*rad;
dHourAngle = dLocalMeanSiderealTime - dRightAscension;
dLatitudeInRadians = udtLocation.dLatitude*rad;
dCos_Latitude = cos( dLatitudeInRadians );
dSin_Latitude = sin( dLatitudeInRadians );
dCos_HourAngle= cos( dHourAngle );
udtSunCoordinates->dZenithAngle = (acos( dCos_Latitude*dCos_HourAngle
*cos(dDeclination) + sin( dDeclination )*dSin_Latitude));
dY = -sin( dHourAngle );
dX = tan( dDeclination )*dCos_Latitude - dSin_Latitude*dCos_HourAngle;
udtSunCoordinates->dAzimuth = atan2( dY, dX );
if ( udtSunCoordinates->dAzimuth < 0.0 )
udtSunCoordinates->dAzimuth = udtSunCoordinates->dAzimuth + twopi;
udtSunCoordinates->dAzimuth = udtSunCoordinates->dAzimuth/rad;
// Parallax Correction
dParallax=(dEarthMeanRadius/dAstronomicalUnit)
*sin(udtSunCoordinates->dZenithAngle);
udtSunCoordinates->dZenithAngle=(udtSunCoordinates->dZenithAngle
+ dParallax)/rad;
}
}

39
sunpos.h Executable file
View File

@ -0,0 +1,39 @@
// This file is available in electronic form at http://www.psa.es/sdg/sunpos.htm
#ifndef __SUNPOS_H
#define __SUNPOS_H
// Declaration of some constants
#define pi 3.14159265358979323846
#define twopi (2*pi)
#define rad (pi/180)
#define dEarthMeanRadius 6371.01 // In km
#define dAstronomicalUnit 149597890 // In km
struct cTime
{
int iYear;
int iMonth;
int iDay;
double dHours;
double dMinutes;
double dSeconds;
};
struct cLocation
{
double dLongitude;
double dLatitude;
};
struct cSunCoordinates
{
double dZenithAngle;
double dAzimuth;
};
void sunpos(cTime udtTime, cLocation udtLocation, cSunCoordinates *udtSunCoordinates);
#endif