diff --git a/HMC5883L.cpp b/HMC5883L.cpp
new file mode 100755
index 0000000..b4ff4e8
--- /dev/null
+++ b/HMC5883L.cpp
@@ -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 .
+
+ 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
+#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.";
+}
\ No newline at end of file
diff --git a/HMC5883L.h b/HMC5883L.h
new file mode 100755
index 0000000..917d2d4
--- /dev/null
+++ b/HMC5883L.h
@@ -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 .
+
+ 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
+#include
+
+
+
+#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
\ No newline at end of file
diff --git a/PCF8583.cpp b/PCF8583.cpp
new file mode 100755
index 0000000..e605f58
--- /dev/null
+++ b/PCF8583.cpp
@@ -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
+#include
+#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);
+}
+
diff --git a/PCF8583.h b/PCF8583.h
new file mode 100755
index 0000000..4163ec5
--- /dev/null
+++ b/PCF8583.h
@@ -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
+#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
diff --git a/RTClib.cpp b/RTClib.cpp
new file mode 100755
index 0000000..37a7d37
--- /dev/null
+++ b/RTClib.cpp
@@ -0,0 +1,246 @@
+// Code by JeeLabs http://news.jeelabs.org/code/
+// Released to the public domain! Enjoy!
+
+#include
+#include "RTClib.h"
+#ifdef __AVR__
+ #include
+ #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 // capital A so it is error prone on case-sensitive filesystems
+#else
+ #include
+#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);
+}
+
+////////////////////////////////////////////////////////////////////////////////
diff --git a/RTClib.h b/RTClib.h
new file mode 100755
index 0000000..a9301af
--- /dev/null
+++ b/RTClib.h
@@ -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_
diff --git a/TinyGPS.cpp b/TinyGPS.cpp
new file mode 100755
index 0000000..deae922
--- /dev/null
+++ b/TinyGPS.cpp
@@ -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;
diff --git a/TinyGPS.h b/TinyGPS.h
new file mode 100755
index 0000000..0711907
--- /dev/null
+++ b/TinyGPS.h
@@ -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
+
+#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
diff --git a/hh12.cpp b/hh12.cpp
new file mode 100755
index 0000000..18cce59
--- /dev/null
+++ b/hh12.cpp
@@ -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);
+
+
+}
+
diff --git a/hh12.h b/hh12.h
new file mode 100755
index 0000000..2edafa0
--- /dev/null
+++ b/hh12.h
@@ -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
diff --git a/k3ng_rotator_controller.ino b/k3ng_rotator_controller.ino
index dad1f84..b1eeaea 100644
--- a/k3ng_rotator_controller.ino
+++ b/k3ng_rotator_controller.ino
@@ -1,651 +1,606 @@
-/* Arduino Rotator Controller "2.0 Edition"
- Anthony Good
- K3NG
- anthony.good@gmail.com
+/* Arduino Rotator Controller
+ * Anthony Good
+ * K3NG
+ * anthony.good@gmail.com
+ *
+ * Contributions from John Eigenbode, W3SA
+ * w3sa@arrl.net
+ * Contributions: AZ/EL testing and debugging, AZ/EL LCD Enhancements, original North center code, Az/El Rotator Control Connector Pins
+ *
+ * Contributions from Jim Balls, M0CKE
+ * makidoja@gmail.com
+ * Contributions: Rotary Encoder Preset Support
+ *
+ * Contributions from Gord, VO1GPK
+ * Contribution: FEATURE_ADAFRUIT_BUTTONS code
+ *
+ * Moon2 and sunpos libraries courtesy of Pete Hardie, VE5VA
+ *
+ * Non-English extensions ideas, code, and testing provided by Marcin SP5IOU, Hjalmar OZ1JHM, and Sverre LA3ZA
+ *
+ * Testing, ideas, and hardware provided by Anthony M0UPU, Bent OZ1CT, Eric WB6KCN, Norm N3YKF, and many others
+ *
+ * Translations: Maximo, EA1DDO
+ *
+ ***************************************************************************************************************
+ *
+ * This program is licensed under the Creative Commons Attribution-NonCommercial-ShareAlike 3.0 Unported License
+ *
+ * http://creativecommons.org/licenses/by-nc-sa/3.0/
+ *
+ * http://creativecommons.org/licenses/by-nc-sa/3.0/legalcode
+ *
+ *
+ ***************************************************************************************************************
+ *
+ *
+ *
+ *
+ * All copyrights are the property of their respective owners
+ *
+ * Very basic ASCII Art Schematic
+ *
+ **+----------------Yaesu Pin 1
+ |
+ | N
+ | D6---{1000 ohms}---P 2N2222
+ | N or similar
+ |
+ | GND
+ |
+ ||+----------------Yaesu Pin 2
+ |
+ | N
+ | D7---{1000 ohms}---P 2N2222
+ | N or similar
+ |
+ | GND
+ |
+ | A0-------------+---------------------Yaesu Pin 4
+ |
+ | [0.01uF]
+ |
+ | GND
+ |
+ | D10---{4.7K}---+---------------------Yaesu Pin 3
+ |
+ | [10uF]
+ |
+ | GND
+ |
+ |
+ | Not Connected------------------------Yaesu Pin 6
+ |
+ | GND----------------------------------Yaesu Pin 5
+ |
+ | Alternatively Yaesu Pin 3 can be connected to Pin 6 if variable speed functionality (X commands) are not desired. This will feed +5V directly
+ | into the speed voltage pin and set the unit for maximum speed all the time
+ |
+ | Yaesu Azimuth Only Rotator Controller Connector Pins
+ |
+ | 6 || 5
+ | 4 3
+ | 2 1
+ | 1 - ground to rotate L
+ | 2 - ground to rotate R
+ | 3 - speed voltage (input); 4.5V = max speed
+ | 4 - analog azimuth voltage (output); 0V = full CCW, ~4.9V = full CW
+ | 5 - ground
+ | 6 - +5V or so
+ |
+ | Yaesu Az/El Rotator Control Connector Pins
+ |
+ | 7 | | 6
+ | 3 8 1
+ | 5 4
+ | 2
+ |
+ | 1 - 2 - 4.5 VDC corresponding to 0 to 180 degrees elevation
+ | 2 - Connect to Pin 8 to rotate right (clockwise)
+ | 3 - Connect to Pin 8 to rotate Down
+ | 4 - Connect to Pin 8 to rotate left (counterclockwise)
+ | 5 - Connect to Pin 8 to rotate Up
+ | 6 - 2 - 4.5 VDC corresponding to 0 to 450 degrees rotation
+ | 7 - 13 - 6 VDC at up to 200 mA
+ | 8 - Common ground
+ |
+ | ASCII Art Schematic
+ |
+ ||+----------------Yaesu Pin 4
+ |
+ | N
+ | D6--{1000 ohms}---P 2N2222
+ | N or similar
+ |
+ | GND
+ |
+ ||+----------------Yaesu Pin 2
+ |
+ | N
+ | D7--{1000 ohms}---P 2N2222
+ | N or similar
+ |
+ | GND
+ ||+----------------Yaesu Pin 5
+ |
+ | N
+ | D8--{1000 ohms}---P 2N2222
+ | N or similar
+ |
+ | GND
+ |
+ ||+----------------Yaesu Pin 3
+ |
+ | N
+ | D9--{1000 ohms}---P 2N2222
+ | N or similar
+ |
+ | GND
+ |
+ | A0-----------------------------------Yaesu Pin 6
+ |
+ | A1-----------------------------------Yaesu Pin 1
+ |
+ | NC-----------------------------------Yaesu Pin 7
+ |
+ | GND----------------------------------Yaesu Pin 8
+ |
+ | Quick Start
+ |
+ | In order to test and calibrate your unit, connect the Serial Monitor to the COM port set for 9600 and carriage return
+ | All command letters must be uppercase.
+ | The backslash d (\d) command toggles debug mode which will periodically display key parameters.
+ |
+ | To test basic operation, send commands using Serial Monitor:
+ | Rotate left(CCW): L
+ | Rotate right(CW): R
+ | Stop rotation: A or S commands
+ | Read the current azimuth: C
+ | Go to an azimuth automatically: M command (examples: M180 = go to 180 degrees, M010 = go to 10 degrees
+ |
+ | To calibrate the unit, send the O command and rotate to 180 degrees / full CCW and send a carriage return, then
+ | send the F command and rotate to 270 degrees / full CW and send a carriage return (assuming a 450 degrees rotation rotator).
+ | If you are operating a 360 degree rotation rotator, for the F command rotate to 180 degrees full CW, not 270.
+ |
+ | ( CW means clockwise (or LEFT on Yaesu rotators) and CCW means counter clockwise (or RIGHT on Yaesu rotators))
+ |
+ |
+ | It does properly handle the 450 degree rotation capability of the Yaesu rotators.
+ |
+ | This code has been successfully interfaced with non-Yaesu rotators. Email me if you have a rotator you would like to interface this to.
+ |
+ | With the addition of a reasonable capacity DC power supply and two relays, this unit could entirely replace a control unit if desired.
+ |
+ *********************************************************************************************************************************************
+ *
+ * New in this release:
+ *
+ * (Please note that many features are in the process of being documented. The {documented} flags are to keep track of
+ * what has been documented and what hasn't.)
+ *
+ * HH-12 encoder support {documented}
+ * OPTION_PULSE_IGNORE_AMBIGUOUS_PULSES
+ * \P PWM command is now \W
+ * \P is Park command
+ * park_in_progress_pin // goes high when a park has been initiated and rotation is in progress {documented}
+ * parked_pin // goes high when in a parked position {documented}
+ *
+ * Introduced in 2013112701UNSTABLE
+ * heading_reading_inhibit_pin {documented}
+ * FEATURE_LIMIT_SENSE {documented}
+ **#define az_limit_sense_pin 0 // input - low stops azimuthal rotation {documented}
+ **#define el_limit_sense_pin 0 // input - low stops elevation rotation {documented}
+ * \Axxx command - manually set azimuth, xxx = azimuth (FEATURE_AZ_POSITION_ROTARY_ENCODER or FEATURE_AZ_POSITION_PULSE_INPUT only) {documented}
+ * \Bxxx command - manually set elevation, xxx = elevation (FEATURE_EL_POSITION_POTENTIOMETER or FEATURE_EL_POSITION_ROTARY_ENCODER only) {documented}
+ *
+ * Introduced in 2013112801UNSTABLE
+ * fixed bug with preset encoder start and kill button
+ *
+ * Introduced in 2013122201UNSTABLE
+ * FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
+ * FEATURE_EL_POSITION_INCREMENTAL_ENCODER
+ * OPTION_INCREMENTAL_ENCODER_PULLUPS
+ **#define AZ_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV 8000.0
+ **#define EL_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV 8000.0
+ * AZIMUTH_STARTING_POINT_DEFAULT and AZIMUTH_ROTATION_CAPABILITY_DEFAULT are now persistent
+ * Yaesu P35, P45, and Z commands no longer write to eeprom {documented}
+ *
+ * Introduced in 2013122301UNSTABLE
+ * control_port points to the hardware port for computer interface
+ * remote_unit_port points to the hardware port for interfacing to remote unit
+ * removed OPTION_SERIAL1, 2, 3, 4
+ * SS command: SS0 = control port, SS1 = remote unit port
+ *
+ * Introduced in 1.9.2014010102-UNSTABLE
+ * No longer need to manually uncomment hh12.h or object declarations
+ * No longer need to manually uncomment LiquidCrystal lcd() {documented}
+ * No longer need to manually uncomment Adafruit_ADXL345 accel {documented}
+ * No longer need to manually uncomment ADXL345 accel {documented}
+ * No longer need to manually uncomment Adafruit_LSM303 lsm;
+ * No longer need to manually uncomment HMC5883L compass;
+ * FEATURE_4_BIT_LCD_DISPLAY {documented}
+ * FEATURE_ADAFRUIT_I2C_LCD {documented}
+ * FEATURE_YOURDUINO_I2C_LCD {documented}
+ * FEATURE_RFROBOT_I2C_DISPLAY
+ *
+ * Introduced in 1.9.2014010201-UNSTABLE
+ * No longer need to uncomment:
+ * FEATURE_LCD_DISPLAY {documented}
+ * FEATURE_I2C_LCD {documented}
+ * any include files {documented}
+ *
+ * Introduced in 1.9.2014010401-UNSTABLE
+ * serial led duration now set by SERIAL_LED_TIME_MS
+ *
+ * Introduced in 1.9.2014010901-UNSTABLE
+ **#define CONTROL_PORT_MAPPED_TO &Serial // change this line to map the control port to a different serial port (Serial1, Serial2, etc.) {documented}
+ **#define REMOTE_PORT_MAPPED_TO &Serial1 // change this line to map the remote_unit port to a different serial port {documented}
+ * start of remote unit pin control
+ *
+ * Introduced in 1.9.2014011101-UNSTABLE
+ * remote unit pin control (add 100 to a pin number define to map to remote unit pin) {documented}
+ * FEATURE_CLOCK {documented}
+ * FEATURE_MOON_TRACKING {documented}
+ **#define DEFAULT_LATITUDE 40.889958 {documented}
+ **#define DEFAULT_LONGITUDE -75.585972 {documented}
+ *
+ **#define INTERNAL_CLOCK_CORRECTION 0.00145
+ *
+ * \C - show clock {documented}
+ * \O - set clock \OYYYYMMDDHHmm {documented}
+ * \Mx - x = 0: deactive moon tracking; x = 1: activate moon tracking {documented}
+ * \Gxxxxxx - set coordinates via grid square (example: \GFN20EV) {documented}
+ *
+ * Park is now deactivated when issuing a Yaesu command (other than C) or when doing manual rotation
+ *
+ * Introduced in 1.9.2014011202-UNSTABLE
+ * FEATURE_GPS
+ **#define GPS_PORT_MAPPED_TO &Serial2 {documented}
+ **#define GPS_PORT_BAUD_RATE 9600 {documented}
+ **#define SYNC_TIME_WITH_GPS 1 {documented}
+ **#define SYNC_COORDINATES_WITH_GPS 1 {documented}
+ **#define GPS_SYNC_PERIOD_SECONDS 10 // how long to consider internal clock syncronized after a GPS reading {documented}
+ **#define GPS_VALID_FIX_AGE_MS 10000 // consider a GPS reading valid if the fix age is less than this {documented}
+ *
+ * Introduced in 1.9.2014011701-UNSTABLE
+ * FEATURE_SUN_TRACKING {documented}
+ * \Ux - x = 0: deactive sun tracking; x = 1: activate sun tracking {documented}
+ * working on FEATURE_TWO_DECIMAL_PLACE_HEADINGS - there is a bug in the azimuth calculations {documented}
+ *
+ * Introduced in 1.9.2014012001-UNSTABLE
+ * FEATURE_AZ_POSITION_INCREMENTAL_ENCODER & FEATURE_EL_POSITION_INCREMENTAL_ENCODER coding
+ *
+ * Introduced in 1.9.2014012401-UNSTABLE
+ * Updated debug output format
+ * \XS - calibration az and el to sun heading - there are calculation bugs
+ *
+ * Introduced in 1.9.2014012601-UNSTABLE
+ * fixed initialize_serial() compilaton error when neither yaesu or easycom protocol is selected in features
+ * fixed bugs in \XS and \XM
+ * still working on implementation \XS and \XM to work with all sensor types
+ *
+ * Introduced in 1.9.2014012701-UNSTABLE
+ * \XS and\XM now working on all sensor types {documented}
+ * moon_tracking_active_pin {documented}
+ * sun_tracking_active_pin {documented}
+ * moon_tracking_activate_line {documented}
+ * sun_tracking_activate_line {documented}
+ *
+ * Introduced in 1.9.2014012801-UNSTABLE
+ * moon_tracking_button {documented}
+ * sun_tracking_button {documented}
+ * \A azimuth calibration now also works with sensors other than rotary encoders and pulse input
+ * \B elevation calibration now also works with sensors other than rotary encoders and pulse input
+ *
+ * Introduced in 1.9.2014013001-UNSTABLE
+ * OPTION_BUTTON_RELEASE_NO_SLOWDOWN {documented}
+ *
+ * Introduced in 1.9.2014013101-UNSTABLEA
+ * Fixed God-awful bug that caused Arduino to crash when running FEATURE_GPS. Note to self: never declare a char in a switch case. It causes unpredicatable, unexplainable evil stuff to occur.
+ *
+ * 1.9.2014020101-UNSTABLE
+ * Fixed bug with elevation PWM
+ *
+ 1.9.2014020501-UNSTABLE
+ gps_sync pin - goes high when clock is GPS synchronized {documented}
- Contributions from John Eigenbode, W3SA
- w3sa@arrl.net
- Contributions: AZ/EL testing and debugging, AZ/EL LCD Enhancements, original North center code, Az/El Rotator Control Connector Pins
+ 1.9.2014020501-UNSTABLE
+ working on decoupling check_serial and yaesu_command and backslash command handling in preparation for Ethernet support
- Contributions from Jim Balls, M0CKE
- makidoja@gmail.com
- Contributions: Rotary Encoder Preset Support
-
- Contributions from Gord, VO1GPK
- Contribution: FEATURE_ADAFRUIT_BUTTONS code
+ 1.9.2014020701-UNSTABLE
+ FEATURE_RTC_PCF8583 {documented}
- ***************************************************************************************************************
+ 1.9.2014021001-UNSTABLE
+ \O command also programs realtime clocks now
- This program is licensed under the Creative Commons Attribution-NonCommercial-ShareAlike 3.0 Unported License
-
- http://creativecommons.org/licenses/by-nc-sa/3.0/
+ 1.9.2014021101-UNSTABLE
+ Fixed bug in PWM outputs when changing direction
+ Ethernet now working with backslash commands, Yaesu commands, and Easycom commands
+ Fixed bug in Easycom (non-standard) AZ and EL commands
- http://creativecommons.org/licenses/by-nc-sa/3.0/legalcode
+ 1.9.2014021201-UNSTABLE
+ Ethernet remote unit slave support (slave only, master using ethernet not done yet)
+
+ 1.9.2014021301-UNSTABLE
+ More Ethernet code work
+
+ 1.9.2014021501-UNSTABLE
+ More print_debug conversion
+
+ 1.9.2014021701-UNSTABLE
+ #define GPS_MIRROR_PORT &Serial3 {documented}
- ***************************************************************************************************************
+ 1.9.2014021801-UNSTABLE
+ OPTION_DISPLAY_SMALL_CLOCK
+ #define LCD_SMALL_CLOCK_POSITION LEFT
+ OPTION_DISPLAY_GPS_INDICATOR
+ #define LCD_GPS_INDICATOR_POSITION RIGHT
+ OPTION_DISPLAY_MOON_TRACKING_CONTINUOUSLY
+ #define LCD_MOON_TRACKING_ROW 3
+ #define LCD_MOON_TRACKING_UPDATE_INTERVAL 5000
+ OPTION_DISPLAY_SUN_TRACKING_CONTINUOUSLY
+ #define LCD_SUN_TRACKING_ROW 4
+ #define LCD_SUN_TRACKING_UPDATE_INTERVAL 5000
+ #define LCD_ROWS 4
+{documentation stops here ---------------------------------------------------------}
+ 1.9.2014021901-UNSTABLE
+ fixed bug with Yourduino LCD display initialization (thanks PA3FPQ)
+ added GPS counters to debug output
+ FEATURE_POWER_SWITCH
+ #define POWER_SWITCH_IDLE_TIMEOUT 15 (unit: minutes)
+ #define power_switch 0
+ OPTION_DISPLAY_MOON_OR_SUN_TRACKING_CONDITIONAL
+ #define LCD_MOON_OR_SUN_TRACKING_CONDITIONAL_ROW 3
+ OPTION_DISPLAY_BIG_CLOCK
+ 1.9.2014021902-UNSTABLE
+ #define GPS_UPDATE_LATENCY_COMPENSATION_MS 200
- All copyrights are the property of their respective owners
+ 1.9.2014022001-UNSTABLE
+ Fixed issue with FEATURE_RFROBOT_I2C_DISPLAY & FEATURE_ADAFRUIT_I2C_LCD compilation (thanks EA1DDO)
- ASCII Art Schematic
-
- +----------------Yaesu Pin 1
- |
- N
- D6---{1000 ohms}---P 2N2222
- N or similar
- |
- GND
-
- +----------------Yaesu Pin 2
- |
- N
- D7---{1000 ohms}---P 2N2222
- N or similar
- |
- GND
-
- A0-------------+---------------------Yaesu Pin 4
- |
- [0.01uF]
- |
- GND
-
- D10---{4.7K}---+---------------------Yaesu Pin 3
- |
- [10uF]
- |
- GND
-
-
- Not Connected------------------------Yaesu Pin 6
-
- GND----------------------------------Yaesu Pin 5
+ 1.9.2014022101-UNSTABLE
+ #define AZIMUTH_CALIBRATION_FROM_ARRAY {180,630}
+ #define AZIMUTH_CALIBRATION_TO_ARRAY {180,630}
+ #define ELEVATION_CALIBRATION_FROM_ARRAY {-180,0,180}
+ #define ELEVATION_CALIBRATION_TO_ARRAY {-180,0,180}
+ #define rotate_cw_ccw 0
+ #define az_stepper_motor_direction 0
+ #define el_stepper_motor_direction 0
+ bug fix for long clock display
+ performance improvement for az / el display on LCD
+
+ 1.9.2014022201-UNSTABLE
+ bug fix for long clock display
- Alternatively Yaesu Pin 3 can be connected to Pin 6 if variable speed functionality (X commands) are not desired. This will feed +5V directly
- into the speed voltage pin and set the unit for maximum speed all the time
+ 1.9.2014022202-UNSTABLE
+ #define az_stepper_motor_pulse 0
+ #define el_stepper_motor_pulse 0
+ OPTION_DISPLAY_ALT_HHMM_CLOCK_AND_MAIDENHEAD {documented}
+ #define LCD_SMALL_CLOCK_AND_MAIDENHEAD_POSITION {documented}
+ #define LCD_SMALL_CLOCK_AND_MAIDENHEAD_ROW 4 {documented}
+ #define LCD_GPS_INDICATOR_ROW 1 {documented}
- Yaesu Azimuth Only Rotator Controller Connector Pins
-
- 6 || 5
- 4 3
- 2 1
- 1 - ground to rotate L
- 2 - ground to rotate R
- 3 - speed voltage (input); 4.5V = max speed
- 4 - analog azimuth voltage (output); 0V = full CCW, ~4.9V = full CW
- 5 - ground
- 6 - +5V or so
+ 1.9.2014030201-UNSTABLE
+ Fixed compilation issue with Yourduino LCD display ()
- Yaesu Az/El Rotator Control Connector Pins
-
- 7 | | 6
- 3 8 1
- 5 4
- 2
-
- 1 - 2 - 4.5 VDC corresponding to 0 to 180 degrees elevation
- 2 - Connect to Pin 8 to rotate right (clockwise)
- 3 - Connect to Pin 8 to rotate Down
- 4 - Connect to Pin 8 to rotate left (counterclockwise)
- 5 - Connect to Pin 8 to rotate Up
- 6 - 2 - 4.5 VDC corresponding to 0 to 450 degrees rotation
- 7 - 13 - 6 VDC at up to 200 mA
- 8 - Common ground
+ 1.9.2014030301-UNSTABLE
+ OPTION_EXTERNAL_ANALOG_REFERENCE
+ more debug_print conversion
- ASCII Art Schematic
-
- +----------------Yaesu Pin 4
- |
- N
- D6--{1000 ohms}---P 2N2222
- N or similar
- |
- GND
-
- +----------------Yaesu Pin 2
- |
- N
- D7--{1000 ohms}---P 2N2222
- N or similar
- |
- GND
- +----------------Yaesu Pin 5
- |
- N
- D8--{1000 ohms}---P 2N2222
- N or similar
- |
- GND
-
- +----------------Yaesu Pin 3
- |
- N
- D9--{1000 ohms}---P 2N2222
- N or similar
- |
- GND
-
- A0-----------------------------------Yaesu Pin 6
-
- A1-----------------------------------Yaesu Pin 1
-
- NC-----------------------------------Yaesu Pin 7
-
- GND----------------------------------Yaesu Pin 8
+ 1.9.2014030901-UNSTABLE
+ OPTION_DISPLAY_SMALL_CLOCK renamed to OPTION_DISPLAY_HHMM_CLOCK {documented}
+ LCD_SMALL_CLOCK_POSITION renamed to LCD_HHMM_CLOCK_POSITION {documented}
+ OPTION_DISPLAY_HHMMSS_CLOCK {documented}
+ OPTION_DISPLAY_DISABLE_DIRECTION_STATUS {documented}
+ OPTION_DISPLAY_SMALL_CLOCK_AND_MAIDENHEAD renamed to OPTION_DISPLAY_ALT_HHMM_CLOCK_AND_MAIDENHEAD {documented}
+ OPTION_DISPLAY_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD {documented}
- Quick Start
-
- In order to test and calibrate your unit, connect the Serial Monitor to the COM port set for 9600 and carriage return
- All command letters must be uppercase.
- The backslash d (\d) command toggles debug mode which will periodically display key parameters.
-
- To test basic operation, send commands using Serial Monitor:
- Rotate left(CCW): L
- Rotate right(CW): R
- Stop rotation: A or S commands
- Read the current azimuth: C
- Go to an azimuth automatically: M command (examples: M180 = go to 180 degrees, M010 = go to 10 degrees
-
- To calibrate the unit, send the O command and rotate to 180 degrees / full CCW and send a carriage return, then
- send the F command and rotate to 270 degrees / full CW and send a carriage return (assuming a 450 degrees rotation rotator).
- If you are operating a 360 degree rotation rotator, for the F command rotate to 180 degrees full CW, not 270.
-
- ( CW means clockwise (or LEFT on Yaesu rotators) and CCW means counter clockwise (or RIGHT on Yaesu rotators))
-
- To use this code with AZ/EL rotators, uncomment the FEATURE_ELEVATION_CONTROL line below
-
- It does properly handle the 450 degree rotation capability of the Yaesu rotators.
-
- This code has been successfully interfaced with non-Yaesu rotators. Email me if you have a rotator you would like to interface this to.
-
- With the addition of a reasonable capacity DC power supply and two relays, this unit could entirely replace a control unit if desired.
+ #define LCD_HHMM_CLOCK_POSITION LEFT //LEFT or RIGHT {documented}
+ #define LCD_HHMMSS_CLOCK_POSITION LEFT //LEFT or RIGHT {documented}
+ #define LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_POSITION LEFT {documented}
+ #define LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_ROW 1 {documented}
+ #define LCD_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD_POSITION LEFT {documented}
+ #define LCD_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD_ROW 1 {documented}
- 9/12/11 W3SA JJE added code to correct elevation display which was not following A1 input (map function was not working using the variables)
- Added code to keep azimuth and elevation updated if changed from the rotor control unit.
- Added code to handle flipped azimuth of antenna when elevation passes 90 degrees.
- Changed LCD display to display Direction, Azimuth and Elevation of antenna(s) on first line of display and actual Rotor azimuth and elevation on the second line
- Then when the elevation has passed 90 degrees you would get:
- NNE A 15 E 75
- RTR A 195 E 115
- Otherwise it would be
- NNE A 15 E 75
- RTR A 15 E 75
-
-
- 01/02/13 M0CKE added code for a cheap rotary encoder input for setting the azimuth direction, rotary encoder connected to pins 6 & 7 with the center to ground,
- degrees are set by turning the encoder cw or ccw with 1 click being 1 degree if turned slowly or 1 click being 10 degree by turning quickly, this replaces the
- preset pot and can be enabled by uncommenting "#define FEATURE_AZ_PRESET_ENCODER" below.
+ 1.9.2014031001-UNSTABLE
+ OPTION_DISPLAY_DISABLE_DIRECTION_STATUS changed to OPTION_DISPLAY_DIRECTION_STATUS {documented}
+ worked on FEATURE_TWO_DECIMAL_PLACE_HEADINGS
+ LANGUAGE_ENGLISH
-*/
+ 1.9.2014031101-UNSTABLE
+ fixed issue with errant stuff happening, appears to have been from a bad char variable somewhere
+ 1.9.2014031201-UNSTABLE
+ Easycom improvements - space and LF are now also command delimiters. Also fixed bug with one decimal place. Works with PSTRotator
+ Fixed issue with LCD display updating when target az or target el was changed during rotation
+ I2C_LCD_COLOR also applies to Yourduino LCD display
+
+ 1.9.2014031301-UNSTABLE
+ HH-12 elevation bug fix
+
+ 1.9.2014031401-UNSTABLE
+ FEATURE_MASTER_WITH_SERIAL_SLAVE
+ FEATURE_MASTER_WITH_ETHERNET_SLAVE
+ FEATURE_EL_POSITION_MEMSIC_2125 under development - not working yet
+
+ 1.9.2014031501-UNSTABLE
+ fixed a bug with azimuth and elevation offset zeroing out first decimal place
+ 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
+
+ 1.9.2014032201-UNSTABLE
+ Changed master/slave AZ and EL command result format: AZxxx.xxxxxx EL+xxx.xxxxxx
+ Slave CL command
+
+ 1.9.2014032501-UNSTABLE
+ OPTION_SYNC_MASTER_CLOCK_TO_SLAVE
+
+ 1.9.2014032601-UNSTABLE
+ fixed "if (clock_status == SLAVE_SYNC) {clock_status = FREE_RUNNING;}" compile error
+
+ 1.9.2014032701-UNSTABLE
+ more work on FEATURE_EL_POSITION_MEMSIC_2125
+
+ 1.9.2014032801-UNSTABLE
+ more work on FEATURE_EL_POSITION_MEMSIC_2125
+
+ 1.9.2014032802-UNSTABLE
+ OPTION_CLOCK_ALWAYS_HAVE_HOUR_LEADING_ZERO
+
+ 1.9.2014032901-UNSTABLE
+ fixed issue with OPTION_CLOCK_ALWAYS_HAVE_HOUR_LEADING_ZERO
+
+ 1.9.2014040301-UNSTABLE
+ OPTION_DISABLE_HMC5883L_ERROR_CHECKING
+ HARDWARE_EA4TX_ARS_USB
+ HARDWARE_M0UPU
+ rotator_hardware.h file
+ rotator_features_ea4tx_ars_usb.h
+ rotator_pins_ea4tx_ars_usb.h
+ #define AZ_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV 2000.0
+ #define EL_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV 2000.0
+
+ 1.9.2014040501-UNSTABLE
+ FEATURE_EL_POSITION_INCREMENTAL_ENCODER now does 360 degrees of rotation rather than 720
+
+ 1.9.2014040601-UNSTABLE
+ OPTION_PRESET_ENCODER_0_360_DEGREES
+
+ 1.9.2014041001-UNSTABLE
+ more OPTION_PRESET_ENCODER_0_360_DEGREES work
+
+ 1.9.2014041101-UNSTABLE
+ service_rotation() - fixed rollover bug with az and el slow down
+
+ 1.9.2014041201-UNSTABLE
+ Fixed decimal place issue with Easycom AZ and EL query commands
+ FEATURE_EL_POSITION_INCREMENTAL_ENCODER - fixed storage and retrieval of elevation in eeprom
+ Bug fix - stop command wouldn't work when in slow down
+ AZ_INITIALLY_IN_SLOW_DOWN_PWM
+ EL_INITIALLY_IN_SLOW_DOWN_PWM
+
+ 1.9.2014052301-UNSTABLE
+ Fixed compilation error when FEATURE_JOYSTICK_CONTROL is activated and FEATURE_ELEVATION_CONTROL is disabled
+
+ */
+
+#define CODE_VERSION "2.0.2014070201"
#include
#include
-#include
+#include
#include
+#include "rotator_hardware.h"
+#ifdef HARDWARE_EA4TX_ARS_USB
+#include "rotator_features_ea4tx_ars_usb.h"
+#else
#include "rotator_features.h"
-#include "rotator_pins.h"
-
-//#include "pins.h"
-//#include "pins_m0upu.h"
-
-#define CODE_VERSION "2013091101"
-
-
-
-/* -------------------------- rotation settings ---------------------------------------*/
-
-#define AZIMUTH_STARTING_POINT_DEFAULT 180 // the starting point in degrees of the azimuthal rotator
- // (the Yaesu GS-232B Emulation Z command will override this and write the setting to eeprom)
-#define AZIMUTH_ROTATION_CAPABILITY_DEFAULT 450 // the default rotation capability of the rotator in degrees
- // (the Yaesu P36 and P45 commands will override this and write the setting to eeprom)
-#define ELEVATION_MAXIMUM_DEGREES 180 // change this to set the maximum elevation in degrees
-
-
-
-
-
-
-
-
-/* ---------------------------- object declarations ----------------------------------------------
-
- Object declarations are required for several devices, including LCD displays, compass devices, and accelerometers
-
-
-*/
-
-/* uncomment this section for classic 4 bit interface LCD display (in addition to FEATURE_LCD_DISPLAY above) */
-//#define FEATURE_LCD_DISPLAY
-//#include
-//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);
-/* end of classic 4 bit interface LCD display section */
-
-/* uncomment this section for Adafruit I2C LCD display */
-//#define FEATURE_LCD_DISPLAY
-//#define FEATURE_I2C_LCD
-//#include
-//#include
-//Adafruit_RGBLCDShield lcd = Adafruit_RGBLCDShield();
-//#define FEATURE_ADAFRUIT_BUTTONS // Uncomment this to use Adafruit LCD buttons for manual AZ/EL instead of normal buttons
-/* end of Adafruit I2C LCD display */
-
-
-/* uncomment the section for YourDuino.com I2C LCD display */
-//#define FEATURE_LCD_DISPLAY
-//#define FEATURE_I2C_LCD
-//#define OPTION_INITIALIZE_YOURDUINO_I2C
-//#define I2C_ADDR 0x20
-//#define BACKLIGHT_PIN 3
-//#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
-//#define LED_OFF 1
-//#define LED_ON 0
-//#include
-//#include
-//LiquidCrystal_I2C lcd(I2C_ADDR,En_pin,Rw_pin,Rs_pin,D4_pin,D5_pin,D6_pin,D7_pin);
-/* end of of section to uncomment for YourDuino.com I2C LCD display */
-
-/* uncomment the section for DFRobot I2C LCD display */
-//#define FEATURE_LCD_DISPLAY
-//#define FEATURE_I2C_LCD
-//#include
-//LiquidCrystal_I2C lcd(0x27,16,2);
-/* end of of section to uncomment for DFRobot I2C LCD display */
-
-//#include // Uncomment for experimental HMC5883L digital compass support
-//HMC5883L compass; // Uncomment for HMC5883L digital compass support
-
-
-//#include // uncomment for any Adafruit sensors/libraries
-
-//#include // Uncomment for elevation ADXL345 accelerometer using Love Electronics ADXL345 library
-//ADXL345 accel; // Uncomment for elevation ADXL345 accelerometer support using Love Electronics ADXL345 library
-
-//#include // uncomment for elevation ADXL345 accelerometer using Adafruit ADXL345 library
-//Adafruit_ADXL345 accel = Adafruit_ADXL345(12345); // Uncomment for elevation ADXL345 accelerometer support using Adafruit ADXL345 library
-
-//#include // uncomment for azimuth / elevation LSM303 compass / accelerometer
-//Adafruit_LSM303 lsm; // Uncomment for LSM303 support (azimuth and/or elevation) using Adafruit LSM303 library
-
-
-
-/* ---------------------- dependency checking - don't touch this unless you know what you are doing ---------------------*/
-
-
-#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega1284P__) || defined(__AVR_ATmega644P__)
-#define OPTION_SERIAL1_SUPPORT
-#endif
-
-#if defined(__AVR_ATmega2560__)
-#define OPTION_SERIAL2_SUPPORT
-#define OPTION_SERIAL3_SUPPORT
-#endif
-
-
-#if (defined(FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT) || defined(FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT)) && !defined(FEATURE_HOST_REMOTE_PROTOCOL)
-#define FEATURE_HOST_REMOTE_PROTOCOL
-#endif
-
-#if !defined(FEATURE_REMOTE_UNIT_SLAVE) && !defined(FEATURE_YAESU_EMULATION) && !defined(FEATURE_EASYCOM_EMULATION)
-#error "You need to activate FEATURE_YAESU_EMULATION or FEATURE_YAESU_EMULATION or make this unit a remote by activating FEATURE_REMOTE_UNIT_SLAVE"
-#endif
-
-#if defined(FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT) && !defined(OPTION_SERIAL1_SUPPORT)
-#error "You need hardware with Serial1 port for remote unit communications"
-#undef FEATURE_HOST_REMOTE_PROTOCOL
-#undef FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT
-#endif
-
-#if defined(FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT) && !defined(OPTION_SERIAL1_SUPPORT)
-#error "You need hardware with Serial1 port for remote unit communications"
-#undef FEATURE_HOST_REMOTE_PROTOCOL
-#undef FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT
-#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_AZ_POSITION_GET_FROM_REMOTE_UNIT)
-#error "You must turn off FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT if using FEATURE_REMOTE_UNIT_SLAVE"
-#undef FEATURE_HOST_REMOTE_PROTOCOL
-#undef FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT
-#endif //FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT
-
-#if defined(FEATURE_REMOTE_UNIT_SLAVE) && defined(FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT)
-#error "You must turn off FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT if using FEATURE_REMOTE_UNIT_SLAVE"
-#undef FEATURE_HOST_REMOTE_PROTOCOL
-#undef FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT
-#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))
-#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))
-#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_I2C_LCD) && !defined(FEATURE_WIRE_SUPPORT)
-#define FEATURE_WIRE_SUPPORT
-#endif
-
-#if (defined(FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB)||defined(FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB)||defined(FEATURE_EL_POSITION_LSM303)||defined(FEATURE_AZ_POSITION_LSM303)) && !defined(FEATURE_WIRE_SUPPORT)
-#define FEATURE_WIRE_SUPPORT
#endif
+#include "rotator_dependencies.h"
+#ifdef FEATURE_4_BIT_LCD_DISPLAY
+#include // required for classic 4 bit interface LCD display (FEATURE_4_BIT_LCD_DISPLAY)
+#endif // FEATURE_4_BIT_LCD_DISPLAY
#ifdef FEATURE_WIRE_SUPPORT
-#include
-#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"
+#include // required for FEATURE_I2C_LCD, any ADXL345 feature, FEATURE_AZ_POSITION_HMC5883L, FEATURE_EL_POSITION_LSM303
+#endif
+#if defined(FEATURE_ADAFRUIT_I2C_LCD)
+#include // required for Adafruit I2C LCD display
+#include // required for Adafruit I2C LCD display
+#endif
+#if defined(FEATURE_YOURDUINO_I2C_LCD) || defined(FEATURE_RFROBOT_I2C_DISPLAY)
+#include // required for YourDuino.com or DFRobot I2C LCD display
+#endif
+#if defined(FEATURE_YOURDUINO_I2C_LCD)
+#include // required for YourDuino.com I2C LCD display
+#endif
+#if defined(FEATURE_AZ_POSITION_HMC5883L)
+#include // required for HMC5883L digital compass support
+#endif
+#if defined(FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB) || defined(FEATURE_AZ_POSITION_LSM303) || defined(FEATURE_EL_POSITION_LSM303)
+#include // required for any Adafruit sensor libraries
+#endif
+#if defined(FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB)
+#include // required for elevation ADXL345 accelerometer using Love Electronics ADXL345 library
+#endif
+#if defined(FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB)
+#include // required for elevation ADXL345 accelerometer using Adafruit ADXL345 library (FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB)
+#endif
+#if defined(FEATURE_EL_POSITION_LSM303) || defined(FEATURE_AZ_POSITION_LSM303)
+#include // required for azimuth and/or elevation using LSM303 compass and/or accelerometer
+#endif
+#if defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)
+#include "moon2.h"
+#endif // defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)
+#ifdef FEATURE_SUN_TRACKING
+#include "sunpos.h"
+#endif // FEATURE_SUN_TRACKING
+#ifdef FEATURE_GPS
+#include "TinyGPS.h"
+#endif // FEATURE_GPS
+#ifdef FEATURE_RTC_DS1307
+#include "RTClib.h"
+#endif // FEATURE_RTC_DS1307
+#ifdef FEATURE_RTC_PCF8583
+#include "PCF8583.h"
+#endif //FEATURE_RTC_PCF8583
+#ifdef FEATURE_ETHERNET
+#include "SPI.h"
+#include "Ethernet.h"
#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"
+#include "rotator.h"
+#ifdef HARDWARE_EA4TX_ARS_USB
+#include "rotator_pins_ea4tx_ars_usb.h"
#endif
-
-
-#if !defined(FEATURE_ELEVATION_CONTROL) && defined(FEATURE_EL_PRESET_ENCODER)
-#undef FEATURE_EL_PRESET_ENCODER
+#ifdef HARDWARE_M0UPU
+#include "rotator_pins_m0upu.h"
#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)
-#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)
-#error "You must specify one EL position sensor feature"
+#if !defined(HARDWARE_M0UPU) && !defined(HARDWARE_EA4TX_ARS_USB)
+#include "rotator_pins.h"
#endif
+#include "rotator_settings.h"
-#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
+// #include "pins.h" // note to Goody: reload IDE after uncommenting one of these
+// #include "pins_m0upu.h"
-
-/*---------------------- macros - don't touch these unless you know what you are doing ---------------------*/
-#define AZ 1
-#define EL 2
-
-#ifdef FEATURE_ROTARY_ENCODER_SUPPORT
-#define DIR_CCW 0x10 // CW Encoder Code (Do not change)
-#define DIR_CW 0x20 // CCW Encoder Code (Do not change)
-#endif //FEATURE_ROTARY_ENCODER_SUPPORT
-
-#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 1
-#define REQUEST_DOWN 2
-#define REQUEST_ELEVATION 3
-#define REQUEST_KILL 5
-
-#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
-#ifdef FEATURE_ELEVATION_CONTROL
-#define LOADED_AZIMUTHS_ELEVATIONS 3
-#define RUNNING_AZIMUTHS_ELEVATIONS 4
-#endif //FEATURE_ELEVATION_CONTROL
-
-#define LCD_UNDEF 0
-#define LCD_HEADING 1
-#define LCD_DIRECTION 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 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
-
-/* ------end of macros ------- */
-
-/* --------------------------- 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 255
-
-//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
-#define AZ_SLOW_START_STEPS 20
-
-#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
-#define AZ_SLOW_DOWN_PWM_STOP 20 // ending PWM value for slow down
-#define AZ_SLOW_DOWN_STEPS 20
-
-//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
-#define EL_SLOW_START_STEPS 20
-
-#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 TIMED_SLOW_DOWN_TIME 2000
-
-//Variable frequency output settings
-#define AZ_VARIABLE_FREQ_OUTPUT_LOW 1 // Frequency in hertz of minimum speed
-#define AZ_VARIABLE_FREQ_OUTPUT_HIGH 50 // Frequency in hertz of maximum speed
-#define EL_VARIABLE_FREQ_OUTPUT_LOW 1 // Frequency in hertz of minimum speed
-#define EL_VARIABLE_FREQ_OUTPUT_HIGH 50 // 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 1.0
-#define OPERATION_TIMEOUT 60000 // timeout for any rotation operation in mS ; 60 seconds is usually enough unless you have the speed turned down
-#define TIMED_INTERVAL_ARRAY_SIZE 20
-#define SERIAL_BAUD_RATE 115200 //9600 // 9600
-#define SERIAL1_BAUD_RATE 9600 // 9600
-#define SERIAL2_BAUD_RATE 9600 // 9600
-#define SERIAL3_BAUD_RATE 9600 // 9600
-#define LCD_UPDATE_TIME 1000 // LCD update time in milliseconds
-#define AZ_BRAKE_DELAY 3000 // in milliseconds
-#define EL_BRAKE_DELAY 3000 // in milliseconds
-
-#define EEPROM_MAGIC_NUMBER 100
-#define EEPROM_WRITE_DIRTY_CONFIG_TIME 30 //time in seconds
-
-
-#ifdef FEATURE_ONE_DECIMAL_PLACE_HEADINGS
-#define HEADING_MULTIPLIER 10
-#define LCD_HEADING_MULTIPLIER 10.0
-#define LCD_DECIMAL_PLACES 1
-#else //FEATURE_ONE_DECIMAL_PLACE_HEADINGS
-#define HEADING_MULTIPLIER 1
-#define LCD_HEADING_MULTIPLIER 1.0
-#define LCD_DECIMAL_PLACES 0
-#endif //FEATURE_ONE_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 0.0
-#define PARK_ELEVATION 0.0
-
-#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 0 // this does not apply if using FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT
-#define ELEVATION_MEASUREMENT_FREQUENCY_MS 0 // 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
-
/*----------------------- variables -------------------------------------*/
+byte incoming_serial_byte = 0;
+
+#ifdef FEATURE_TWO_DECIMAL_PLACE_HEADINGS
+long azimuth = 0;
+long raw_azimuth = 0;
+long target_azimuth = 0;
+long target_raw_azimuth = 0;
+long azimuth_starting_point = AZIMUTH_STARTING_POINT_DEFAULT;
+long azimuth_rotation_capability = AZIMUTH_ROTATION_CAPABILITY_DEFAULT;
+#else
int azimuth = 0;
int raw_azimuth = 0;
int target_azimuth = 0;
int target_raw_azimuth = 0;
+int azimuth_starting_point = AZIMUTH_STARTING_POINT_DEFAULT;
+int azimuth_rotation_capability = AZIMUTH_ROTATION_CAPABILITY_DEFAULT;
+#endif
-byte incoming_serial_byte = 0;
-byte serial0_buffer[COMMAND_BUFFER_SIZE];
-int serial0_buffer_index = 0;
+
+
+
+byte control_port_buffer[COMMAND_BUFFER_SIZE];
+int control_port_buffer_index = 0;
byte az_state = IDLE;
byte debug_mode = DEFAULT_DEBUG_STATE;
int analog_az = 0;
@@ -666,7 +621,7 @@ byte az_request_queue_state = NONE;
unsigned long az_slowstart_start_time = 0;
byte az_slow_start_step = 0;
-unsigned long az_last_step_time = 0;
+unsigned long az_last_step_time = 0;
byte az_slow_down_step = 0;
unsigned long az_timed_slow_down_start_time = 0;
byte backslash_command = 0;
@@ -676,24 +631,28 @@ struct config_t {
int analog_az_full_ccw;
int analog_az_full_cw;
int analog_el_0_degrees;
- int analog_el_max_elevation;
- int azimuth_starting_point;
- int azimuth_rotation_capability;
+ int analog_el_max_elevation;
+ // int azimuth_starting_point;
+ // int azimuth_rotation_capability;
float last_azimuth;
float last_elevation;
+ int last_az_incremental_encoder_position;
+ int last_el_incremental_encoder_position;
+ float azimuth_offset;
+ float elevation_offset;
} configuration;
-#ifdef FEATURE_TIMED_BUFFER
+#ifdef FEATURE_TIMED_BUFFER
int timed_buffer_azimuths[TIMED_INTERVAL_ARRAY_SIZE];
int timed_buffer_number_entries_loaded = 0;
int timed_buffer_entry_pointer = 0;
int timed_buffer_interval_value_seconds = 0;
unsigned long last_timed_buffer_action_time = 0;
byte timed_buffer_status = 0;
-#endif //FEATURE_TIMED_BUFFER
+#endif // FEATURE_TIMED_BUFFER
byte normal_az_speed_voltage = 0;
byte current_az_speed_voltage = 0;
@@ -709,174 +668,289 @@ byte el_slowstart_active = EL_SLOWSTART_DEFAULT;
byte el_slowdown_active = EL_SLOWDOWN_DEFAULT;
unsigned long el_slowstart_start_time = 0;
byte el_slow_start_step = 0;
-unsigned long el_last_step_time = 0;
+unsigned long el_last_step_time = 0;
byte el_slow_down_step = 0;
unsigned long el_timed_slow_down_start_time = 0;
byte normal_el_speed_voltage = 0;
byte current_el_speed_voltage = 0;
-int display_elevation = 0; // Variable added to handle elevation beyond 90 degrees. /// W3SA
+int display_elevation = 0;
byte el_state = IDLE;
int analog_el = 0;
unsigned long el_last_rotate_initiation = 0;
-#ifdef FEATURE_TIMED_BUFFER
+#ifdef FEATURE_TIMED_BUFFER
int timed_buffer_elevations[TIMED_INTERVAL_ARRAY_SIZE];
-#endif //FEATURE_TIMED_BUFFER
+#endif // FEATURE_TIMED_BUFFER
byte elevation_button_was_pushed = 0;
-#endif
+#endif // FEATURE_ELEVATION_CONTROL
#ifdef FEATURE_LCD_DISPLAY
unsigned long last_lcd_update = 0;
-String last_direction_string;
+String last_row_0_string; // this is only used in update_display(), however if you make it a static within the funtion, the compiler errors out with a strange error
byte push_lcd_update = 0;
-#define LCD_COLUMNS 16
-//#define LCD_COLUMNS 20
-#ifdef FEATURE_I2C_LCD
-#define RED 0x1
-#define YELLOW 0x3
-#define GREEN 0x2
-#define TEAL 0x6
-#define BLUE 0x4
-#define VIOLET 0x5
-#define WHITE 0x7
-byte lcdcolor = GREEN; // default color of I2C LCD display
-#endif //FEATURE_I2C_LCD
-#endif //FEATURE_LCD_DISPLAY
+
+//#ifdef FEATURE_I2C_LCD
+//byte lcdcolor = I2C_LCD_COLOR;
+//#endif // FEATURE_I2C_LCD
+#endif // FEATURE_LCD_DISPLAY
#ifdef FEATURE_ROTARY_ENCODER_SUPPORT
#ifdef OPTION_ENCODER_HALF_STEP_MODE // Use the half-step state table (emits a code at 00 and 11)
const unsigned char ttable[6][4] = {
- {0x3 , 0x2, 0x1, 0x0}, {0x23, 0x0, 0x1, 0x0},
- {0x13, 0x2, 0x0, 0x0}, {0x3 , 0x5, 0x4, 0x0},
- {0x3 , 0x3, 0x4, 0x10}, {0x3 , 0x5, 0x3, 0x20}
+ { 0x3, 0x2, 0x1, 0x0 }, { 0x23, 0x0, 0x1, 0x0 },
+ { 0x13, 0x2, 0x0, 0x0 }, { 0x3, 0x5, 0x4, 0x0 },
+ { 0x3, 0x3, 0x4, 0x10 }, { 0x3, 0x5, 0x3, 0x20 }
};
#else // Use the full-step state table (emits a code at 00 only)
const unsigned char ttable[7][4] = {
- {0x0, 0x2, 0x4, 0x0}, {0x3, 0x0, 0x1, 0x10},
- {0x3, 0x2, 0x0, 0x0}, {0x3, 0x2, 0x1, 0x0},
- {0x6, 0x0, 0x4, 0x0}, {0x6, 0x5, 0x0, 0x10},
- {0x6, 0x5, 0x4, 0x0},
+ { 0x0, 0x2, 0x4, 0x0 }, { 0x3, 0x0, 0x1, 0x10 },
+ { 0x3, 0x2, 0x0, 0x0 }, { 0x3, 0x2, 0x1, 0x0 },
+ { 0x6, 0x0, 0x4, 0x0 }, { 0x6, 0x5, 0x0, 0x10 },
+ { 0x6, 0x5, 0x4, 0x0 },
};
-#endif //OPTION_ENCODER_HALF_STEP_MODE
+#endif // OPTION_ENCODER_HALF_STEP_MODE
#ifdef FEATURE_AZ_PRESET_ENCODER // Rotary Encoder State Tables
+#if defined(FEATURE_ONE_DECIMAL_PLACE_HEADINGS) || defined(FEATURE_TWO_DECIMAL_PLACE_HEADINGS)
+double az_encoder_raw_degrees = 0;
+#else
int az_encoder_raw_degrees = 0;
-#define ENCODER_IDLE 0
-#define ENCODER_AZ_PENDING 1
-#define ENCODER_EL_PENDING 2
-#define ENCODER_AZ_EL_PENDING 3
+#endif
volatile unsigned char az_encoder_state = 0;
#ifdef FEATURE_EL_PRESET_ENCODER
volatile unsigned char el_encoder_state = 0;
+#if defined(FEATURE_ONE_DECIMAL_PLACE_HEADINGS) || defined(FEATURE_TWO_DECIMAL_PLACE_HEADINGS)
+double el_encoder_degrees = 0;
+#else
int el_encoder_degrees = 0;
-#endif //FEATURE_EL_PRESET_ENCODER
+#endif
+#endif // FEATURE_EL_PRESET_ENCODER
byte preset_encoders_state = ENCODER_IDLE;
-#endif //FEATURE_AZ_PRESET_ENCODER
-#endif //FEATURE_ROTARY_ENCODER_SUPPORT
+#endif // FEATURE_AZ_PRESET_ENCODER
+#endif // FEATURE_ROTARY_ENCODER_SUPPORT
#ifdef DEBUG_PROFILE_LOOP_TIME
float average_loop_time = 0;
-#endif //DEBUG_PROFILE_LOOP_TIME
+#endif // DEBUG_PROFILE_LOOP_TIME
#ifdef FEATURE_AZ_POSITION_PULSE_INPUT
volatile float az_position_pulse_input_azimuth = 0;
volatile byte last_known_az_state = 0;
-#endif //FEATURE_AZ_POSITION_PULSE_INPUT
+#endif // FEATURE_AZ_POSITION_PULSE_INPUT
#ifdef FEATURE_EL_POSITION_PULSE_INPUT
volatile float el_position_pulse_input_elevation = 0;
volatile byte last_known_el_state = 0;
-#endif //FEATURE_EL_POSITION_PULSE_INPUT
+#endif // FEATURE_EL_POSITION_PULSE_INPUT
-#ifdef FEATURE_REMOTE_UNIT_SLAVE
-byte serial_read_event_flag[] = {0,0,0,0,0};
-byte serial0_buffer_carriage_return_flag = 0;
+#if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_MASTER_WITH_SERIAL_SLAVE)
+byte serial_read_event_flag[] = { 0, 0, 0, 0, 0 };
+byte control_port_buffer_carriage_return_flag = 0;
#endif
-#ifdef FEATURE_HOST_REMOTE_PROTOCOL
-byte serial1_buffer[COMMAND_BUFFER_SIZE];
-int serial1_buffer_index = 0;
-byte serial1_buffer_carriage_return_flag = 0;
+#if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+byte remote_unit_port_buffer[COMMAND_BUFFER_SIZE];
+int remote_unit_port_buffer_index = 0;
+byte remote_unit_port_buffer_carriage_return_flag = 0;
unsigned long serial1_last_receive_time = 0;
byte remote_unit_command_submitted = 0;
unsigned long last_remote_unit_command_time = 0;
unsigned int remote_unit_command_timeouts = 0;
unsigned int remote_unit_bad_results = 0;
-unsigned int remote_unit_good_results = 0;
+unsigned long remote_unit_good_results = 0;
unsigned int remote_unit_incoming_buffer_timeouts = 0;
byte remote_unit_command_results_available = 0;
float remote_unit_command_result_float = 0;
byte remote_port_rx_sniff = 0;
byte remote_port_tx_sniff = 0;
byte suspend_remote_commands = 0;
-#endif
+#endif //FEATURE_MASTER_WITH_SERIAL_SLAVE
#ifdef DEBUG_POSITION_PULSE_INPUT
-//unsigned int az_position_pule_interrupt_handler_flag = 0;
-//unsigned int el_position_pule_interrupt_handler_flag = 0;
+// unsigned int az_position_pule_interrupt_handler_flag = 0;
+// unsigned int el_position_pule_interrupt_handler_flag = 0;
volatile unsigned long az_pulse_counter = 0;
volatile unsigned long el_pulse_counter = 0;
volatile unsigned int az_pulse_counter_ambiguous = 0;
volatile unsigned int el_pulse_counter_ambiguous = 0;
-#endif //DEBUG_POSITION_PULSE_INPUT
+#endif // DEBUG_POSITION_PULSE_INPUT
-/*
+#ifdef FEATURE_PARK
+byte park_status = NOT_PARKED;
+byte park_serial_initiated = 0;
+#endif // FEATURE_PARK
+
+#ifdef FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
+volatile int az_incremental_encoder_position = 0;
+volatile byte az_3_phase_encoder_last_phase_a_state = 0;
+volatile byte az_3_phase_encoder_last_phase_b_state = 0;
+#ifdef DEBUG_AZ_POSITION_INCREMENTAL_ENCODER
+volatile int az_position_incremental_encoder_interrupt = 0;
+#endif // DEBUG_AZ_POSITION_INCREMENTAL_ENCODER
+#endif // FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
+
+#ifdef FEATURE_EL_POSITION_INCREMENTAL_ENCODER
+volatile int el_incremental_encoder_position = 0;
+volatile byte el_3_phase_encoder_last_phase_a_state = 0;
+volatile byte el_3_phase_encoder_last_phase_b_state = 0;
+#ifdef DEBUG_EL_POSITION_INCREMENTAL_ENCODER
+volatile int el_position_incremental_encoder_interrupt = 0;
+#endif // DEBUG_EL_POSITION_INCREMENTAL_ENCODER
+#endif // FEATURE_EL_POSITION_INCREMENTAL_ENCODER
+
+#if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION) || defined(FEATURE_CLOCK)
+HardwareSerial * control_port;
+#endif
+
+#if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE)
+HardwareSerial * remote_unit_port;
+#endif
+
+#if defined(FEATURE_GPS)
+HardwareSerial * gps_port;
+#ifdef GPS_MIRROR_PORT
+HardwareSerial * (gps_mirror_port);
+#endif //GPS_MIRROR_PORT
+#endif //defined(FEATURE_GPS)
+
+#if defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)
+double latitude = DEFAULT_LATITUDE;
+double longitude = DEFAULT_LONGITUDE;
+#endif
+
+
+#ifdef FEATURE_MOON_TRACKING
+byte moon_tracking_active = 0;
+byte moon_visible = 0;
+double moon_azimuth = 0;
+double moon_elevation = 0;
+#endif // FEATURE_MOON_TRACKING
+
+#ifdef FEATURE_SUN_TRACKING
+float sun_azimuth = 0;
+float sun_elevation = 0;
+cTime c_time;
+cLocation c_loc;
+cSunCoordinates c_sposn;
+byte sun_visible = 0;
+byte sun_tracking_active = 0;
+#endif // FEATURE_SUN_TRACKING
+
+#ifdef FEATURE_CLOCK
+unsigned long clock_years = 0;
+unsigned long clock_months = 0;
+unsigned long clock_days = 0;
+unsigned long clock_hours = 0;
+unsigned long clock_minutes = 0;
+unsigned long clock_seconds = 0;
+int clock_year_set = 2014;
+byte clock_month_set = 1;
+byte clock_day_set = 1;
+byte clock_sec_set = 0;
+unsigned long clock_hour_set = 0;
+unsigned long clock_min_set = 0;
+unsigned long millis_at_last_calibration = 0;
+#endif // FEATURE_CLOCK
+
+#if defined(FEATURE_GPS) || defined(FEATURE_RTC) || defined(FEATURE_CLOCK)
+byte clock_status = FREE_RUNNING;
+#endif // defined(FEATURE_GPS) || defined(FEATURE_RTC)
+
+#ifdef FEATURE_GPS
+byte gps_data_available = 0;
+#endif // FEATURE_GPS
+
+#ifdef FEATURE_ETHERNET
+byte mac[] = {ETHERNET_MAC_ADDRESS};
+IPAddress ip(ETHERNET_IP_ADDRESS);
+IPAddress gateway(ETHERNET_IP_GATEWAY);
+IPAddress subnet(ETHERNET_IP_SUBNET_MASK);
+EthernetClient ethernetclient0;
+EthernetServer ethernetserver0(ETHERNET_TCP_PORT_0);
+#ifdef ETHERNET_TCP_PORT_1
+EthernetClient ethernetclient1;
+EthernetServer ethernetserver1(ETHERNET_TCP_PORT_1);
+#endif //ETHERNET_TCP_PORT_1
+#ifdef FEATURE_MASTER_WITH_ETHERNET_SLAVE
+EthernetClient ethernetslavelinkclient0;
+IPAddress slave_unit_ip(ETHERNET_SLAVE_IP_ADDRESS);
+byte ethernetslavelinkclient0_state = ETHERNET_SLAVE_DISCONNECTED;
+unsigned int ethernet_slave_reconnects = 0;
+#endif //FEATURE_MASTER_WITH_ETHERNET_SLAVE
+#endif //FEATURE_ETHERNET
+
+#ifdef FEATURE_POWER_SWITCH
+unsigned long last_activity_time = 0;
+#endif //FEATURE_POWER_SWITCH
+
+#ifdef FEATURE_STEPPER_MOTOR
+byte az_stepper_motor_last_direction = STEPPER_UNDEF;
+byte az_stepper_motor_last_pin_state = LOW;
+#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
+unsigned long az_stepper_pulse_period_us = 0;
+unsigned long az_stepper_pulses_remaining = 0;
+#ifdef FEATURE_ELEVATION_CONTROL
+unsigned long el_stepper_pulse_period_us = 0;
+unsigned long el_stepper_pulses_remaining = 0;
+#endif //FEATURE_ELEVATION_CONTROL
+#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
+#ifdef FEATURE_ELEVATION_CONTROL
+byte el_stepper_motor_last_direction = STEPPER_UNDEF;
+byte el_stepper_motor_last_pin_state = LOW;
+#endif //FEATURE_ELEVATION_CONTROL
+#endif //FEATURE_STEPPER_MOTOR
- 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!
-*/
#ifdef FEATURE_AZIMUTH_CORRECTION
-float azimuth_calibration_from[] = {180, 630}; /* these are in "raw" degrees, i.e. when going east past 360 degrees, add 360 degrees*/
-float azimuth_calibration_to[] = {180, 630};
-#endif //FEATURE_AZIMUTH_CORRECTION
+float azimuth_calibration_from[] = AZIMUTH_CALIBRATION_FROM_ARRAY;
+float azimuth_calibration_to[] = AZIMUTH_CALIBRATION_TO_ARRAY;
+#endif // FEATURE_AZIMUTH_CORRECTION
#ifdef FEATURE_ELEVATION_CORRECTION
-float elevation_calibration_from[] = {-180, 0, 180};
-float elevation_calibration_to[] = { 180, 0, 180};
-#endif //FEATURE_ELEVATION_CORRECTION
+float elevation_calibration_from[] = ELEVATION_CALIBRATION_FROM_ARRAY;
+float elevation_calibration_to[] = ELEVATION_CALIBRATION_TO_ARRAY;
+#endif // FEATURE_ELEVATION_CORRECTION
/* ------------------ let's start doing some stuff now that we got the formalities out of the way --------------------*/
void setup() {
-
+
delay(1000);
initialize_serial();
initialize_peripherals();
- read_settings_from_eeprom();
-
- initialize_pins();
-
- read_azimuth();
- #ifdef FEATURE_YAESU_EMULATION
- report_current_azimuth(); // Yaesu - report the azimuth right off the bat without a C command; the Arduino doesn't wake up quick enough
- // to get first C command from HRD and if HRD doesn't see anything it doesn't connect
- #endif //FEATURE_YAESU_EMULATION
+ read_settings_from_eeprom();
- #ifdef FEATURE_TIMED_BUFFER
+ initialize_pins();
+
+ read_azimuth(0);
+ #ifdef FEATURE_YAESU_EMULATION
+ //report_current_azimuth(); // Yaesu - report the azimuth right off the bat without a C command; the Arduino doesn't wake up quick enough
+ // to get first C command from HRD and if HRD doesn't see anything it doesn't connect
+ #endif // FEATURE_YAESU_EMULATION
+
+ #ifdef FEATURE_TIMED_BUFFER
timed_buffer_status = EMPTY;
- #endif //FEATURE_TIMED_BUFFER
-
+ #endif // FEATURE_TIMED_BUFFER
+
#ifdef FEATURE_LCD_DISPLAY
initialize_display();
#endif
-
- initialize_rotary_encoders();
-
+
+ initialize_rotary_encoders();
+
initialize_interrupts();
-
-}
+
+} /* setup */
/*-------------------------- here's where the magic happens --------------------------------*/
void loop() {
-
+
check_serial();
read_headings();
#ifndef FEATURE_REMOTE_UNIT_SLAVE
@@ -885,7 +959,7 @@ void loop() {
az_check_operation_timeout();
#ifdef FEATURE_TIMED_BUFFER
check_timed_interval();
- #endif //FEATURE_TIMED_BUFFER
+ #endif // FEATURE_TIMED_BUFFER
read_headings();
check_buttons();
check_overlap();
@@ -893,16 +967,16 @@ void loop() {
#ifdef FEATURE_ELEVATION_CONTROL
el_check_operation_timeout();
#endif
- #endif //ndef FEATURE_REMOTE_UNIT_SLAVE
+ #endif // ndef FEATURE_REMOTE_UNIT_SLAVE
read_headings();
#ifdef FEATURE_LCD_DISPLAY
update_display();
#endif
-
+
read_headings();
-
+
#ifndef FEATURE_REMOTE_UNIT_SLAVE
#ifdef OPTION_AZ_MANUAL_ROTATE_LIMITS
check_az_manual_rotate_limit();
@@ -912,143 +986,186 @@ void loop() {
#ifdef OPTION_EL_MANUAL_ROTATE_LIMITS
check_el_manual_rotate_limit();
#endif
-
+
check_az_speed_pot();
-
+
#ifdef FEATURE_AZ_PRESET_ENCODER // Rotary Encoder or Preset Selector
check_preset_encoders();
#else
check_az_preset_potentiometer();
- #endif //FEATURE_AZ_PRESET_ENCODER
- #endif //ndef FEATURE_REMOTE_UNIT_SLAVE
-
+ #endif // FEATURE_AZ_PRESET_ENCODER
+ #endif // ndef FEATURE_REMOTE_UNIT_SLAVE
+
+ #ifdef DEBUG_DUMP
output_debug();
-
+ #endif //DEBUG_DUMP
+
check_for_dirty_configuration();
-
+
read_headings();
-
+
+ #ifdef DEBUG_PROFILE_LOOP_TIME
profile_loop_time();
-
- #ifdef FEATURE_REMOTE_UNIT_SLAVE
+ #endif //DEBUG_PROFILE_LOOP_TIME
+
+ #ifdef FEATURE_REMOTE_UNIT_SLAVE
service_remote_unit_serial_buffer();
- #endif //FEATURE_REMOTE_UNIT_SLAVE
-
- #ifdef FEATURE_HOST_REMOTE_PROTOCOL
- service_remote_communications_incoming_serial_buffer();
- #endif //FEATURE_HOST_REMOTE_PROTOCOL
+ #endif // FEATURE_REMOTE_UNIT_SLAVE
+
+ #if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+ service_remote_communications_incoming_buffer();
+ #endif // defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
#ifdef FEATURE_JOYSTICK_CONTROL
check_joystick();
- #endif //FEATURE_JOYSTICK_CONTROL
+ #endif // FEATURE_JOYSTICK_CONTROL
#ifdef FEATURE_ROTATION_INDICATOR_PIN
service_rotation_indicator_pin();
- #endif //FEATURE_ROTATION_INDICATOR_PIN
-
+ #endif // FEATURE_ROTATION_INDICATOR_PIN
+
+ #ifdef FEATURE_PARK
+ service_park();
+ #endif // FEATURE_PARK
+
+ #ifdef FEATURE_LIMIT_SENSE
+ check_limit_sense();
+ #endif // FEATURE_LIMIT_SENSE
+
+ #ifdef FEATURE_MOON_TRACKING
+ service_moon_tracking();
+ #endif // FEATURE_MOON_TRACKING
+
+ #ifdef FEATURE_SUN_TRACKING
+ service_sun_tracking();
+ #endif // FEATURE_SUN_TRACKING
+
+ #ifdef FEATURE_GPS
+ service_gps();
+ #endif // FEATURE_GPS
+
+ #ifdef FEATURE_RTC
+ service_rtc();
+ #endif // FEATURE_RTC
+
+ #ifdef FEATURE_ETHERNET
+ service_ethernet();
+ #endif // FEATURE_ETHERNET
+
+ #ifdef FEATURE_POWER_SWITCH
+ service_power_switch();
+ #endif //FEATURE_POWER_SWITCH
+
+ #if defined(FEATURE_CLOCK) && defined(OPTION_SYNC_MASTER_CLOCK_TO_SLAVE) && (defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE))
+ sync_master_clock_to_slave();
+ #endif
+
service_blink_led();
-}
+} /* loop */
/* -------------------------------------- subroutines -----------------------------------------------
-
- Where the real work happens...
-
-*/
+ *
+ * Where the real work happens...
+ *
+ */
void read_headings(){
-
- read_azimuth();
-
+
+ read_azimuth(0);
+
#ifdef FEATURE_ELEVATION_CONTROL
- read_elevation();
+ read_elevation(0);
#endif
-
+
}
-//--------------------------------------------------------------
+// --------------------------------------------------------------
void service_blink_led(){
-
+
+
+ #ifdef blink_led
static unsigned long last_blink_led_transition = 0;
static byte blink_led_status = 0;
-
- #ifdef blink_led
- if ((millis() - last_blink_led_transition) >= 1000){
- if (blink_led_status){
- digitalWrite(blink_led,LOW);
- blink_led_status = 0;
+
+
+ if (((millis() - last_blink_led_transition) >= 1000) && (blink_led != 0)) {
+ if (blink_led_status) {
+ digitalWriteEnhanced(blink_led, LOW);
+ blink_led_status = 0;
} else {
- digitalWrite(blink_led,HIGH);
+ digitalWriteEnhanced(blink_led, HIGH);
blink_led_status = 1;
}
last_blink_led_transition = millis();
}
-
- #endif //blink_led
-
-}
+ #endif // blink_led
-//--------------------------------------------------------------
+} /* service_blink_led */
+
+
+// --------------------------------------------------------------
+#ifdef DEBUG_PROFILE_LOOP_TIME
void profile_loop_time(){
- #ifdef DEBUG_PROFILE_LOOP_TIME
static unsigned long last_time = 0;
static unsigned long last_print_time = 0;
-
- average_loop_time = (average_loop_time + (millis()-last_time))/2.0;
+
+ average_loop_time = (average_loop_time + (millis() - last_time)) / 2.0;
last_time = millis();
-
- if (debug_mode){
- if ((millis()-last_print_time) > 1000){
- Serial.print(F("avg loop time: "));
- Serial.println(average_loop_time,2);
+
+ if (debug_mode) {
+ if ((millis() - last_print_time) > 1000) {
+ debug_print("avg loop time: ");
+ debug_print_float(average_loop_time, 2);
+ debug_println("");
last_print_time = millis();
}
}
- #endif //DEBUG_PROFILE_LOOP_TIME
-
-
-}
-//--------------------------------------------------------------
+} /* profile_loop_time */
+
+#endif //DEBUG_PROFILE_LOOP_TIME
+// --------------------------------------------------------------
void check_az_speed_pot() {
-
+
static unsigned long last_pot_check_time = 0;
int pot_read = 0;
byte new_azimuth_speed_voltage = 0;
-
-
- if (az_speed_pot && azimuth_speed_voltage && ((millis() - last_pot_check_time) > 500)) {
- pot_read = analogRead(az_speed_pot);
+
+
+ if (az_speed_pot && azimuth_speed_voltage && ((millis() - last_pot_check_time) > 500)) {
+ pot_read = analogReadEnhanced(az_speed_pot);
new_azimuth_speed_voltage = map(pot_read, SPEED_POT_LOW, SPEED_POT_HIGH, SPEED_POT_LOW_MAP, SPEED_POT_HIGH_MAP);
if (new_azimuth_speed_voltage != normal_az_speed_voltage) {
#ifdef DEBUG_AZ_SPEED_POT
if (debug_mode) {
- Serial.print(F("check_az_speed_pot: normal_az_speed_voltage: "));
- Serial.print(normal_az_speed_voltage);
- Serial.print(F(" new_azimuth_speed_voltage:"));
- Serial.println(new_azimuth_speed_voltage);
- }
- #endif //DEBUG_AZ_SPEED_POT
- //analogWrite(azimuth_speed_voltage, new_azimuth_speed_voltage);
- normal_az_speed_voltage = new_azimuth_speed_voltage;
+ debug_print("check_az_speed_pot: normal_az_speed_voltage: ");
+ debug_print_int(normal_az_speed_voltage);
+ debug_print(" new_azimuth_speed_voltage:");
+ debug_print_int(new_azimuth_speed_voltage);
+ debug_println("");
+ }
+ #endif // DEBUG_AZ_SPEED_POT
+ // analogWriteEnhanced(azimuth_speed_voltage, new_azimuth_speed_voltage);
+ normal_az_speed_voltage = new_azimuth_speed_voltage;
update_az_variable_outputs(normal_az_speed_voltage);
#if defined(OPTION_EL_SPEED_FOLLOWS_AZ_SPEED) && defined(FEATURE_ELEVATION_CONTROL)
- normal_el_speed_voltage = new_azimuth_speed_voltage;
+ normal_el_speed_voltage = new_azimuth_speed_voltage;
update_el_variable_outputs(normal_el_speed_voltage);
- #endif //OPTION_EL_SPEED_FOLLOWS_AZ_SPEED
+ #endif // OPTION_EL_SPEED_FOLLOWS_AZ_SPEED
}
- last_pot_check_time = millis();
+ last_pot_check_time = millis();
}
-
-}
-//--------------------------------------------------------------
+
+} /* check_az_speed_pot */
+// --------------------------------------------------------------
void check_az_preset_potentiometer() {
-
+
byte check_pot = 0;
static unsigned long last_pot_check_time = 0;
@@ -1058,142 +1175,213 @@ void check_az_preset_potentiometer() {
byte button_read = 0;
static byte pot_changed_waiting = 0;
- if (az_preset_pot){
+ if (az_preset_pot) {
if (last_pot_read == 9999) { // initialize last_pot_read the first time we hit this subroutine
- last_pot_read = analogRead(az_preset_pot);
+ last_pot_read = analogReadEnhanced(az_preset_pot);
}
-
+
if (!pot_changed_waiting) {
if (preset_start_button) { // if we have a preset start button, check it
- button_read = digitalRead(preset_start_button);
- if (button_read == LOW) {check_pot = 1;}
+ button_read = digitalReadEnhanced(preset_start_button);
+ if (button_read == BUTTON_ACTIVE_STATE) {
+ check_pot = 1;
+ }
} else { // if not, check the pot every 500 mS
- if ((millis() - last_pot_check_time) < 250) {check_pot = 1;}
- }
+ if ((millis() - last_pot_check_time) < 250) {
+ check_pot = 1;
+ }
+ }
if (check_pot) {
- pot_read = analogRead(az_preset_pot);
+ pot_read = analogReadEnhanced(az_preset_pot);
new_pot_azimuth = map(pot_read, AZ_PRESET_POT_FULL_CW, AZ_PRESET_POT_FULL_CCW, AZ_PRESET_POT_FULL_CW_MAP, AZ_PRESET_POT_FULL_CCW_MAP);
- if ((abs(last_pot_read - pot_read) > 4) && (abs(new_pot_azimuth - (raw_azimuth/HEADING_MULTIPLIER)) > AZIMUTH_TOLERANCE)) {
+ if ((abs(last_pot_read - pot_read) > 4) && (abs(new_pot_azimuth - (raw_azimuth / HEADING_MULTIPLIER)) > AZIMUTH_TOLERANCE)) {
pot_changed_waiting = 1;
- if (debug_mode) {Serial.println(F("check_az_preset_potentiometer: in pot_changed_waiting"));}
+ #ifdef DEBUG_AZ_PRESET_POT
+ if (debug_mode) {
+ debug_println("check_az_preset_potentiometer: in pot_changed_waiting");
+ }
+ #endif // DEBUG_AZ_PRESET_POT
last_pot_read = pot_read;
- }
+ }
}
last_pot_check_time = millis();
} else { // we're in pot change mode
- pot_read = analogRead(az_preset_pot);
+ pot_read = analogReadEnhanced(az_preset_pot);
if (abs(pot_read - last_pot_read) > 3) { // if the pot has changed, reset the timer
last_pot_check_time = millis();
last_pot_read = pot_read;
- } else {
+ } else {
if ((millis() - last_pot_check_time) >= 250) { // has it been awhile since the last pot change?
new_pot_azimuth = map(pot_read, AZ_PRESET_POT_FULL_CW, AZ_PRESET_POT_FULL_CCW, AZ_PRESET_POT_FULL_CW_MAP, AZ_PRESET_POT_FULL_CCW_MAP);
#ifdef DEBUG_AZ_PRESET_POT
if (debug_mode) {
- Serial.print(F("check_az_preset_potentiometer: pot change - current raw_azimuth: "));
- Serial.print(raw_azimuth/HEADING_MULTIPLIER);
- Serial.print(F(" new_azimuth: "));
- Serial.println(new_pot_azimuth);
+ debug_print("check_az_preset_potentiometer: pot change - current raw_azimuth: ");
+ debug_print_float(raw_azimuth / HEADING_MULTIPLIER,0);
+ debug_print(" new_azimuth: ");
+ debug_print_int(new_pot_azimuth);
+ debug_println("");
}
- #endif //DEBUG_AZ_PRESET_POT
- submit_request(AZ,REQUEST_AZIMUTH_RAW,new_pot_azimuth*HEADING_MULTIPLIER);
+ #endif // DEBUG_AZ_PRESET_POT
+ submit_request(AZ, REQUEST_AZIMUTH_RAW, new_pot_azimuth * HEADING_MULTIPLIER, 44);
pot_changed_waiting = 0;
last_pot_read = pot_read;
last_pot_check_time = millis();
}
}
- }
- } //if (az_preset_pot)
-}
-//--------------------------------------------------------------
+ }
+ } // if (az_preset_pot)
+} /* check_az_preset_potentiometer */
+// --------------------------------------------------------------
void initialize_rotary_encoders(){
-
+
#ifdef FEATURE_AZ_PRESET_ENCODER
- pinMode(az_rotary_preset_pin1, INPUT);
- pinMode(az_rotary_preset_pin2, INPUT);
+ pinModeEnhanced(az_rotary_preset_pin1, INPUT);
+ pinModeEnhanced(az_rotary_preset_pin2, INPUT);
az_encoder_raw_degrees = raw_azimuth;
#ifdef OPTION_ENCODER_ENABLE_PULLUPS
- digitalWrite(az_rotary_preset_pin1, HIGH);
- digitalWrite(az_rotary_preset_pin2, HIGH);
- #endif //OPTION_ENCODER_ENABLE_PULLUPS
- #endif //FEATURE_AZ_PRESET_ENCODER
-
-
+ digitalWriteEnhanced(az_rotary_preset_pin1, HIGH);
+ digitalWriteEnhanced(az_rotary_preset_pin2, HIGH);
+ #endif // OPTION_ENCODER_ENABLE_PULLUPS
+ #endif // FEATURE_AZ_PRESET_ENCODER
+
+
#ifdef FEATURE_EL_PRESET_ENCODER
- pinMode(el_rotary_preset_pin1, INPUT);
- pinMode(el_rotary_preset_pin2, INPUT);
+ pinModeEnhanced(el_rotary_preset_pin1, INPUT);
+ pinModeEnhanced(el_rotary_preset_pin2, INPUT);
el_encoder_degrees = elevation;
#ifdef OPTION_ENCODER_ENABLE_PULLUPS
- digitalWrite(el_rotary_preset_pin1, HIGH);
- digitalWrite(el_rotary_preset_pin2, HIGH);
- #endif //OPTION_ENCODER_ENABLE_PULLUPS
- #endif //FEATURE_EL_PRESET_ENCODER
-
+ digitalWriteEnhanced(el_rotary_preset_pin1, HIGH);
+ digitalWriteEnhanced(el_rotary_preset_pin2, HIGH);
+ #endif // OPTION_ENCODER_ENABLE_PULLUPS
+ #endif // FEATURE_EL_PRESET_ENCODER
+
#ifdef FEATURE_AZ_POSITION_ROTARY_ENCODER
- pinMode(az_rotary_position_pin1, INPUT);
- pinMode(az_rotary_position_pin2, INPUT);
+ pinModeEnhanced(az_rotary_position_pin1, INPUT);
+ pinModeEnhanced(az_rotary_position_pin2, INPUT);
#ifdef OPTION_ENCODER_ENABLE_PULLUPS
- digitalWrite(az_rotary_position_pin1, HIGH);
- digitalWrite(az_rotary_position_pin2, HIGH);
- #endif //OPTION_ENCODER_ENABLE_PULLUPS
- #endif //FEATURE_AZ_POSITION_ROTARY_ENCODER
-
-
+ digitalWriteEnhanced(az_rotary_position_pin1, HIGH);
+ digitalWriteEnhanced(az_rotary_position_pin2, HIGH);
+ #endif // OPTION_ENCODER_ENABLE_PULLUPS
+ #endif // FEATURE_AZ_POSITION_ROTARY_ENCODER
+
+
#ifdef FEATURE_EL_POSITION_ROTARY_ENCODER
- pinMode(el_rotary_position_pin1, INPUT);
- pinMode(el_rotary_position_pin2, INPUT);
+ pinModeEnhanced(el_rotary_position_pin1, INPUT);
+ pinModeEnhanced(el_rotary_position_pin2, INPUT);
#ifdef OPTION_ENCODER_ENABLE_PULLUPS
- digitalWrite(el_rotary_position_pin1, HIGH);
- digitalWrite(el_rotary_position_pin2, HIGH);
- #endif //OPTION_ENCODER_ENABLE_PULLUPS
- #endif //FEATURE_EL_POSITION_ROTARY_ENCODER
-
-
-
-}
+ digitalWriteEnhanced(el_rotary_position_pin1, HIGH);
+ digitalWriteEnhanced(el_rotary_position_pin2, HIGH);
+ #endif // OPTION_ENCODER_ENABLE_PULLUPS
+ #endif // FEATURE_EL_POSITION_ROTARY_ENCODER
-//--------------------------------------------------------------
+ #ifdef FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
+ pinMode(az_incremental_encoder_pin_phase_a, INPUT);
+ pinMode(az_incremental_encoder_pin_phase_b, INPUT);
+ pinMode(az_incremental_encoder_pin_phase_z, INPUT);
+ #ifdef OPTION_INCREMENTAL_ENCODER_PULLUPS
+ digitalWrite(az_incremental_encoder_pin_phase_a, HIGH);
+ digitalWrite(az_incremental_encoder_pin_phase_b, HIGH);
+ digitalWrite(az_incremental_encoder_pin_phase_z, HIGH);
+ #endif // OPTION_INCREMENTAL_ENCODER_PULLUPS
+ attachInterrupt(AZ_POSITION_INCREMENTAL_ENCODER_A_PIN_INTERRUPT, az_position_incremental_encoder_interrupt_handler, CHANGE);
+ attachInterrupt(AZ_POSITION_INCREMENTAL_ENCODER_B_PIN_INTERRUPT, az_position_incremental_encoder_interrupt_handler, CHANGE);
+ delay(250);
+ az_3_phase_encoder_last_phase_a_state = digitalRead(az_incremental_encoder_pin_phase_a);
+ az_3_phase_encoder_last_phase_b_state = digitalRead(az_incremental_encoder_pin_phase_b);
+ #endif // FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
+
+ #ifdef FEATURE_EL_POSITION_INCREMENTAL_ENCODER
+ pinMode(el_incremental_encoder_pin_phase_a, INPUT);
+ pinMode(el_incremental_encoder_pin_phase_b, INPUT);
+ pinMode(el_incremental_encoder_pin_phase_z, INPUT);
+ #ifdef OPTION_INCREMENTAL_ENCODER_PULLUPS
+ digitalWrite(el_incremental_encoder_pin_phase_a, HIGH);
+ digitalWrite(el_incremental_encoder_pin_phase_b, HIGH);
+ digitalWrite(el_incremental_encoder_pin_phase_z, HIGH);
+ #endif // OPTION_INCREMENTAL_ENCODER_PULLUPS
+ attachInterrupt(EL_POSITION_INCREMENTAL_ENCODER_A_PIN_INTERRUPT, el_position_incremental_encoder_interrupt_handler, CHANGE);
+ attachInterrupt(EL_POSITION_INCREMENTAL_ENCODER_B_PIN_INTERRUPT, el_position_incremental_encoder_interrupt_handler, CHANGE);
+ delay(250);
+ el_3_phase_encoder_last_phase_a_state = digitalRead(el_incremental_encoder_pin_phase_a);
+ el_3_phase_encoder_last_phase_b_state = digitalRead(el_incremental_encoder_pin_phase_b);
+ #endif // FEATURE_EL_POSITION_INCREMENTAL_ENCODER
+
+} /* initialize_rotary_encoders */
+
+
+// --------------------------------------------------------------
#ifdef FEATURE_AZ_PRESET_ENCODER
void check_preset_encoders(){
-
+
static unsigned long last_encoder_change_time = 0;
- byte button_read = 0;
+ byte button_read = HIGH;
byte number_columns = 0;
static byte submit_encoder_change = 0;
static unsigned long last_preset_start_button_start = 0;
static unsigned long last_preset_start_button_kill = 0;
static unsigned long last_encoder_move = 0;
-
- #ifdef FEATURE_AZ_PRESET_ENCODER
- static unsigned long az_timestamp[5];
- #endif //FEATURE_AZ_PRESET_ENCODER
-
- #ifdef FEATURE_EL_PRESET_ENCODER
- static unsigned long el_timestamp[5];
- #endif //FEATURE_EL_PRESET_ENCODER
#ifdef FEATURE_AZ_PRESET_ENCODER
- az_encoder_state = ttable[az_encoder_state & 0xf][((digitalRead(az_rotary_preset_pin2) << 1) | digitalRead(az_rotary_preset_pin1))];
- unsigned char az_encoder_result = az_encoder_state & 0x30;
- #endif //FEATURE_AZ_PRESET_ENCODER
-
+ static unsigned long az_timestamp[5];
+ #endif // FEATURE_AZ_PRESET_ENCODER
+
#ifdef FEATURE_EL_PRESET_ENCODER
- el_encoder_state = ttable[el_encoder_state & 0xf][((digitalRead(el_rotary_preset_pin2) << 1) | digitalRead(el_rotary_preset_pin1))];
- unsigned char el_encoder_result = el_encoder_state & 0x30;
- #endif //FEATURE_EL_PRESET_ENCODER
-
+ static unsigned long el_timestamp[5];
+ #endif // FEATURE_EL_PRESET_ENCODER
+
#ifdef FEATURE_AZ_PRESET_ENCODER
- if (az_encoder_result) { // If rotary encoder modified
+ az_encoder_state = ttable[az_encoder_state & 0xf][((digitalReadEnhanced(az_rotary_preset_pin2) << 1) | digitalReadEnhanced(az_rotary_preset_pin1))];
+ unsigned char az_encoder_result = az_encoder_state & 0x30;
+ #ifdef DEBUG_PRESET_ENCODERS
+ static byte last_az_rotary_preset_pin1 = 0;
+ static byte last_az_rotary_preset_pin2 = 0;
+
+ if ((debug_mode) && (( last_az_rotary_preset_pin1 != digitalReadEnhanced(az_rotary_preset_pin1)) || ( last_az_rotary_preset_pin2 != digitalReadEnhanced(az_rotary_preset_pin2)))) {
+ debug_print("check_preset_encoders: az_rotary_preset_pin1: ");
+ debug_print_int(digitalReadEnhanced(az_rotary_preset_pin1));
+ debug_print(" az_rotary_preset_pin2: ");
+ debug_print_int(digitalReadEnhanced(az_rotary_preset_pin2));
+ debug_print(" encoder_result: ");
+ debug_print_int(az_encoder_result);
+ debug_println("");
+ }
+ last_az_rotary_preset_pin1 = digitalReadEnhanced(az_rotary_preset_pin1);
+ last_az_rotary_preset_pin2 = digitalReadEnhanced(az_rotary_preset_pin2);
+ #endif // DEBUG_PRESET_ENCODERS
+
+ #endif // FEATURE_AZ_PRESET_ENCODER
+
+ #ifdef FEATURE_EL_PRESET_ENCODER
+ el_encoder_state = ttable[el_encoder_state & 0xf][((digitalReadEnhanced(el_rotary_preset_pin2) << 1) | digitalReadEnhanced(el_rotary_preset_pin1))];
+ unsigned char el_encoder_result = el_encoder_state & 0x30;
+ #endif // FEATURE_EL_PRESET_ENCODER
+
+ #ifdef FEATURE_AZ_PRESET_ENCODER
+ if (az_encoder_result) { // If rotary encoder modified
az_timestamp[0] = az_timestamp[1]; // Encoder step timer
- az_timestamp[1] = az_timestamp[2];
- az_timestamp[2] = az_timestamp[3];
- az_timestamp[3] = az_timestamp[4];
+ az_timestamp[1] = az_timestamp[2];
+ az_timestamp[2] = az_timestamp[3];
+ az_timestamp[3] = az_timestamp[4];
az_timestamp[4] = millis();
-
+
last_encoder_move = millis();
-
+
+
+ #ifdef DEBUG_PRESET_ENCODERS
+ char tempchar[12] = "";
+ if (debug_mode) {
+ debug_print("check_preset_encoders: az_timestamps:");
+ for (int y = 0; y < 5; y++) {
+ debug_print(" ");
+ dtostrf(az_timestamp[y],0,0,tempchar);
+ debug_print(tempchar);
+ }
+ debug_println("");
+ }
+ #endif // DEBUG_PRESET_ENCODERS
+
unsigned long az_elapsed_time = (az_timestamp[4] - az_timestamp[0]); // Encoder step time difference for 10's step
#ifdef OPTION_PRESET_ENCODER_RELATIVE_CHANGE
@@ -1204,33 +1392,85 @@ void check_preset_encoders(){
az_encoder_raw_degrees = raw_azimuth;
}
}
- #endif //OPTION_PRESET_ENCODER_RELATIVE_CHANGE
-
- //bbbbbb
-
- if (az_encoder_result == DIR_CW) {
- if (az_elapsed_time < 250 /* mSec */) {az_encoder_raw_degrees += (5*HEADING_MULTIPLIER);} else {az_encoder_raw_degrees += (1*HEADING_MULTIPLIER);}; // Single deg increase unless encoder turned quickly then 10's step
- //if (az_encoder_raw_degrees >=(360*HEADING_MULTIPLIER)) {az_encoder_raw_degrees -= (360*HEADING_MULTIPLIER);};
- if (az_encoder_raw_degrees >((configuration.azimuth_starting_point+configuration.azimuth_rotation_capability)*HEADING_MULTIPLIER)) {
- az_encoder_raw_degrees =
- ((configuration.azimuth_starting_point*HEADING_MULTIPLIER)
- /* + ((configuration.azimuth_starting_point+configuration.azimuth_rotation_capability)*HEADING_MULTIPLIER) - az_encoder_raw_degrees*/);
- }
+ #endif // OPTION_PRESET_ENCODER_RELATIVE_CHANGE
+
+ // bbbbbb
+
+ #ifndef OPTION_PRESET_ENCODER_0_360_DEGREES
+ if (az_encoder_result == DIR_CW) {
+ #ifdef DEBUG_PRESET_ENCODERS
+ debug_print("check_preset_encoders: az CW");
+ #endif // DEBUG_PRESET_ENCODERS
+ if (az_elapsed_time < 250 /* mSec */) {
+ az_encoder_raw_degrees += (5 * HEADING_MULTIPLIER);
+ } else { az_encoder_raw_degrees += (1 * HEADING_MULTIPLIER); }; // Single deg increase unless encoder turned quickly then 10's step
+ // if (az_encoder_raw_degrees >=(360*HEADING_MULTIPLIER)) {az_encoder_raw_degrees -= (360*HEADING_MULTIPLIER);};
+ if (az_encoder_raw_degrees > ((azimuth_starting_point + azimuth_rotation_capability) * HEADING_MULTIPLIER)) {
+ az_encoder_raw_degrees =
+ ((azimuth_starting_point * HEADING_MULTIPLIER)
+ /* + ((azimuth_starting_point+azimuth_rotation_capability)*HEADING_MULTIPLIER) - az_encoder_raw_degrees*/);
+ }
}
- if (az_encoder_result == DIR_CCW) {
- if (az_elapsed_time < 250 /* mSec */) {az_encoder_raw_degrees -= (5*HEADING_MULTIPLIER);} else {az_encoder_raw_degrees -= (1*HEADING_MULTIPLIER);}; // Single deg decrease unless encoder turned quickly then 10's step
- //if (az_encoder_raw_degrees < 0) {az_encoder_raw_degrees = (360*HEADING_MULTIPLIER);};
- if (az_encoder_raw_degrees < (configuration.azimuth_starting_point*HEADING_MULTIPLIER)) {
- az_encoder_raw_degrees = (((configuration.azimuth_starting_point+configuration.azimuth_rotation_capability)*HEADING_MULTIPLIER)
- /*- (az_encoder_raw_degrees-(configuration.azimuth_starting_point*HEADING_MULTIPLIER))*/);
- }
+ if (az_encoder_result == DIR_CCW) {
+ #ifdef DEBUG_PRESET_ENCODERS
+ debug_print("check_preset_encoders: az CCW");
+ #endif // DEBUG_PRESET_ENCODERS
+ if (az_elapsed_time < 250 /* mSec */) {
+ az_encoder_raw_degrees -= (5 * HEADING_MULTIPLIER);
+ } else { az_encoder_raw_degrees -= (1 * HEADING_MULTIPLIER); }; // Single deg decrease unless encoder turned quickly then 10's step
+ // if (az_encoder_raw_degrees < 0) {az_encoder_raw_degrees = (360*HEADING_MULTIPLIER);};
+ if (az_encoder_raw_degrees < (azimuth_starting_point * HEADING_MULTIPLIER)) {
+ az_encoder_raw_degrees = (((azimuth_starting_point + azimuth_rotation_capability) * HEADING_MULTIPLIER)
+ /*- (az_encoder_raw_degrees-(azimuth_starting_point*HEADING_MULTIPLIER))*/);
+ }
}
- last_encoder_change_time = millis(); // Encoder Check Timer
+ #else //ndef OPTION_PRESET_ENCODER_0_360_DEGREES
+ if (az_encoder_result == DIR_CW) {
+ #ifdef DEBUG_PRESET_ENCODERS
+ debug_print("check_preset_encoders: az CW");
+ #endif // DEBUG_PRESET_ENCODERS
+ if (az_elapsed_time < 250) { // Single deg increase unless encoder turned quickly then 10's step
+ az_encoder_raw_degrees += (5 * HEADING_MULTIPLIER);
+ } else {
+ az_encoder_raw_degrees += (1 * HEADING_MULTIPLIER);
+ }
+ if (az_encoder_raw_degrees > (360 * HEADING_MULTIPLIER)) {
+ //az_encoder_raw_degrees = (360 * HEADING_MULTIPLIER);
+ az_encoder_raw_degrees = 0;
+ //} else {
+ // if (az_encoder_raw_degrees < 0) {
+ // az_encoder_raw_degrees = 0;
+ // }
+ }
+ }
+ if (az_encoder_result == DIR_CCW) {
+ #ifdef DEBUG_PRESET_ENCODERS
+ debug_print("check_preset_encoders: az CCW");
+ #endif // DEBUG_PRESET_ENCODERS
+ if (az_elapsed_time < 250) { // Single deg decrease unless encoder turned quickly then 10's step
+ az_encoder_raw_degrees -= (5 * HEADING_MULTIPLIER);
+ } else {
+ az_encoder_raw_degrees -= (1 * HEADING_MULTIPLIER);
+ }
+ //if (az_encoder_raw_degrees > (360 * HEADING_MULTIPLIER)) {
+ // az_encoder_raw_degrees = (360 * HEADING_MULTIPLIER);
+ //} else {
+ if (az_encoder_raw_degrees < 0) {
+ //az_encoder_raw_degrees = 0;
+ az_encoder_raw_degrees = 359 * HEADING_MULTIPLIER;
+ }
+ //}
+ }
+ #endif //ndef OPTION_PRESET_ENCODER_0_360_DEGREES
+
+
+
+ last_encoder_change_time = millis(); // Encoder Check Timer
#ifdef FEATURE_LCD_DISPLAY
push_lcd_update = 1; // push an LCD update
- #endif //FEATURE_LCD_DISPLAY
-
+ #endif // FEATURE_LCD_DISPLAY
+
if (preset_encoders_state == ENCODER_IDLE) {
preset_encoders_state = ENCODER_AZ_PENDING;
} else {
@@ -1238,19 +1478,18 @@ void check_preset_encoders(){
preset_encoders_state = ENCODER_AZ_EL_PENDING;
}
}
-
+
#ifdef DEBUG_PRESET_ENCODERS
- if (debug_mode) {
- Serial.print(F("check_preset_encoders: az target: "));
- Serial.println(az_encoder_raw_degrees/HEADING_MULTIPLIER,1);
- }
- #endif //DEBUG_PRESET_ENCODERS
-
+ debug_print("check_preset_encoders: az target: ");
+ dtostrf((az_encoder_raw_degrees / HEADING_MULTIPLIER),0,1,tempchar);
+ debug_println(tempchar);
+ #endif // DEBUG_PRESET_ENCODERS
+
} // if (az_encoder_result)
- #endif //FEATURE_AZ_PRESET_ENCODER
-
+ #endif // FEATURE_AZ_PRESET_ENCODER
+
#ifdef FEATURE_EL_PRESET_ENCODER
-
+
#ifdef OPTION_PRESET_ENCODER_RELATIVE_CHANGE
if ((preset_encoders_state == ENCODER_IDLE) || (preset_encoders_state == ENCODER_AZ_PENDING)) {
if (el_request_queue_state == IN_PROGRESS_TO_TARGET) {
@@ -1259,34 +1498,50 @@ void check_preset_encoders(){
el_encoder_degrees = elevation;
}
}
- #endif //OPTION_PRESET_ENCODER_RELATIVE_CHANGE
-
- if (el_encoder_result) { // If rotary encoder modified
+ #endif // OPTION_PRESET_ENCODER_RELATIVE_CHANGE
+
+ if (el_encoder_result) { // If rotary encoder modified
el_timestamp[0] = el_timestamp[1]; // Encoder step timer
- el_timestamp[1] = el_timestamp[2];
- el_timestamp[2] = el_timestamp[3];
- el_timestamp[3] = el_timestamp[4];
+ el_timestamp[1] = el_timestamp[2];
+ el_timestamp[2] = el_timestamp[3];
+ el_timestamp[3] = el_timestamp[4];
el_timestamp[4] = millis();
-
+
last_encoder_move = millis();
-
+
unsigned long el_elapsed_time = (el_timestamp[4] - el_timestamp[0]); // Encoder step time difference for 10's step
-
+
if (el_encoder_result == DIR_CW) { // Rotary Encoder CW 0 - 359 Deg
-
- if (el_elapsed_time < 250) {el_encoder_degrees += (5*HEADING_MULTIPLIER);} else {el_encoder_degrees += (1*HEADING_MULTIPLIER);}; // Single deg increase unless encoder turned quickly then 10's step
- if (el_encoder_degrees > (180*HEADING_MULTIPLIER)) {el_encoder_degrees = (180*HEADING_MULTIPLIER);};
+ #ifdef DEBUG_PRESET_ENCODERS
+ debug_println("check_preset_encoders: el CW");
+ #endif // DEBUG_PRESET_ENCODERS
+ if (el_elapsed_time < 250) {
+ el_encoder_degrees += (5 * HEADING_MULTIPLIER);
+ } else { el_encoder_degrees += (1 * HEADING_MULTIPLIER); }; // Single deg increase unless encoder turned quickly then 10's step
+ if (el_encoder_degrees > (180 * HEADING_MULTIPLIER)) {
+ el_encoder_degrees = (180 * HEADING_MULTIPLIER);
+ }
+ ;
}
- if (el_encoder_result == DIR_CCW) { // Rotary Encoder CCW 359 - 0 Deg
- if (el_elapsed_time < 250) {el_encoder_degrees -= (5*HEADING_MULTIPLIER);} else {el_encoder_degrees -= (1*HEADING_MULTIPLIER);}; // Single deg decrease unless encoder turned quickly then 10's step
- if (el_encoder_degrees < 0) {el_encoder_degrees = 0;};
+ if (el_encoder_result == DIR_CCW) {
+ #ifdef DEBUG_PRESET_ENCODERS
+ debug_println("check_preset_encoders: el CCW");
+ #endif // DEBUG_PRESET_ENCODERS
+ // Rotary Encoder CCW 359 - 0 Deg
+ if (el_elapsed_time < 250) {
+ el_encoder_degrees -= (5 * HEADING_MULTIPLIER);
+ } else { el_encoder_degrees -= (1 * HEADING_MULTIPLIER); }; // Single deg decrease unless encoder turned quickly then 10's step
+ if (el_encoder_degrees < 0) {
+ el_encoder_degrees = 0;
+ }
+ ;
}
- last_encoder_change_time = millis(); // Encoder Check Timer
-
+ last_encoder_change_time = millis(); // Encoder Check Timer
+
#ifdef FEATURE_LCD_DISPLAY
last_lcd_update = 0; // push an LCD update
- #endif //FEATURE_LCD_DISPLAY
-
+ #endif // FEATURE_LCD_DISPLAY
+
if (preset_encoders_state == ENCODER_IDLE) {
preset_encoders_state = ENCODER_EL_PENDING;
} else {
@@ -1294,1195 +1549,832 @@ void check_preset_encoders(){
preset_encoders_state = ENCODER_AZ_EL_PENDING;
}
}
-
+
#ifdef DEBUG_PRESET_ENCODERS
- if (debug_mode) {
- Serial.print(F("check_preset_encoders: el target: "));
- Serial.println(el_encoder_degrees/HEADING_MULTIPLIER,1);
- }
- #endif //DEBUG_PRESET_ENCODERS
+ debug_print("check_preset_encoders: el target: ");
+ dtostrf(el_encoder_degrees / HEADING_MULTIPLIER,0,1,tempchar);
+ debug_println(tempchar);
+ #endif // DEBUG_PRESET_ENCODERS
-
- } // if (el_encoder_result)
-
-
- #endif //FEATURE_EL_PRESET_ENCODER
- if ((preset_encoders_state != ENCODER_IDLE) && (!submit_encoder_change)) { // Check button or timer
- if (preset_start_button) { // if we have a preset start button, check it
- button_read = digitalRead(preset_start_button);
- if (button_read == LOW) {
+ } // if (el_encoder_result)
+
+
+ #endif // FEATURE_EL_PRESET_ENCODER
+
+ if ((preset_encoders_state != ENCODER_IDLE) && (!submit_encoder_change)) { // Check button or timer
+ if (preset_start_button) { // if we have a preset start button, check it
+ button_read = digitalReadEnhanced(preset_start_button);
+ if (button_read == BUTTON_ACTIVE_STATE) {
submit_encoder_change = 1;
last_preset_start_button_start = millis();
+
+ #ifdef DEBUG_PRESET_ENCODERS
+ debug_println("check_preset_encoders: preset_start_button submit_encoder_change");
+ #endif // DEBUG_PRESET_ENCODERS
}
- } else {
- if ((millis() - last_encoder_change_time) > 2000) {submit_encoder_change = 1;} //if enc not changed for more than 2 sec, rotate to target
- }
- } //if (!enc_changed_waiting)
+ } else {
+ if ((millis() - last_encoder_change_time) > 2000) { // if enc not changed for more than 2 sec, rotate to target
+ #ifdef DEBUG_PRESET_ENCODERS
+ debug_println("check_preset_encoders: timer submit_encoder_change");
+ #endif // DEBUG_PRESET_ENCODERS
+ submit_encoder_change = 1;
+ }
+ }
+ } // if (!enc_changed_waiting)
if (preset_start_button) { // if we have a preset start button, check it
- button_read = digitalRead(preset_start_button);
- if ((button_read == LOW) && (!submit_encoder_change) && ((millis() - last_preset_start_button_start) > 250)
- && ((millis() - last_preset_start_button_kill) > 250) && (preset_encoders_state == ENCODER_IDLE)) {
+ button_read = digitalReadEnhanced(preset_start_button);
+ if ((button_read == BUTTON_ACTIVE_STATE) && (!submit_encoder_change) && ((millis() - last_preset_start_button_start) > 250)
+ && ((millis() - last_preset_start_button_kill) > 250) && (preset_encoders_state == ENCODER_IDLE)) {
#ifdef DEBUG_PRESET_ENCODERS
- if (debug_mode) {
- Serial.println(F("check_preset_encoders: preset button kill"));
- }
- #endif //DEBUG_PRESET_ENCODERS
- #ifdef FEATURE_AZ_PRESET_ENCODER
+ debug_println("check_preset_encoders: preset button kill");
+ #endif // DEBUG_PRESET_ENCODERS
+ #ifdef FEATURE_AZ_PRESET_ENCODER
if (az_state != IDLE) {
- submit_request(AZ,REQUEST_KILL,0);
+ submit_request(AZ, REQUEST_KILL, 0, 45);
}
- #endif //FEATURE_AZ_PRESET_ENCODER
+ #endif // FEATURE_AZ_PRESET_ENCODER
#ifdef FEATURE_EL_PRESET_ENCODER
if (el_state != IDLE) {
- submit_request(EL,REQUEST_KILL,0);
+ submit_request(EL, REQUEST_KILL, 0, 46);
}
- #endif //FEATURE_EL_PRESET_ENCODER
+ #endif // FEATURE_EL_PRESET_ENCODER
last_preset_start_button_kill = millis();
}
}
-
- if ((submit_encoder_change) && (button_read == HIGH)) {
- #ifdef DEBUG_PRESET_ENCODERS
- if (debug_mode) {
- Serial.println(F("check_preset_encoders: submit_encoder_change "));
- }
- #endif //DEBUG_PRESET_ENCODERS
-
+ if ((submit_encoder_change) && (button_read == BUTTON_INACTIVE_STATE)) {
+ #ifdef DEBUG_PRESET_ENCODERS
+ debug_println("check_preset_encoders: submit_encoder_change ");
+ #endif // DEBUG_PRESET_ENCODERS
+
+
if ((preset_encoders_state == ENCODER_AZ_PENDING) || (preset_encoders_state == ENCODER_AZ_EL_PENDING)) {
- submit_request(AZ,REQUEST_AZIMUTH_RAW,az_encoder_raw_degrees);
+ #ifndef OPTION_PRESET_ENCODER_0_360_DEGREES
+ submit_request(AZ, REQUEST_AZIMUTH_RAW, az_encoder_raw_degrees, 47);
+ #else
+ submit_request(AZ, REQUEST_AZIMUTH, az_encoder_raw_degrees, 47);
+ #endif //ndef OPTION_PRESET_ENCODER_0_360_DEGREES
}
-
+
#ifdef FEATURE_EL_PRESET_ENCODER
if ((preset_encoders_state == ENCODER_EL_PENDING) || (preset_encoders_state == ENCODER_AZ_EL_PENDING)) {
- submit_request(EL,REQUEST_ELEVATION,el_encoder_degrees);
- }
- #endif //FEATURE_EL_PRESET_ENCODER
-
+ submit_request(EL, REQUEST_ELEVATION, el_encoder_degrees, 48);
+ }
+ #endif // FEATURE_EL_PRESET_ENCODER
+
preset_encoders_state = ENCODER_IDLE;
submit_encoder_change = 0;
- } //if (submit_encoder_change)
-
- if ((preset_start_button) && (preset_encoders_state != ENCODER_IDLE) && ((millis() - last_encoder_move) > ENCODER_PRESET_TIMEOUT)){ // timeout if we have a preset start button
+ } // if (submit_encoder_change)
+
+ if ((preset_start_button) && (preset_encoders_state != ENCODER_IDLE) && ((millis() - last_encoder_move) > ENCODER_PRESET_TIMEOUT)) { // timeout if we have a preset start button
preset_encoders_state = ENCODER_IDLE;
#ifdef FEATURE_LCD_DISPLAY
push_lcd_update = 1; // push an LCD update
- #endif //FEATURE_LCD_DISPLAY
+ #endif // FEATURE_LCD_DISPLAY
}
-}
-
-#endif //FEATURE_AZ_PRESET_ENCODER
+} /* check_preset_encoders */
-//--------------------------------------------------------------
+#endif // FEATURE_AZ_PRESET_ENCODER
+
+// --------------------------------------------------------------
#ifdef OPTION_AZ_MANUAL_ROTATE_LIMITS
void check_az_manual_rotate_limit() {
- if ((current_az_state() == ROTATING_CCW) && (raw_azimuth <= (AZ_MANUAL_ROTATE_CCW_LIMIT*HEADING_MULTIPLIER))) {
+ if ((current_az_state() == ROTATING_CCW) && (raw_azimuth <= (AZ_MANUAL_ROTATE_CCW_LIMIT * HEADING_MULTIPLIER))) {
#ifdef DEBUG_AZ_MANUAL_ROTATE_LIMITS
- if (debug_mode) {
- Serial.print(F("check_az_manual_rotate_limit: stopping - hit AZ_MANUAL_ROTATE_CCW_LIMIT of "));
- Serial.println(AZ_MANUAL_ROTATE_CCW_LIMIT);
- }
- #endif //DEBUG_AZ_MANUAL_ROTATE_LIMITS
- submit_request(AZ,REQUEST_KILL,0);
+ debug_print("check_az_manual_rotate_limit: stopping - hit AZ_MANUAL_ROTATE_CCW_LIMIT of ");
+ debug_print_int(AZ_MANUAL_ROTATE_CCW_LIMIT);
+ debug_println("");
+ #endif // DEBUG_AZ_MANUAL_ROTATE_LIMITS
+ submit_request(AZ, REQUEST_KILL, 0, 49);
}
- if ((current_az_state() == ROTATING_CW) && (raw_azimuth >= (AZ_MANUAL_ROTATE_CW_LIMIT*HEADING_MULTIPLIER))) {
+ if ((current_az_state() == ROTATING_CW) && (raw_azimuth >= (AZ_MANUAL_ROTATE_CW_LIMIT * HEADING_MULTIPLIER))) {
#ifdef DEBUG_AZ_MANUAL_ROTATE_LIMITS
- if (debug_mode) {
- Serial.print(F("check_az_manual_rotate_limit: stopping - hit AZ_MANUAL_ROTATE_CW_LIMIT of "));
- Serial.println(AZ_MANUAL_ROTATE_CW_LIMIT);
- }
- #endif //DEBUG_AZ_MANUAL_ROTATE_LIMITS
- submit_request(AZ,REQUEST_KILL,0);
+ debug_print("check_az_manual_rotate_limit: stopping - hit AZ_MANUAL_ROTATE_CW_LIMIT of ");
+ debug_print_int(AZ_MANUAL_ROTATE_CW_LIMIT);
+ debug_println("");
+ #endif // DEBUG_AZ_MANUAL_ROTATE_LIMITS
+ submit_request(AZ, REQUEST_KILL, 0, 50);
}
-}
-#endif //#ifdef OPTION_AZ_MANUAL_ROTATE_LIMITS
+} /* check_az_manual_rotate_limit */
+#endif // #ifdef OPTION_AZ_MANUAL_ROTATE_LIMITS
-//--------------------------------------------------------------
+// --------------------------------------------------------------
#if defined(OPTION_EL_MANUAL_ROTATE_LIMITS) && defined(FEATURE_ELEVATION_CONTROL)
void check_el_manual_rotate_limit() {
- if ((current_el_state() == ROTATING_DOWN) && (elevation <= (EL_MANUAL_ROTATE_DOWN_LIMIT*HEADING_MULTIPLIER))) {
+ if ((current_el_state() == ROTATING_DOWN) && (elevation <= (EL_MANUAL_ROTATE_DOWN_LIMIT * HEADING_MULTIPLIER))) {
#ifdef DEBUG_EL_MANUAL_ROTATE_LIMITS
- if (debug_mode) {
- Serial.print(F("check_el_manual_rotate_limit: stopping - hit EL_MANUAL_ROTATE_DOWN_LIMIT of "));
- Serial.println(EL_MANUAL_ROTATE_DOWN_LIMIT);
- }
- #endif //DEBUG_EL_MANUAL_ROTATE_LIMITS
- submit_request(EL,REQUEST_KILL,0);
+ debug_print("check_el_manual_rotate_limit: stopping - hit EL_MANUAL_ROTATE_DOWN_LIMIT of ");
+ debug_print_int(EL_MANUAL_ROTATE_DOWN_LIMIT);
+ debug_println("");
+ #endif // DEBUG_EL_MANUAL_ROTATE_LIMITS
+ submit_request(EL, REQUEST_KILL, 0, 51);
}
- if ((current_el_state() == ROTATING_UP) && (elevation >= (EL_MANUAL_ROTATE_UP_LIMIT*HEADING_MULTIPLIER))) {
+ if ((current_el_state() == ROTATING_UP) && (elevation >= (EL_MANUAL_ROTATE_UP_LIMIT * HEADING_MULTIPLIER))) {
#ifdef DEBUG_EL_MANUAL_ROTATE_LIMITS
- if (debug_mode) {
- Serial.print(F("check_el_manual_rotate_limit: stopping - hit EL_MANUAL_ROTATE_UP_LIMIT of "));
- Serial.println(EL_MANUAL_ROTATE_UP_LIMIT);
- }
- #endif //DEBUG_EL_MANUAL_ROTATE_LIMITS
- submit_request(EL,REQUEST_KILL,0);
+ debug_print("check_el_manual_rotate_limit: stopping - hit EL_MANUAL_ROTATE_UP_LIMIT of ");
+ debug_print_int(EL_MANUAL_ROTATE_UP_LIMIT);
+ debug_println("");
+ #endif // DEBUG_EL_MANUAL_ROTATE_LIMITS
+ submit_request(EL, REQUEST_KILL, 0, 52);
}
-}
-#endif //#ifdef OPTION_EL_MANUAL_ROTATE_LIMITS
+} /* check_el_manual_rotate_limit */
+#endif // #ifdef OPTION_EL_MANUAL_ROTATE_LIMITS
-//--------------------------------------------------------------
+// --------------------------------------------------------------
void check_brake_release() {
-
-
+
+
static byte in_az_brake_release_delay = 0;
static unsigned long az_brake_delay_start_time = 0;
+
#ifdef FEATURE_ELEVATION_CONTROL
static byte in_el_brake_release_delay = 0;
static unsigned long el_brake_delay_start_time = 0;
- #endif //FEATURE_ELEVATION_CONTROL
-
+ #endif // FEATURE_ELEVATION_CONTROL
+
if ((az_state == IDLE) && (brake_az_engaged)) {
if (in_az_brake_release_delay) {
if ((millis() - az_brake_delay_start_time) > AZ_BRAKE_DELAY) {
brake_release(AZ, BRAKE_RELEASE_OFF);
- in_az_brake_release_delay = 0;
- }
+ in_az_brake_release_delay = 0;
+ }
} else {
az_brake_delay_start_time = millis();
in_az_brake_release_delay = 1;
}
- }
-
- #ifdef FEATURE_ELEVATION_CONTROL
+ }
+
+ #ifdef FEATURE_ELEVATION_CONTROL
if ((el_state == IDLE) && (brake_el_engaged)) {
if (in_el_brake_release_delay) {
if ((millis() - el_brake_delay_start_time) > EL_BRAKE_DELAY) {
brake_release(EL, BRAKE_RELEASE_OFF);
- in_el_brake_release_delay = 0;
- }
+ in_el_brake_release_delay = 0;
+ }
} else {
el_brake_delay_start_time = millis();
in_el_brake_release_delay = 1;
- }
- }
- #endif //FEATURE_ELEVATION_CONTROL
-
-}
+ }
+ }
+ #endif // FEATURE_ELEVATION_CONTROL
-//--------------------------------------------------------------
+} /* check_brake_release */
+
+// --------------------------------------------------------------
void brake_release(byte az_or_el, byte operation){
-
+
if (az_or_el == AZ) {
if (brake_az) {
if (operation == BRAKE_RELEASE_ON) {
- digitalWrite(brake_az,HIGH);
+ digitalWriteEnhanced(brake_az, HIGH);
brake_az_engaged = 1;
#ifdef DEBUG_BRAKE
- if (debug_mode) {
- Serial.println(F("brake_release: brake_az BRAKE_RELEASE_ON"));
- }
- #endif //DEBUG_BRAKE
+ debug_println("brake_release: brake_az BRAKE_RELEASE_ON");
+ #endif // DEBUG_BRAKE
} else {
- digitalWrite(brake_az,LOW);
- brake_az_engaged = 0;
+ digitalWriteEnhanced(brake_az, LOW);
+ brake_az_engaged = 0;
#ifdef DEBUG_BRAKE
- if (debug_mode) {
- Serial.println(F("brake_release: brake_az BRAKE_RELEASE_OFF"));
- }
- #endif //DEBUG_BRAKE
- }
- }
+ debug_println("brake_release: brake_az BRAKE_RELEASE_OFF");
+ #endif // DEBUG_BRAKE
+ }
+ }
} else {
- #ifdef FEATURE_ELEVATION_CONTROL
+ #ifdef FEATURE_ELEVATION_CONTROL
if (brake_el) {
- digitalWrite(brake_el,HIGH);
+ digitalWriteEnhanced(brake_el, HIGH);
brake_el_engaged = 1;
#ifdef DEBUG_BRAKE
- if (debug_mode) {
- Serial.println(F("brake_release: brake_el BRAKE_RELEASE_ON"));
- }
- #endif //DEBUG_BRAKE
+ debug_println("brake_release: brake_el BRAKE_RELEASE_ON");
+ #endif // DEBUG_BRAKE
} else {
- digitalWrite(brake_el,LOW);
- brake_el_engaged = 0;
+ digitalWriteEnhanced(brake_el, LOW);
+ brake_el_engaged = 0;
#ifdef DEBUG_BRAKE
- if (debug_mode) {
- Serial.println(F("brake_release: brake_el BRAKE_RELEASE_OFF"));
- }
- #endif //DEBUG_BRAKE
+ debug_println("brake_release: brake_el BRAKE_RELEASE_OFF");
+ #endif // DEBUG_BRAKE
}
- #endif //FEATURE_ELEVATION_CONTROL
- }
-}
+ #endif // FEATURE_ELEVATION_CONTROL
+ }
+} /* brake_release */
-//--------------------------------------------------------------
+// --------------------------------------------------------------
void check_overlap(){
static byte overlap_led_status = 0;
static unsigned long last_check_time;
-
+
if ((overlap_led) && ((millis() - last_check_time) > 500)) {
- //if ((analog_az > (500*HEADING_MULTIPLIER)) && (azimuth > (ANALOG_AZ_OVERLAP_DEGREES*HEADING_MULTIPLIER)) && (!overlap_led_status)) {
- if ((raw_azimuth > (ANALOG_AZ_OVERLAP_DEGREES*HEADING_MULTIPLIER)) && (!overlap_led_status)) {
- digitalWrite(overlap_led, HIGH);
- overlap_led_status = 1;
- #ifdef DEBUG_OVERLAP
- if (debug_mode) {
- Serial.print(F("check_overlap: in overlap\r\n"));
- }
- #endif //DEBUG_OVERLAP
- } else {
- //if (((analog_az < (500*HEADING_MULTIPLIER)) || (azimuth < (ANALOG_AZ_OVERLAP_DEGREES*HEADING_MULTIPLIER))) && (overlap_led_status)) {
- if ((raw_azimuth < (ANALOG_AZ_OVERLAP_DEGREES*HEADING_MULTIPLIER)) && (overlap_led_status)) {
- digitalWrite(overlap_led, LOW);
- overlap_led_status = 0;
- #ifdef DEBUG_OVERLAP
- if (debug_mode) {
- Serial.print(F("check_overlap: overlap off\r\n"));
- }
- #endif //DEBUG_OVERLAP
- }
- }
- last_check_time = millis();
-
+ // if ((analog_az > (500*HEADING_MULTIPLIER)) && (azimuth > (ANALOG_AZ_OVERLAP_DEGREES*HEADING_MULTIPLIER)) && (!overlap_led_status)) {
+ if ((raw_azimuth > (ANALOG_AZ_OVERLAP_DEGREES * HEADING_MULTIPLIER)) && (!overlap_led_status)) {
+ digitalWriteEnhanced(overlap_led, HIGH);
+ overlap_led_status = 1;
+ #ifdef DEBUG_OVERLAP
+ debug_println("check_overlap: in overlap");
+ #endif // DEBUG_OVERLAP
+ } else {
+ // if (((analog_az < (500*HEADING_MULTIPLIER)) || (azimuth < (ANALOG_AZ_OVERLAP_DEGREES*HEADING_MULTIPLIER))) && (overlap_led_status)) {
+ if ((raw_azimuth < (ANALOG_AZ_OVERLAP_DEGREES * HEADING_MULTIPLIER)) && (overlap_led_status)) {
+ digitalWriteEnhanced(overlap_led, LOW);
+ overlap_led_status = 0;
+ #ifdef DEBUG_OVERLAP
+ debug_println("check_overlap: overlap off");
+ #endif // DEBUG_OVERLAP
+ }
+ }
+ last_check_time = millis();
+
}
-}
+} /* check_overlap */
-//--------------------------------------------------------------
-#ifdef FEATURE_YAESU_EMULATION
-void yaesu_serial_command(){
-
-
- if (incoming_serial_byte == 10) { return; } // ignore carriage returns
- if ((incoming_serial_byte != 13) && (serial0_buffer_index < COMMAND_BUFFER_SIZE)) { // if it's not a carriage return, add it to the buffer
- serial0_buffer[serial0_buffer_index] = incoming_serial_byte;
- serial0_buffer_index++;
- } else { // we got a carriage return, time to get to work on the command
- if ((serial0_buffer[0] > 96) && (serial0_buffer[0] < 123)) {
- serial0_buffer[0] = serial0_buffer[0] - 32;
- }
- switch (serial0_buffer[0]) { // look at the first character of the command
- case 'C': // C - return current azimuth
- #ifdef DEBUG_SERIAL
- if (debug_mode) {Serial.println(F("yaesu_serial_command: C cmd"));}
- #endif //DEBUG_SERIAL
- #ifdef OPTION_DELAY_C_CMD_OUTPUT
- delay(400);
- #endif
- report_current_azimuth();
- break;
- case 'F': // F - full scale calibration
- #ifdef DEBUG_SERIAL
- if (debug_mode) {Serial.println(F("yaesu_serial_command: F cmd"));}
- #endif //DEBUG_SERIAL
- yaesu_f_command();
- break;
-
- case 'H': print_help(); break; // H - print help (simulated Yaesu GS-232A help - not all commands are supported
- case 'L': // L - manual left (CCW) rotation
- #ifdef DEBUG_SERIAL
- if (debug_mode) {Serial.println(F("yaesu_serial_command: L cmd"));}
- #endif //DEBUG_SERIAL
- submit_request(AZ,REQUEST_CCW,0);
- Serial.println();
- break;
- case 'O': // O - offset calibration
- #ifdef DEBUG_SERIAL
- if (debug_mode) {Serial.println(F("yaesu_serial_command: O cmd"));}
- #endif //DEBUG_SERIAL
- yaesu_o_command();
- break;
- case 'R': // R - manual right (CW) rotation
- #ifdef DEBUG_SERIAL
- if (debug_mode) {Serial.println(F("yaesu_serial_command: R cmd"));}
- #endif //DEBUG_SERIAL
- submit_request(AZ,REQUEST_CW,0);
- Serial.println();
- break;
- case 'A': // A - CW/CCW rotation stop
- #ifdef DEBUG_SERIAL
- if (debug_mode) {Serial.println(F("yaesu_serial_command: A cmd"));}
- #endif //DEBUG_SERIAL
- submit_request(AZ,REQUEST_STOP,0);
- Serial.println();
- break;
- case 'S': // S - all stop
- #ifdef DEBUG_SERIAL
- if (debug_mode) {Serial.println(F("yaesu_serial_command: S cmd"));}
- #endif //DEBUG_SERIAL
- submit_request(AZ,REQUEST_STOP,0);
- #ifdef FEATURE_ELEVATION_CONTROL
- submit_request(EL,REQUEST_STOP,0);
- #endif
- #ifdef FEATURE_TIMED_BUFFER
- clear_timed_buffer();
- #endif //FEATURE_TIMED_BUFFER
- Serial.println();
- break;
- case 'M': // M - auto azimuth rotation
- #ifdef DEBUG_SERIAL
- if (debug_mode) {Serial.println(F("yaesu_serial_command: M cmd"));}
- #endif //DEBUG_SERIAL
- yaesu_m_command();
- break;
- #ifdef FEATURE_TIMED_BUFFER
- case 'N': // N - number of loaded timed interval entries
- #ifdef DEBUG_SERIAL
- if (debug_mode) {Serial.println(F("yaesu_serial_command: N cmd"));}
- #endif //DEBUG_SERIAL
- Serial.println(timed_buffer_number_entries_loaded);
- break;
- #endif //FEATURE_TIMED_BUFFER
- #ifdef FEATURE_TIMED_BUFFER
- case 'T': initiate_timed_buffer(); break; // T - initiate timed tracking
- #endif //FEATURE_TIMED_BUFFER
- case 'X': // X - azimuth speed change
- #ifdef DEBUG_SERIAL
- if (debug_mode) {Serial.println(F("yaesu_serial_command: X cmd"));}
- #endif //DEBUG_SERIAL
- yaesu_x_command();
- break;
- #ifdef FEATURE_ELEVATION_CONTROL
- case 'U': // U - manual up rotation
- #ifdef DEBUG_SERIAL
- if (debug_mode) {Serial.println(F("yaesu_serial_command: U cmd"));}
- #endif //DEBUG_SERIAL
- submit_request(EL,REQUEST_UP,0);
- Serial.println();
- break;
- case 'D': // D - manual down rotation
- #ifdef DEBUG_SERIAL
- if (debug_mode) {Serial.println(F("yaesu_serial_command: D cmd"));}
- #endif //DEBUG_SERIAL
- submit_request(EL,REQUEST_DOWN,0);
- Serial.println();
- break;
- case 'E': // E - stop elevation rotation
- #ifdef DEBUG_SERIAL
- if (debug_mode) {Serial.println(F("yaesu_serial_command: E cmd"));}
- #endif //DEBUG_SERIAL
- submit_request(EL,REQUEST_STOP,0);
- Serial.println();
- break;
- case 'B': report_current_elevation(); break; // B - return current elevation
- #endif
- case 'W': // W - auto elevation rotation
- #ifdef DEBUG_SERIAL
- if (debug_mode) {Serial.println(F("yaesu_serial_command: W cmd"));}
- #endif //DEBUG_SERIAL
- yaesu_w_command();
- break;
- #ifdef OPTION_GS_232B_EMULATION
- case 'P': yaesu_p_command(); break; // P - switch between 360 and 450 degree mode
- case 'Z': // Z - Starting point toggle
- if (configuration.azimuth_starting_point == 180) {
- configuration.azimuth_starting_point = 0;
- Serial.println(F("N Center"));
- } else {
- configuration.azimuth_starting_point = 180;
- Serial.println(F("S Center"));
- }
- write_settings_to_eeprom();
- break;
- #endif
- default:
- Serial.println(F("?>"));
- #ifdef DEBUG_SERIAL
- if (debug_mode) {
- Serial.print(F("check_serial: serial0_buffer_index: "));
- Serial.println(serial0_buffer_index);
- for (int debug_x = 0; debug_x < serial0_buffer_index; debug_x++) {
- Serial.print(F("check_serial: serial0_buffer["));
- Serial.print(debug_x);
- Serial.print(F("]: "));
- Serial.print(serial0_buffer[debug_x]);
- Serial.print(F(" "));
- Serial.write(serial0_buffer[debug_x]);
- Serial.println();
- }
- }
- #endif //DEBUG_SERIAL
- }
- clear_command_buffer();
- }
-}
-#endif //FEATURE_YAESU_EMULATION
-//--------------------------------------------------------------
+// --------------------------------------------------------------
void clear_command_buffer(){
- serial0_buffer_index = 0;
- serial0_buffer[0] = 0;
-
-
+ control_port_buffer_index = 0;
+ control_port_buffer[0] = 0;
+
+
}
-//--------------------------------------------------------------
-
-#ifdef FEATURE_EASYCOM_EMULATION
-void easycom_serial_commmand(){
-
- /* Easycom protocol implementation
-
- Implemented commands:
-
- Command Meaning Parameters
- ------- ------- ----------
- AZ Azimuth number - 1 decimal place
- EL Elevation number - 1 decimal place
-
- ML Move Left
- MR Move Right
- MU Move Up
- MD Move Down
- SA Stop azimuth moving
- SE Stop elevation moving
-
- VE Request Version
-
- Easycom has no way to report azimuth or elevation back to the client, or report errors
-
-
- */
-
-
- float heading = -1;
-
-
-
- if ((incoming_serial_byte != 13) && (incoming_serial_byte != 10) && (incoming_serial_byte != 32) && (serial0_buffer_index < COMMAND_BUFFER_SIZE)){ // if it's not a CR, LF, or space, add it to the buffer
- if ((incoming_serial_byte > 96) && (incoming_serial_byte < 123)) {incoming_serial_byte = incoming_serial_byte - 32;} //uppercase it
- serial0_buffer[serial0_buffer_index] = incoming_serial_byte;
- serial0_buffer_index++;
- } else { // time to get to work on the command
- if (serial0_buffer_index){
- switch (serial0_buffer[0]) { // look at the first character of the command
- case 'A': //AZ
- if (serial0_buffer[1] == 'Z'){ // format is AZx.x or AZxx.x or AZxxx.x (why didn't they make it fixed length?)
- switch (serial0_buffer_index) {
- #ifdef OPTION_EASYCOM_AZ_QUERY_COMMAND
- case 2:
- Serial.print("AZ");
- Serial.println(float(azimuth*HEADING_MULTIPLIER),1);
- clear_command_buffer();
- return;
- break;
- #endif //OPTION_EASYCOM_AZ_QUERY_COMMAND
- case 5: // format AZx.x
- heading = (serial0_buffer[2]-48) + ((serial0_buffer[4]-48)/10);
- break;
- case 6: // format AZxx.x
- heading = ((serial0_buffer[2]-48)*10) + (serial0_buffer[3]-48) + ((serial0_buffer[5]-48)/10);
- break;
- case 7: // format AZxxx.x
- heading = ((serial0_buffer[2]-48)*100) + ((serial0_buffer[3]-48)*10) + (serial0_buffer[4]-48) + ((serial0_buffer[6]-48)/10);
- break;
- //default: Serial.println("?"); break;
- }
- if (((heading >= 0) && (heading < 451)) && (serial0_buffer[serial0_buffer_index-2] == '.')){
- submit_request(AZ,REQUEST_AZIMUTH,(heading*HEADING_MULTIPLIER));
- } else {
- Serial.println("?");
- }
- } else {
- Serial.println("?");
- }
- break;
- #ifdef FEATURE_ELEVATION_CONTROL
- case 'E': //EL
- if (serial0_buffer[1] == 'L') {
- switch (serial0_buffer_index) {
- #ifdef OPTION_EASYCOM_EL_QUERY_COMMAND
- case 2:
- Serial.print("EL");
- Serial.println(float(elevation*HEADING_MULTIPLIER),1);
- clear_command_buffer();
- return;
- break;
- #endif //OPTION_EASYCOM_EL_QUERY_COMMAND
- case 5: // format ELx.x
- heading = (serial0_buffer[2]-48) + ((serial0_buffer[4]-48)/10);
- break;
- case 6: // format ELxx.x
- heading = ((serial0_buffer[2]-48)*10) + (serial0_buffer[3]-48) + ((serial0_buffer[5]-48)/10);
- break;
- case 7: // format ELxxx.x
- heading = ((serial0_buffer[2]-48)*100) + ((serial0_buffer[3]-48)*10) + (serial0_buffer[4]-48) + ((serial0_buffer[6]-48)/10);
- break;
- //default: Serial.println("?"); break;
- }
- if (((heading >= 0) && (heading < 181)) && (serial0_buffer[serial0_buffer_index-2] == '.')){
- submit_request(EL,REQUEST_ELEVATION,(heading*HEADING_MULTIPLIER));
- } else {
- Serial.println("?");
- }
- } else {
- Serial.println(F("?"));
- }
- break;
- #endif //#FEATURE_ELEVATION_CONTROL
- case 'S': // SA or SE - stop azimuth, stop elevation
- switch (serial0_buffer[1]) {
- case 'A':
- submit_request(AZ,REQUEST_STOP,0);
- break;
- #ifdef FEATURE_ELEVATION_CONTROL
- case 'E':
- submit_request(EL,REQUEST_STOP,0);
- break;
- #endif //FEATURE_ELEVATION_CONTROL
- default: Serial.println("?"); break;
- }
- break;
- case 'M': // ML, MR, MU, MD - move left, right, up, down
- switch (serial0_buffer[1]){
- case 'L': // ML - move left
- submit_request(AZ,REQUEST_CCW,0);
- break;
- case 'R': // MR - move right
- submit_request(AZ,REQUEST_CW,0);
- break;
- #ifdef FEATURE_ELEVATION_CONTROL
- case 'U': // MU - move up
- submit_request(EL,REQUEST_UP,0);
- break;
- case 'D': // MD - move down
- submit_request(EL,REQUEST_DOWN,0);
- break;
- #endif //FEATURE_ELEVATION_CONTROL
- default: Serial.println(F("?")); break;
- }
- break;
- case 'V': // VE - version query
- if (serial0_buffer[1] == 'E') {Serial.println(F("VE002"));} // not sure what to send back, sending 002 because this is easycom version 2?
- break;
- default: Serial.println("?"); break;
- }
-
- }
- clear_command_buffer();
- }
-
-
-}
-#endif //FEATURE_EASYCOM_EMULATION
-//--------------------------------------------------------------
+// --------------------------------------------------------------
#if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_ANCILLARY_PIN_CONTROL)
byte get_analog_pin(byte pin_number){
-
+
byte return_output = 0;
-
- switch(pin_number){
+
+ switch (pin_number) {
case 0: return_output = A0; break;
case 1: return_output = A1; break;
case 2: return_output = A2; break;
case 3: return_output = A3; break;
case 4: return_output = A4; break;
- case 5: return_output = A5; break;
- case 6: return_output = A6; break;
- }
-
+ case 5: return_output = A5; break;
+ case 6: return_output = A6; break;
+ }
+
return return_output;
-
-}
-#endif //FEATURE_REMOTE_UNIT_SLAVE
-//--------------------------------------------------------------
+}
+#endif // FEATURE_REMOTE_UNIT_SLAVE
+
+// --------------------------------------------------------------
#ifdef FEATURE_REMOTE_UNIT_SLAVE
-void remote_unit_serial_command(){
-
-
- if (serial_read_event_flag[0]){
- Serial.print("EVS0");
- Serial.write(incoming_serial_byte);
- Serial.println();
- }
-
- if ((incoming_serial_byte != 10) && (serial0_buffer_index < COMMAND_BUFFER_SIZE)){
- //incoming_serial_byte = toupper(incoming_serial_byte);
- serial0_buffer[serial0_buffer_index] = incoming_serial_byte;
- serial0_buffer_index++;
- if ((incoming_serial_byte == 13) || (serial0_buffer_index == COMMAND_BUFFER_SIZE)){
- serial0_buffer_carriage_return_flag = 1;
- }
- }
-
-}
-
-#endif //FEATURE_REMOTE_UNIT_SLAVE
-
-
-//--------------------------------------------------------------
-#ifdef FEATURE_REMOTE_UNIT_SLAVE
void service_remote_unit_serial_buffer(){
-
-
+
+
/*
-
- This implements a protocol for host unit to remote unit communications
+ *
+ * This implements a protocol for host unit to remote unit communications
+ *
+ *
+ * Remote Slave Unit Protocol Reference
+ *
+ * PG - ping
+ * AZ - read azimuth
+ * EL - read elevation
+ * DOxx - digital pin initialize as output;
+ * DIxx - digital pin initialize as input
+ * DPxx - digital pin initialize as input with pullup
+ * DRxx - digital pin read
+ * DLxx - digital pin write low
+ * DHxx - digital pin write high
+ * DTxxyyyy - digital pin tone output
+ * NTxx - no tone
+ * ARxx - analog pin read
+ * AWxxyyy - analog pin write
+ * SWxy - serial write byte
+ * SDx - deactivate serial read event; x = port #
+ * SSxyyyyyy... - serial write sting; x = port #, yyyy = string of characters to send
+ * SAx - activate serial read event; x = port #
+ * RB - reboot
+ *
+ * Responses
+ *
+ * ER - report an error (remote to host only)
+ * EV - report an event (remote to host only)
+ * OK - report success (remote to host only)
+ * CS - report a cold start (remote to host only)
+ *
+ * Error Codes
+ *
+ * ER01 - Serial port buffer timeout
+ * ER02 - Command syntax error
+ *
+ * Events
+ *
+ * EVSxy - Serial port read event; x = serial port number, y = byte returned
+ *
+ *
+ */
- Remote Slave Unit Protocol Reference
-
- PG - ping
- AZ - read azimuth
- EL - read elevation
- DOxx - digital pin initialize as output;
- DIxx - digital pin initialize as input
- DPxx - digital pin initialize as input with pullup
- DRxx - digital pin read
- DLxx - digital pin write low
- DHxx - digital pin write high
- DTxxyyyy - digital pin tone output
- NTxx - no tone
- ARxx - analog pin read
- AWxxyyy - analog pin write
- SWxy - serial write byte
- SDx - deactivate serial read event; x = port #
- SSxyyyyyy... - serial write sting; x = port #, yyyy = string of characters to send
- SAx - activate serial read event; x = port #
- RB - reboot
-
- Responses
-
- ER - report an error (remote to host only)
- EV - report an event (remote to host only)
- OK - report success (remote to host only)
- CS - report a cold start (remote to host only)
-
- Error Codes
-
- ER01 - Serial port buffer timeout
- ER02 - Command syntax error
-
- Events
-
- EVSxy - Serial port read event; x = serial port number, y = byte returned
-
-
-*/
-
-
String command_string;
byte command_good = 0;
-
- if (serial0_buffer_carriage_return_flag) {
-
- // TODO: if checksumming is turned on, parse out the checksum, validate it, return an error if invalid, chop it off if valid and continue
-
- if (serial0_buffer_index < 3){
- Serial.println(F("ER02")); // we don't have enough characters - syntax error
+
+ if (control_port_buffer_carriage_return_flag) {
+
+ if (control_port_buffer_index < 3) {
+ control_port->println(F("ER02")); // we don't have enough characters - syntax error
} else {
- command_string = String(char(toupper(serial0_buffer[0]))) + String(char(toupper(serial0_buffer[1])));
-
+ command_string = String(char(toupper(control_port_buffer[0]))) + String(char(toupper(control_port_buffer[1])));
+
#ifdef DEBUG_SERVICE_SERIAL_BUFFER
- Serial.print(F("serial_serial_buffer: command_string: "));
- Serial.print(command_string);
- Serial.print(F("$ serial0_buffer_index: "));
- Serial.println(serial0_buffer_index);
- #endif //DEBUG_SERVICE_SERIAL_BUFFER
-
- if ((command_string == "SS") && (serial0_buffer[2] > 47) && (serial0_buffer[2] < 53)){ // this is a variable length command
+ debug_print("serial_serial_buffer: command_string: ");
+ debug_print(command_string);
+ debug_print("$ control_port_buffer_index: ");
+ debug_print_int(control_port_buffer_index);
+ debug_println("");
+ #endif // DEBUG_SERVICE_SERIAL_BUFFER
+
+ if ((command_string == "SS") && (control_port_buffer[2] > 47) && (control_port_buffer[2] < 53)) { // this is a variable length command
command_good = 1;
- for (byte x = 3;x < serial0_buffer_index;x++){
- switch(serial0_buffer[2]-48){
- case 0: Serial.write(serial0_buffer[x]); break;
- #ifdef OPTION_SERIAL1_SUPPORT
- case 1: Serial1.write(serial0_buffer[x]); break;
- #endif //OPTION_SERIAL1_SUPPORT
- #ifdef OPTION_SERIAL2_SUPPORT
- case 2: Serial2.write(serial0_buffer[x]); break;
- #endif //OPTION_SERIAL1_SUPPORT
- #ifdef OPTION_SERIAL3_SUPPORT
- case 3: Serial3.write(serial0_buffer[x]); break;
- #endif //OPTION_SERIAL1_SUPPORT
+ for (byte x = 3; x < control_port_buffer_index; x++) {
+ switch (control_port_buffer[2] - 48) {
+ case 0: control_port->write(control_port_buffer[x]); break;
+ #if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE)
+ case 1: remote_unit_port->write(control_port_buffer[x]); break;
+ #endif
}
}
}
- //yyyy
- if (serial0_buffer_index == 3) {
- if (command_string == "PG") {Serial.println(F("PG"));command_good = 1;} // PG - ping
- if (command_string == "RB") {wdt_enable(WDTO_30MS); while(1) {}} // RB - reboot
+
+ if (control_port_buffer_index == 3) {
+ if (command_string == "PG") {
+ control_port->println(F("PG")); command_good = 1;
+ } // PG - ping
+ if (command_string == "RB") {
+ wdt_enable(WDTO_30MS); while (1) {
+ }
+ } // RB - reboot
if (command_string == "AZ") {
- Serial.print(F("AZ"));
- if (raw_azimuth < 1000) {Serial.print("0");}
- if (raw_azimuth < 100) {Serial.print("0");}
- if (raw_azimuth < 10) {Serial.print("0");}
- Serial.println(raw_azimuth);
+ control_port->print(F("AZ"));
+ if (raw_azimuth < 1000) {
+ control_port->print("0");
+ }
+ if (raw_azimuth < 100) {
+ control_port->print("0");
+ }
+ if (raw_azimuth < 10) {
+ control_port->print("0");
+ }
+ control_port->println(raw_azimuth);
command_good = 1;
}
#ifdef FEATURE_ELEVATION_CONTROL
if (command_string == "EL") {
- Serial.print(F("EL"));
+ control_port->print(F("EL"));
if (elevation >= 0) {
- Serial.print("+");
+ control_port->print("+");
} else {
- Serial.print("-");
+ control_port->print("-");
}
- if (abs(elevation) < 1000) {Serial.print("0");}
- if (abs(elevation) < 100) {Serial.print("0");}
- if (abs(elevation) < 10) {Serial.print("0");}
- Serial.println(abs(elevation));
- command_good = 1;
- }
- #endif //FEATURE_ELEVATION_CONTROL
+ if (abs(elevation) < 1000) {
+ control_port->print("0");
+ }
+ if (abs(elevation) < 100) {
+ control_port->print("0");
+ }
+ if (abs(elevation) < 10) {
+ control_port->print("0");
+ }
+ control_port->println(abs(elevation));
+ command_good = 1;
+ }
+ #endif // FEATURE_ELEVATION_CONTROL
} // end of three byte commands
- if (serial0_buffer_index == 4) {
- if ((command_string == "SA") & (serial0_buffer[2] > 47) && (serial0_buffer[2] < 53)){
- serial_read_event_flag[serial0_buffer[2]-48] = 1;
+ if (control_port_buffer_index == 4) {
+ if ((command_string == "SA") & (control_port_buffer[2] > 47) && (control_port_buffer[2] < 53)) {
+ serial_read_event_flag[control_port_buffer[2] - 48] = 1;
command_good = 1;
- Serial.println("OK");
+ control_port->println("OK");
}
- if ((command_string == "SD") & (serial0_buffer[2] > 47) && (serial0_buffer[2] < 53)){
- serial_read_event_flag[serial0_buffer[2]-48] = 0;
+ if ((command_string == "SD") & (control_port_buffer[2] > 47) && (control_port_buffer[2] < 53)) {
+ serial_read_event_flag[control_port_buffer[2] - 48] = 0;
command_good = 1;
- Serial.println("OK");
- }
-
+ control_port->println("OK");
+ }
+
}
-
- if (serial0_buffer_index == 5) {
- if (command_string == "SW"){ // Serial Write command
- switch (serial0_buffer[2]){
- case '0': Serial.write(serial0_buffer[3]); command_good = 1; break;
- #ifdef OPTION_SERIAL1_SUPPORT
- case '1': Serial1.write(serial0_buffer[3]); command_good = 1; break;
- #endif //OPTION_SERIAL1_SUPPORT
- }
+
+ if (control_port_buffer_index == 5) {
+ if (command_string == "SW") { // Serial Write command
+ switch (control_port_buffer[2]) {
+ case '0': control_port->write(control_port_buffer[3]); command_good = 1; break;
+ #if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE)
+ case '1': remote_unit_port->write(control_port_buffer[3]); command_good = 1; break;
+ #endif
+ }
}
-
- if (command_string == "DO"){
- if ((((serial0_buffer[2] > 47) && (serial0_buffer[2] < 58)) || (toupper(serial0_buffer[2]) == 'A')) && (serial0_buffer[3] > 47) && (serial0_buffer[3] < 58)){
+
+ if (command_string == "DO") {
+ if ((((control_port_buffer[2] > 47) && (control_port_buffer[2] < 58)) || (toupper(control_port_buffer[2]) == 'A')) && (control_port_buffer[3] > 47) && (control_port_buffer[3] < 58)) {
command_good = 1;
byte pin_value = 0;
- if (toupper(serial0_buffer[2]) == 'A'){
- pin_value = get_analog_pin(serial0_buffer[3]-48);
+ if (toupper(control_port_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(control_port_buffer[3] - 48);
} else {
- pin_value = ((serial0_buffer[2]-48)*10) + (serial0_buffer[3]-48);
+ pin_value = ((control_port_buffer[2] - 48) * 10) + (control_port_buffer[3] - 48);
}
#ifdef DEBUG_SERVICE_SERIAL_BUFFER
- Serial.print(F("service_serial_buffer: pin_value: "));
- Serial.println(pin_value);
- #endif //DEBUG_SERVICE_SERIAL_BUFFER
- Serial.println("OK");
- pinMode(pin_value,OUTPUT);
- }
+ debug_print("service_serial_buffer: pin_value: ");
+ debug_print_int(pin_value);
+ debug_println("");
+ #endif // DEBUG_SERVICE_SERIAL_BUFFER
+ control_port->println("OK");
+ pinModeEnhanced(pin_value, OUTPUT);
+ }
}
-
- if (command_string == "DH"){
- if ((((serial0_buffer[2] > 47) && (serial0_buffer[2] < 58)) || (toupper(serial0_buffer[2]) == 'A')) && (serial0_buffer[3] > 47) && (serial0_buffer[3] < 58)){
+
+ if (command_string == "DH") {
+ if ((((control_port_buffer[2] > 47) && (control_port_buffer[2] < 58)) || (toupper(control_port_buffer[2]) == 'A')) && (control_port_buffer[3] > 47) && (control_port_buffer[3] < 58)) {
command_good = 1;
byte pin_value = 0;
- if (toupper(serial0_buffer[2]) == 'A'){
- pin_value = get_analog_pin(serial0_buffer[3]-48);
+ if (toupper(control_port_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(control_port_buffer[3] - 48);
} else {
- pin_value = ((serial0_buffer[2]-48)*10) + (serial0_buffer[3]-48);
+ pin_value = ((control_port_buffer[2] - 48) * 10) + (control_port_buffer[3] - 48);
}
- digitalWrite(pin_value,HIGH);
- Serial.println("OK");
- }
- }
-
- if (command_string == "DL"){
- if ((((serial0_buffer[2] > 47) && (serial0_buffer[2] < 58)) || (toupper(serial0_buffer[2]) == 'A')) && (serial0_buffer[3] > 47) && (serial0_buffer[3] < 58)){
+ digitalWriteEnhanced(pin_value, HIGH);
+ control_port->println("OK");
+ }
+ }
+
+ if (command_string == "DL") {
+ if ((((control_port_buffer[2] > 47) && (control_port_buffer[2] < 58)) || (toupper(control_port_buffer[2]) == 'A')) && (control_port_buffer[3] > 47) && (control_port_buffer[3] < 58)) {
command_good = 1;
byte pin_value = 0;
- if (toupper(serial0_buffer[2]) == 'A'){
- pin_value = get_analog_pin(serial0_buffer[3]-48);
+ if (toupper(control_port_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(control_port_buffer[3] - 48);
} else {
- pin_value = ((serial0_buffer[2]-48)*10) + (serial0_buffer[3]-48);
+ pin_value = ((control_port_buffer[2] - 48) * 10) + (control_port_buffer[3] - 48);
}
- digitalWrite(pin_value,LOW);
- Serial.println("OK");
- }
- }
-
- if (command_string == "DI"){
- if ((((serial0_buffer[2] > 47) && (serial0_buffer[2] < 58)) || (toupper(serial0_buffer[2]) == 'A')) && (serial0_buffer[3] > 47) && (serial0_buffer[3] < 58)){
+ digitalWriteEnhanced(pin_value, LOW);
+ control_port->println("OK");
+ }
+ }
+
+ if (command_string == "DI") {
+ if ((((control_port_buffer[2] > 47) && (control_port_buffer[2] < 58)) || (toupper(control_port_buffer[2]) == 'A')) && (control_port_buffer[3] > 47) && (control_port_buffer[3] < 58)) {
command_good = 1;
byte pin_value = 0;
- if (toupper(serial0_buffer[2]) == 'A'){
- pin_value = get_analog_pin(serial0_buffer[3]-48);
+ if (toupper(control_port_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(control_port_buffer[3] - 48);
} else {
- pin_value = ((serial0_buffer[2]-48)*10) + (serial0_buffer[3]-48);
+ pin_value = ((control_port_buffer[2] - 48) * 10) + (control_port_buffer[3] - 48);
}
- pinMode(pin_value,INPUT);
- Serial.println("OK");
- }
- }
-
- if (command_string == "DP"){
- if ((((serial0_buffer[2] > 47) && (serial0_buffer[2] < 58)) || (toupper(serial0_buffer[2]) == 'A')) && (serial0_buffer[3] > 47) && (serial0_buffer[3] < 58)){
+ pinModeEnhanced(pin_value, INPUT);
+ control_port->println("OK");
+ }
+ }
+
+ if (command_string == "DP") {
+ if ((((control_port_buffer[2] > 47) && (control_port_buffer[2] < 58)) || (toupper(control_port_buffer[2]) == 'A')) && (control_port_buffer[3] > 47) && (control_port_buffer[3] < 58)) {
command_good = 1;
byte pin_value = 0;
- if (toupper(serial0_buffer[2]) == 'A'){
- pin_value = get_analog_pin(serial0_buffer[3]-48);
+ if (toupper(control_port_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(control_port_buffer[3] - 48);
} else {
- pin_value = ((serial0_buffer[2]-48)*10) + (serial0_buffer[3]-48);
+ pin_value = ((control_port_buffer[2] - 48) * 10) + (control_port_buffer[3] - 48);
}
- //pinMode(pin_value,INPUT_PULLUP);
- pinMode(pin_value,INPUT);
- digitalWrite(pin_value,HIGH);
- Serial.println("OK");
- }
- }
-
- if (command_string == "DR"){
- if ((((serial0_buffer[2] > 47) && (serial0_buffer[2] < 58)) || (toupper(serial0_buffer[2]) == 'A')) && (serial0_buffer[3] > 47) && (serial0_buffer[3] < 58)){
+ // pinModeEnhanced(pin_value,INPUT_PULLUP);
+ pinModeEnhanced(pin_value, INPUT);
+ digitalWriteEnhanced(pin_value, HIGH);
+ control_port->println("OK");
+ }
+ }
+
+ if (command_string == "DR") {
+ if ((((control_port_buffer[2] > 47) && (control_port_buffer[2] < 58)) || (toupper(control_port_buffer[2]) == 'A')) && (control_port_buffer[3] > 47) && (control_port_buffer[3] < 58)) {
command_good = 1;
byte pin_value = 0;
- if (toupper(serial0_buffer[2]) == 'A'){
- pin_value = get_analog_pin(serial0_buffer[3]-48);
+ if (toupper(control_port_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(control_port_buffer[3] - 48);
} else {
- pin_value = ((serial0_buffer[2]-48)*10) + (serial0_buffer[3]-48);
+ pin_value = ((control_port_buffer[2] - 48) * 10) + (control_port_buffer[3] - 48);
}
- byte pin_read = digitalRead(pin_value);
- Serial.print("DR");
- Serial.write(serial0_buffer[2]);
- Serial.write(serial0_buffer[3]);
- if (pin_read){
- Serial.println("1");
+ byte pin_read = digitalReadEnhanced(pin_value);
+ control_port->print("DR");
+ control_port->write(control_port_buffer[2]);
+ control_port->write(control_port_buffer[3]);
+ if (pin_read) {
+ control_port->println("1");
} else {
- Serial.println("0");
+ control_port->println("0");
}
- }
- }
- if (command_string == "AR"){
- if ((((serial0_buffer[2] > 47) && (serial0_buffer[2] < 58)) || (toupper(serial0_buffer[2]) == 'A')) && (serial0_buffer[3] > 47) && (serial0_buffer[3] < 58)){
+ }
+ }
+ if (command_string == "AR") {
+ if ((((control_port_buffer[2] > 47) && (control_port_buffer[2] < 58)) || (toupper(control_port_buffer[2]) == 'A')) && (control_port_buffer[3] > 47) && (control_port_buffer[3] < 58)) {
command_good = 1;
byte pin_value = 0;
- if (toupper(serial0_buffer[2]) == 'A'){
- pin_value = get_analog_pin(serial0_buffer[3]-48);
+ if (toupper(control_port_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(control_port_buffer[3] - 48);
} else {
- pin_value = ((serial0_buffer[2]-48)*10) + (serial0_buffer[3]-48);
+ pin_value = ((control_port_buffer[2] - 48) * 10) + (control_port_buffer[3] - 48);
}
- int pin_read = analogRead(pin_value);
- Serial.print("AR");
- Serial.write(serial0_buffer[2]);
- Serial.write(serial0_buffer[3]);
- if (pin_read < 1000) {Serial.print("0");}
- if (pin_read < 100) {Serial.print("0");}
- if (pin_read < 10) {Serial.print("0");}
- Serial.println(pin_read);
- }
- }
-
- if (command_string == "NT"){
- if ((((serial0_buffer[2] > 47) && (serial0_buffer[2] < 58)) || (toupper(serial0_buffer[2]) == 'A')) && (serial0_buffer[3] > 47) && (serial0_buffer[3] < 58)){
+ int pin_read = analogReadEnhanced(pin_value);
+ control_port->print("AR");
+ control_port->write(control_port_buffer[2]);
+ control_port->write(control_port_buffer[3]);
+ if (pin_read < 1000) {
+ control_port->print("0");
+ }
+ if (pin_read < 100) {
+ control_port->print("0");
+ }
+ if (pin_read < 10) {
+ control_port->print("0");
+ }
+ control_port->println(pin_read);
+ }
+ }
+
+ if (command_string == "NT") {
+ if ((((control_port_buffer[2] > 47) && (control_port_buffer[2] < 58)) || (toupper(control_port_buffer[2]) == 'A')) && (control_port_buffer[3] > 47) && (control_port_buffer[3] < 58)) {
command_good = 1;
byte pin_value = 0;
- if (toupper(serial0_buffer[2]) == 'A'){
- pin_value = get_analog_pin(serial0_buffer[3]-48);
+ if (toupper(control_port_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(control_port_buffer[3] - 48);
} else {
- pin_value = ((serial0_buffer[2]-48)*10) + (serial0_buffer[3]-48);
+ pin_value = ((control_port_buffer[2] - 48) * 10) + (control_port_buffer[3] - 48);
}
noTone(pin_value);
- Serial.println("OK");
- }
- }
-
- } //if (serial0_buffer_index == 5)
-
- if (serial0_buffer_index == 8) {
- if (command_string == "AW"){
- if ((((serial0_buffer[2] > 47) && (serial0_buffer[2] < 58)) || (toupper(serial0_buffer[2]) == 'A')) && (serial0_buffer[3] > 47) && (serial0_buffer[3] < 58)){
+ control_port->println("OK");
+ }
+ }
+
+ } // if (control_port_buffer_index == 5)
+
+ if (control_port_buffer_index == 8) {
+ if (command_string == "AW") {
+ if ((((control_port_buffer[2] > 47) && (control_port_buffer[2] < 58)) || (toupper(control_port_buffer[2]) == 'A')) && (control_port_buffer[3] > 47) && (control_port_buffer[3] < 58)) {
byte pin_value = 0;
- if (toupper(serial0_buffer[2]) == 'A'){
- pin_value = get_analog_pin(serial0_buffer[3]-48);
+ if (toupper(control_port_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(control_port_buffer[3] - 48);
} else {
- pin_value = ((serial0_buffer[2]-48)*10) + (serial0_buffer[3]-48);
+ pin_value = ((control_port_buffer[2] - 48) * 10) + (control_port_buffer[3] - 48);
}
- int write_value = ((serial0_buffer[4]-48)*100) + ((serial0_buffer[5]-48)*10) + (serial0_buffer[6]-48);
- if ((write_value >= 0) && (write_value < 256)){
- analogWrite(pin_value,write_value);
- Serial.println("OK");
+ int write_value = ((control_port_buffer[4] - 48) * 100) + ((control_port_buffer[5] - 48) * 10) + (control_port_buffer[6] - 48);
+ if ((write_value >= 0) && (write_value < 256)) {
+ analogWriteEnhanced(pin_value, write_value);
+ control_port->println("OK");
command_good = 1;
}
- }
- }
+ }
+ }
}
- if (serial0_buffer_index == 9) {
- if (command_string == "DT"){
- if ((((serial0_buffer[2] > 47) && (serial0_buffer[2] < 58)) || (toupper(serial0_buffer[2]) == 'A')) && (serial0_buffer[3] > 47) && (serial0_buffer[3] < 58)){
+ if (control_port_buffer_index == 9) {
+ if (command_string == "DT") {
+ if ((((control_port_buffer[2] > 47) && (control_port_buffer[2] < 58)) || (toupper(control_port_buffer[2]) == 'A')) && (control_port_buffer[3] > 47) && (control_port_buffer[3] < 58)) {
byte pin_value = 0;
- if (toupper(serial0_buffer[2]) == 'A'){
- pin_value = get_analog_pin(serial0_buffer[3]-48);
+ if (toupper(control_port_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(control_port_buffer[3] - 48);
} else {
- pin_value = ((serial0_buffer[2]-48)*10) + (serial0_buffer[3]-48);
+ pin_value = ((control_port_buffer[2] - 48) * 10) + (control_port_buffer[3] - 48);
}
- int write_value = ((serial0_buffer[4]-48)*1000) + ((serial0_buffer[5]-48)*100) + ((serial0_buffer[6]-48)*10) + (serial0_buffer[7]-48);
- if ((write_value >= 0) && (write_value <= 9999)){
- tone(pin_value,write_value);
- Serial.println("OK");
+ int write_value = ((control_port_buffer[4] - 48) * 1000) + ((control_port_buffer[5] - 48) * 100) + ((control_port_buffer[6] - 48) * 10) + (control_port_buffer[7] - 48);
+ if ((write_value >= 0) && (write_value <= 9999)) {
+ tone(pin_value, write_value);
+ control_port->println("OK");
command_good = 1;
}
- }
- }
- }
-
-
- if (!command_good){Serial.println(F("ER02"));}
+ }
+ }
+ }
+
+
+ if (!command_good) {
+ control_port->println(F("ER02"));
+ }
}
- serial0_buffer_carriage_return_flag = 0;
- serial0_buffer_index = 0;
+ control_port_buffer_carriage_return_flag = 0;
+ control_port_buffer_index = 0;
} else {
- if (((millis() - last_serial_receive_time) > REMOTE_BUFFER_TIMEOUT_MS) && serial0_buffer_index){
- Serial.println(F("ER01"));
- serial0_buffer_index = 0;
+ if (((millis() - last_serial_receive_time) > REMOTE_BUFFER_TIMEOUT_MS) && control_port_buffer_index) {
+ control_port->println(F("ER01"));
+ control_port_buffer_index = 0;
}
}
-
-
-}
-#endif //FEATURE_REMOTE_UNIT_SLAVE
-//--------------------------------------------------------------
+
+} /* service_remote_unit_serial_buffer */
+
+ #endif // FEATURE_REMOTE_UNIT_SLAVE
+// --------------------------------------------------------------
void check_serial(){
-
-
- if (Serial.available()) {
+ static unsigned long serial_led_time = 0;
+ float tempfloat = 0;
+ char return_string[100] = "";
+
+ #if !defined(FEATURE_AZ_POSITION_ROTARY_ENCODER) && !defined(FEATURE_AZ_POSITION_PULSE_INPUT)
+ long place_multiplier = 0;
+ byte decimalplace = 0;
+ #endif
+
+ #ifdef FEATURE_CLOCK
+ int temp_year = 0;
+ byte temp_month = 0;
+ byte temp_day = 0;
+ byte temp_minute = 0;
+ byte temp_hour = 0;
+ #endif // FEATURE_CLOCK
+
+ #if defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)
+ char grid[10] = "";
+ byte hit_error = 0;
+ #endif // defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)
+
+ #if defined(FEATURE_AZ_POSITION_ROTARY_ENCODER) || defined(FEATURE_AZ_POSITION_PULSE_INPUT)
+ int new_azimuth = 9999;
+ #endif
+ #ifdef FEATURE_ELEVATION_CONTROL
+ #if defined(FEATURE_EL_POSITION_ROTARY_ENCODER) || defined(FEATURE_EL_POSITION_PULSE_INPUT)
+ int new_elevation = 9999;
+ #endif // FEATURE_ELEVATION_CONTROL
+ #endif // defined(FEATURE_AZ_POSITION_ROTARY_ENCODER) || defined(FEATURE_AZ_POSITION_PULSE_INPUT)
+
+
+ #if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
+
+ if ((serial_led) && (serial_led_time != 0) && ((millis() - serial_led_time) > SERIAL_LED_TIME_MS)) {
+ digitalWriteEnhanced(serial_led, LOW);
+ serial_led_time = 0;
+ }
+
+ if (control_port->available()) {
if (serial_led) {
- digitalWrite(serial_led, HIGH); // blink the LED just to say we got something
+ digitalWriteEnhanced(serial_led, HIGH); // blink the LED just to say we got something
+ serial_led_time = millis();
}
-
- incoming_serial_byte = Serial.read();
+
+ #ifdef FEATURE_POWER_SWITCH
+ last_activity_time = millis();
+ #endif //FEATURE_POWER_SWITCH
+
+ #ifdef DEBUG_SERIAL
+ int control_port_available = control_port->available();
+ #endif // DEBUG_SERIAL
+
+ incoming_serial_byte = control_port->read();
last_serial_receive_time = millis();
-
- if ((incoming_serial_byte == 92) && (serial0_buffer_index == 0)) { // do we have a backslash command?
- serial0_buffer[serial0_buffer_index] = incoming_serial_byte;
- serial0_buffer_index++;
- backslash_command = 1;
- return;
- }
-
- if (backslash_command) {
- if (incoming_serial_byte == 13) { // do we have a carriage return?
- switch(serial0_buffer[1]){
- case 'D': if (debug_mode) {debug_mode = 0;} else {debug_mode = 1;} break; // D - Debug
- case 'E' : // E - Initialize eeprom
- initialize_eeprom_with_defaults();
- Serial.println(F("Initialized eeprom, please reset..."));
- break;
- case 'L': // L - rotate to long path
- if (azimuth < (180*HEADING_MULTIPLIER)){
- submit_request(AZ,REQUEST_AZIMUTH,(azimuth+(180*HEADING_MULTIPLIER)));
- } else {
- submit_request(AZ,REQUEST_AZIMUTH,(azimuth-(180*HEADING_MULTIPLIER)));
- }
- break;
-
- #ifdef FEATURE_HOST_REMOTE_PROTOCOL
- case 'R' :
- Serial.print(F("Remote port rx sniff o"));
- if (remote_port_rx_sniff){
- remote_port_rx_sniff = 0;
- Serial.println("ff");
- } else {
- remote_port_rx_sniff = 1;
- Serial.println("n");
- }
- break;
- case 'S':
- for (int x = 2;x < serial0_buffer_index;x++){
- Serial1.write(serial0_buffer[x]);
- if (remote_port_tx_sniff){
- Serial.write(serial0_buffer[x]);
- }
- }
- Serial1.write(13);
- if (remote_port_tx_sniff){
- Serial.write(13);
- }
- break;
- case 'T' :
- Serial.print(F("Remote port tx sniff o"));
- if (remote_port_tx_sniff){
- remote_port_tx_sniff = 0;
- Serial.println("ff");
- } else {
- remote_port_tx_sniff = 1;
- Serial.println("n");
- }
- break;
- case 'Z' :
- Serial.print(F("Suspend auto remote commands o"));
- if (suspend_remote_commands){
- suspend_remote_commands = 0;
- Serial.println("ff");
- } else {
- suspend_remote_commands = 1;
- Serial.println("n");
- }
- break;
- #endif //FEATURE_HOST_REMOTE_PROTOCOL
-
- #ifdef FEATURE_ANCILLARY_PIN_CONTROL
- case 'N' : // \Nxx - turn pin on; xx = pin number
- if ((((serial0_buffer[2] > 47) && (serial0_buffer[2] < 58)) || (toupper(serial0_buffer[2]) == 'A')) && (serial0_buffer[3] > 47) && (serial0_buffer[3] < 58) && (serial0_buffer_index == 4)){
- byte pin_value = 0;
- if (toupper(serial0_buffer[2]) == 'A'){
- pin_value = get_analog_pin(serial0_buffer[3]-48);
- } else {
- pin_value = ((serial0_buffer[2]-48)*10) + (serial0_buffer[3]-48);
- }
- pinMode(pin_value,OUTPUT);
- digitalWrite(pin_value,HIGH);
- Serial.println("OK");
- } else {
- Serial.println(F("Error"));
- }
- break;
- case 'F' : // \Fxx - turn pin off; xx = pin number
- if ((((serial0_buffer[2] > 47) && (serial0_buffer[2] < 58)) || (toupper(serial0_buffer[2]) == 'A')) && (serial0_buffer[3] > 47) && (serial0_buffer[3] < 58) && (serial0_buffer_index == 4)){
- byte pin_value = 0;
- if (toupper(serial0_buffer[2]) == 'A'){
- pin_value = get_analog_pin(serial0_buffer[3]-48);
- } else {
- pin_value = ((serial0_buffer[2]-48)*10) + (serial0_buffer[3]-48);
- }
- pinMode(pin_value,OUTPUT);
- digitalWrite(pin_value,LOW);
- Serial.println("OK");
- } else {
- Serial.println(F("Error"));
- }
- break;
- case 'P' : // \Pxxyyy - turn on pin PWM; xx = pin number, yyy = PWM value (0-255)
- if (((serial0_buffer[2] > 47) && (serial0_buffer[2] < 58)) && (serial0_buffer[3] > 47) && (serial0_buffer[3] < 58) && (serial0_buffer_index == 7)){
- byte pin_value = 0;
- if (toupper(serial0_buffer[2]) == 'A'){
- pin_value = get_analog_pin(serial0_buffer[3]-48);
- } else {
- pin_value = ((serial0_buffer[2]-48)*10) + (serial0_buffer[3]-48);
- }
- int write_value = ((serial0_buffer[4]-48)*100) + ((serial0_buffer[5]-48)*10) + (serial0_buffer[6]-48);
- if ((write_value >= 0) && (write_value < 256)){
- pinMode(pin_value,OUTPUT);
- analogWrite(pin_value,write_value);
- Serial.println("OK");
- } else {
- Serial.println(F("Error"));
- }
- } else {
- Serial.println(F("Error"));
- }
- break;
- #endif //FEATURE_ANCILLARY_PIN_CONTROL
-
- default: Serial.println(F("error"));
- }
- clear_command_buffer();
- backslash_command = 0;
-
- } else { // no, add the character to the buffer
- if ((incoming_serial_byte > 96) && (incoming_serial_byte < 123)) {incoming_serial_byte = incoming_serial_byte - 32;} //uppercase it
- if (incoming_serial_byte != 10) { // add it to the buffer if it's not a line feed
- serial0_buffer[serial0_buffer_index] = incoming_serial_byte;
- serial0_buffer_index++;
- }
- }
-
- } else {
-
-
- #ifdef FEATURE_YAESU_EMULATION
- yaesu_serial_command();
- #endif //FEATURE_YAESU_EMULATION
-
- #ifdef FEATURE_EASYCOM_EMULATION
- easycom_serial_commmand();
- #endif //FEATURE_EASYCOM_EMULATION
-
- #ifdef FEATURE_REMOTE_UNIT_SLAVE
- remote_unit_serial_command();
- #endif //FEATURE_REMOTE_UNIT_SLAVE
-
- }
-
- if (serial_led) {
- digitalWrite(serial_led, LOW);
- }
- } //if (Serial.available())
-
- #ifdef OPTION_SERIAL1_SUPPORT
- if (Serial1.available()){
- incoming_serial_byte = Serial1.read();
- #ifdef FEATURE_REMOTE_UNIT_SLAVE
- if (serial_read_event_flag[1]){
- Serial.print("EVS1");
- Serial.write(incoming_serial_byte);
- Serial.println();
- }
- #endif //FEATURE_REMOTE_UNIT_SLAVE
- #ifdef FEATURE_HOST_REMOTE_PROTOCOL
- if (remote_port_rx_sniff) {Serial.write(incoming_serial_byte);}
- if ((incoming_serial_byte != 10) && (serial1_buffer_index < COMMAND_BUFFER_SIZE)){
- //incoming_serial_byte = toupper(incoming_serial_byte);
- serial1_buffer[serial1_buffer_index] = incoming_serial_byte;
- serial1_buffer_index++;
- if ((incoming_serial_byte == 13) || (serial1_buffer_index == COMMAND_BUFFER_SIZE)){
- serial1_buffer_carriage_return_flag = 1;
- }
+ #ifdef DEBUG_SERIAL
+ debug_print("check_serial: control_port: ");
+ debug_print_int(control_port_available);
+ debug_print(":");
+ debug_print_int(incoming_serial_byte);
+ debug_println("");
+ #endif // DEBUG_SERIAL
+
+
+ if ((incoming_serial_byte > 96) && (incoming_serial_byte < 123)) { // uppercase it
+ incoming_serial_byte = incoming_serial_byte - 32;
+ }
+
+
+ #ifdef FEATURE_EASYCOM_EMULATION //Easycom uses spaces, linefeeds, and carriage returns as command delimiters----------
+
+ // Easycom only
+
+ if ((control_port_buffer[0] == '\\') or (control_port_buffer[0] == '/') or ((control_port_buffer_index == 0) && ((incoming_serial_byte == '\\') || (incoming_serial_byte == '/')))) {
+ // if it's a backslash command add it to the buffer if it's not a line feed or carriage return
+ if ((incoming_serial_byte != 10) && (incoming_serial_byte != 13)) {
+ control_port_buffer[control_port_buffer_index] = incoming_serial_byte;
+ control_port_buffer_index++;
+ }
+ } else {
+ // if it's an easycom command add it to the buffer if it's not a line feed, carriage return, or space
+ if ((incoming_serial_byte != 10) && (incoming_serial_byte != 13) && (incoming_serial_byte != 32)) {
+ control_port_buffer[control_port_buffer_index] = incoming_serial_byte;
+ control_port_buffer_index++;
+ }
+ }
+
+ // if it is an Easycom command and we have a space, line feed, or carriage return, process it
+ if (((incoming_serial_byte == 10) || (incoming_serial_byte == 13) || (incoming_serial_byte == 32)) && (control_port_buffer[0] != '\\') && (control_port_buffer[0] != '/')){
+ if (control_port_buffer_index > 1){
+ process_easycom_command(control_port_buffer,control_port_buffer_index,CONTROL_PORT0,return_string);
+ control_port->println(return_string);
+ }
+ clear_command_buffer();
+ } else {
+ // if it is a backslash command, process it if we have a carriage return
+ if ((incoming_serial_byte == 13) && ((control_port_buffer[0] == '\\') or (control_port_buffer[0] == '/'))){
+ process_backslash_command(control_port_buffer, control_port_buffer_index, CONTROL_PORT0, return_string);
+ control_port->println(return_string);
+ clear_command_buffer();
+ }
+ }
+
+
+ #else //FEATURE_EASYCOM_EMULATION ------------------------------------------------------
+ // Yaesu, Remote Slave
+ if ((incoming_serial_byte != 10) && (incoming_serial_byte != 13)) { // add it to the buffer if it's not a line feed or carriage return
+ control_port_buffer[control_port_buffer_index] = incoming_serial_byte;
+ control_port_buffer_index++;
+ }
+
+ if (incoming_serial_byte == 13) { // do we have a carriage return?
+ if ((control_port_buffer[0] == '\\') or (control_port_buffer[0] == '/')) {
+ process_backslash_command(control_port_buffer, control_port_buffer_index, CONTROL_PORT0, return_string);
+ } else {
+ #ifdef FEATURE_YAESU_EMULATION
+ process_yaesu_command(control_port_buffer,control_port_buffer_index,CONTROL_PORT0,return_string);
+ #endif //FEATURE_YAESU_EMULATION
+
+ #ifdef FEATURE_REMOTE_UNIT_SLAVE
+ process_remote_slave_command(control_port_buffer,control_port_buffer_index,CONTROL_PORT0,return_string);
+ #endif //FEATURE_REMOTE_UNIT_SLAVE
+ }
+ control_port->println(return_string);
+ clear_command_buffer();
+ }
+
+ #endif //FEATURE_EASYCOM_EMULATION--------------------------
+
+
+
+ } // if (control_port->available())
+ #endif // defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
+
+
+ // remote unit port servicing
+ #if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE)
+ if (remote_unit_port->available()) {
+ incoming_serial_byte = remote_unit_port->read();
+
+ #if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
+ // if (serial_read_event_flag[1]) {
+ // control_port->print("EVS1");
+ // control_port->write(incoming_serial_byte);
+ // control_port->println();
+ // }
+ if (remote_port_rx_sniff) {
+ control_port->write(incoming_serial_byte);
+ }
+ #endif //defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
+
+ if ((incoming_serial_byte != 10) && (remote_unit_port_buffer_index < COMMAND_BUFFER_SIZE)) {
+ // incoming_serial_byte = toupper(incoming_serial_byte);
+ remote_unit_port_buffer[remote_unit_port_buffer_index] = incoming_serial_byte;
+ remote_unit_port_buffer_index++;
+ if ((incoming_serial_byte == 13) || (remote_unit_port_buffer_index == COMMAND_BUFFER_SIZE)) {
+ remote_unit_port_buffer_carriage_return_flag = 1;
+ }
}
serial1_last_receive_time = millis();
- #endif //FEATURE_HOST_REMOTE_PROTOCOL
- }
- #endif //OPTION_SERIAL1_SUPPORT
- #ifdef OPTION_SERIAL2_SUPPORT
- if (Serial2.available()){
- incoming_serial_byte = Serial2.read();
- #ifdef FEATURE_REMOTE_UNIT_SLAVE
- if (serial_read_event_flag[2]){
- Serial.print("EVS1");
- Serial.write(incoming_serial_byte);
- Serial.println();
- }
- #endif //FEATURE_REMOTE_UNIT_SLAVE
}
- #endif //OPTION_SERIAL2_SUPPORT
-
- #ifdef OPTION_SERIAL3_SUPPORT
- if (Serial3.available()){
- incoming_serial_byte = Serial3.read();
- #ifdef FEATURE_REMOTE_UNIT_SLAVE
- if (serial_read_event_flag[3]){
- Serial.print("EVS3");
- Serial.write(incoming_serial_byte);
- Serial.println();
- }
- #endif //FEATURE_REMOTE_UNIT_SLAVE
- }
- #endif //OPTION_SERIAL3_SUPPORT
-
- #ifdef OPTION_SERIAL4_SUPPORT
- if (Serial4.available()){
- incoming_serial_byte = Serial4.read();
- #ifdef FEATURE_REMOTE_UNIT_SLAVE
- if (serial_read_event_flag[4]){
- Serial.print("EVS4");
- Serial.write(incoming_serial_byte);
- Serial.println();
- }
- #endif //FEATURE_REMOTE_UNIT_SLAVE
- }
- #endif //OPTION_SERIAL4_SUPPORT
+ #endif // defined(FEATURE_MASTER_WITH_SERIAL_SLAVE)
-}
+ #ifdef FEATURE_GPS
+ if (gps_port->available()) {
+ byte gps_port_read = gps_port->read();
+ #ifdef GPS_MIRROR_PORT
+ gps_mirror_port->write(gps_port_read);
+ #endif //GPS_MIRROR_PORT
+ #ifdef DEBUG_GPS_SERIAL
+ debug_print_char(gps_port_read);
+ //port_flush();
+ #endif //DEBUG_GPS_SERIAL
+ if (gps.encode(gps_port_read)) {
+ gps_data_available = 1;
+ }
+ }
+ #endif // FEATURE_GPS
-//--------------------------------------------------------------
+ #if defined(GPS_MIRROR_PORT) && defined(FEATURE_GPS)
+ if (gps_mirror_port->available()) {
+ gps_port->write(gps_mirror_port->read());
+ }
+ #endif //defined(GPS_MIRROR_PORT) && defined(FEATURE_GPS)
+
+
+} /* check_serial */
+
+
+// --------------------------------------------------------------
void check_buttons(){
#ifdef FEATURE_ADAFRUIT_BUTTONS
@@ -2491,1062 +2383,1739 @@ void check_buttons(){
if (buttons & BUTTON_RIGHT) {
#else
- if (button_cw && (digitalRead(button_cw) == LOW)) {
- #endif //FEATURE_ADAFRUIT_BUTTONS
+ if (button_cw && (digitalReadEnhanced(button_cw) == BUTTON_ACTIVE_STATE)) {
+ #endif // FEATURE_ADAFRUIT_BUTTONS
if (azimuth_button_was_pushed == 0) {
- #ifdef DEBUG_BUTTONS
- if (debug_mode) {Serial.println(F("check_buttons: button_cw pushed"));}
- #endif //DEBUG_BUTTONS
- #ifdef OPTION_AZ_MANUAL_ROTATE_LIMITS
- if (raw_azimuth < (AZ_MANUAL_ROTATE_CW_LIMIT*HEADING_MULTIPLIER)) {
- #endif
- submit_request(AZ,REQUEST_CW,0);
+ #ifdef DEBUG_BUTTONS
+ debug_println("check_buttons: button_cw pushed");
+ #endif // DEBUG_BUTTONS
+ #ifdef OPTION_AZ_MANUAL_ROTATE_LIMITS
+ if (raw_azimuth < (AZ_MANUAL_ROTATE_CW_LIMIT * HEADING_MULTIPLIER)) {
+ #endif
+ submit_request(AZ, REQUEST_CW, 0, 61);
azimuth_button_was_pushed = 1;
#ifdef OPTION_AZ_MANUAL_ROTATE_LIMITS
- } else {
- #ifdef DEBUG_BUTTONS
- if (debug_mode) {Serial.println(F("check_buttons: exceeded AZ_MANUAL_ROTATE_CW_LIMIT"));}
- #endif //DEBUG_BUTTONS
- }
- #endif
+ } else {
+ #ifdef DEBUG_BUTTONS
+ debug_println("check_buttons: exceeded AZ_MANUAL_ROTATE_CW_LIMIT");
+ #endif // DEBUG_BUTTONS
+ }
+ #endif
}
} else {
- #ifdef FEATURE_ADAFRUIT_BUTTONS
- if (buttons & BUTTON_LEFT) {
- #else
- if (button_ccw && (digitalRead(button_ccw) == LOW)) {
- #endif //FEATURE_ADAFRUIT_BUTTONS
- if (azimuth_button_was_pushed == 0) {
- #ifdef DEBUG_BUTTONS
- if (debug_mode) {
- Serial.println(F("check_buttons: button_ccw pushed"));
- }
- #endif //DEBUG_BUTTONS
- #ifdef OPTION_AZ_MANUAL_ROTATE_LIMITS
- if (raw_azimuth > (AZ_MANUAL_ROTATE_CCW_LIMIT*HEADING_MULTIPLIER)) {
- #endif
- submit_request(AZ,REQUEST_CCW,0);
+ #ifdef FEATURE_ADAFRUIT_BUTTONS
+ if (buttons & BUTTON_LEFT) {
+ #else
+ if (button_ccw && (digitalReadEnhanced(button_ccw) == BUTTON_ACTIVE_STATE)) {
+ #endif // FEATURE_ADAFRUIT_BUTTONS
+ if (azimuth_button_was_pushed == 0) {
+ #ifdef DEBUG_BUTTONS
+ debug_println("check_buttons: button_ccw pushed");
+ #endif // DEBUG_BUTTONS
+ #ifdef OPTION_AZ_MANUAL_ROTATE_LIMITS
+ if (raw_azimuth > (AZ_MANUAL_ROTATE_CCW_LIMIT * HEADING_MULTIPLIER)) {
+ #endif
+ submit_request(AZ, REQUEST_CCW, 0, 62);
azimuth_button_was_pushed = 1;
- #ifdef OPTION_AZ_MANUAL_ROTATE_LIMITS
- } else {
- #ifdef DEBUG_BUTTONS
- if (debug_mode) {Serial.println(F("check_buttons: exceeded AZ_MANUAL_ROTATE_CCW_LIMIT"));}
- #endif //DEBUG_BUTTONS
- }
- #endif //OPTION_AZ_MANUAL_ROTATE_LIMITS
+ #ifdef OPTION_AZ_MANUAL_ROTATE_LIMITS
+ } else {
+ #ifdef DEBUG_BUTTONS
+ debug_println("check_buttons: exceeded AZ_MANUAL_ROTATE_CCW_LIMIT");
+ #endif // DEBUG_BUTTONS
+ }
+ #endif // OPTION_AZ_MANUAL_ROTATE_LIMITS
}
}
}
- #ifdef FEATURE_ADAFRUIT_BUTTONS
+#ifdef FEATURE_ADAFRUIT_BUTTONS
if ((azimuth_button_was_pushed) && (!(buttons & 0x12))) {
#ifdef DEBUG_BUTTONS
- if (debug_mode) {
- Serial.println(F("check_buttons: no button depressed"));
- }
+ debug_println("check_buttons: no button depressed");
#endif // DEBUG_BUTTONS
- submit_request(AZ,REQUEST_STOP,0);
+ submit_request(AZ, REQUEST_STOP, 0, 63);
azimuth_button_was_pushed = 0;
}
-
- #else
- if ((azimuth_button_was_pushed) && (digitalRead(button_ccw) == HIGH) && (digitalRead(button_cw) == HIGH)) {
+
+#else
+ if ((azimuth_button_was_pushed) && (digitalReadEnhanced(button_ccw) == BUTTON_INACTIVE_STATE) && (digitalReadEnhanced(button_cw) == BUTTON_INACTIVE_STATE)) {
delay(200);
- if ((digitalRead(button_ccw) == HIGH) && (digitalRead(button_cw) == HIGH)) {
- #ifdef DEBUG_BUTTONS
- if (debug_mode) {
- Serial.println(F("check_buttons: no AZ button depressed"));
- }
- #endif // DEBUG_BUTTONS
- submit_request(AZ,REQUEST_STOP,0);
- azimuth_button_was_pushed = 0;
+ if ((digitalReadEnhanced(button_ccw) == BUTTON_INACTIVE_STATE) && (digitalReadEnhanced(button_cw) == BUTTON_INACTIVE_STATE)) {
+ #ifdef DEBUG_BUTTONS
+ debug_println("check_buttons: no AZ button depressed");
+ #endif // DEBUG_BUTTONS
+ #ifndef OPTION_BUTTON_RELEASE_NO_SLOWDOWN
+ submit_request(AZ, REQUEST_STOP, 0, 64);
+ #else
+ submit_request(AZ, REQUEST_KILL, 0, 65);
+ #endif // OPTION_BUTTON_RELEASE_NO_SLOWDOWN
+ azimuth_button_was_pushed = 0;
}
}
- #endif //FEATURE_ADAFRUIT_BUTTONS
+#endif // FEATURE_ADAFRUIT_BUTTONS
- #ifdef FEATURE_ELEVATION_CONTROL
- #ifdef FEATURE_ADAFRUIT_BUTTONS
+#ifdef FEATURE_ELEVATION_CONTROL
+#ifdef FEATURE_ADAFRUIT_BUTTONS
if (buttons & 0x08) {
#else
- if (button_up && (digitalRead(button_up) == LOW)) {
- #endif //FEATURE_ADAFRUIT_BUTTONS
+ if (button_up && (digitalReadEnhanced(button_up) == BUTTON_ACTIVE_STATE)) {
+ #endif // FEATURE_ADAFRUIT_BUTTONS
if (elevation_button_was_pushed == 0) {
- submit_request(EL,REQUEST_UP,0);
+ submit_request(EL, REQUEST_UP, 0, 66);
elevation_button_was_pushed = 1;
#ifdef DEBUG_BUTTONS
- if (debug_mode) {
- Serial.println(F("check_buttons: button_up pushed"));
- }
- #endif //DEBUG_BUTTONS
+ debug_println("check_buttons: button_up pushed");
+ #endif // DEBUG_BUTTONS
}
} else {
#ifdef FEATURE_ADAFRUIT_BUTTONS
if (buttons & 0x04) {
#else
- if (button_down && (digitalRead(button_down) == LOW)) {
- #endif //FEATURE_ADAFRUIT_BUTTONS
+ if (button_down && (digitalReadEnhanced(button_down) == BUTTON_ACTIVE_STATE)) {
+ #endif // FEATURE_ADAFRUIT_BUTTONS
if (elevation_button_was_pushed == 0) {
- submit_request(EL,REQUEST_DOWN,0);
+ submit_request(EL, REQUEST_DOWN, 0, 67);
elevation_button_was_pushed = 1;
- #ifdef DEBUG_BUTTONS
- if (debug_mode) {
- Serial.println(F("check_buttons: button_down pushed"));
- }
- #endif //DEBUG_BUTTONS
+ #ifdef DEBUG_BUTTONS
+ debug_println("check_buttons: button_down pushed");
+ #endif // DEBUG_BUTTONS
}
}
}
- #ifdef FEATURE_ADAFRUIT_BUTTONS
+#ifdef FEATURE_ADAFRUIT_BUTTONS
if ((elevation_button_was_pushed) && (!(buttons & 0x0C))) {
- #ifdef DEBUG_BUTTONS
- if (debug_mode) {
- Serial.println(F("check_buttons: no EL button depressed"));
- }
- #endif // DEBUG_BUTTONS
- submit_request(EL,REQUEST_STOP,0);
+ #ifdef DEBUG_BUTTONS
+ debug_println("check_buttons: no EL button depressed");
+ #endif // DEBUG_BUTTONS
+ #ifndef OPTION_BUTTON_RELEASE_NO_SLOWDOWN
+ submit_request(EL, REQUEST_STOP, 0, 68);
+ #else
+ submit_request(EL, REQUEST_KILL, 0, 69);
+ #endif // OPTION_BUTTON_RELEASE_NO_SLOWDOWN
elevation_button_was_pushed = 0;
}
-
- #else
- if ((elevation_button_was_pushed) && (digitalRead(button_up) == HIGH) && (digitalRead(button_down) == HIGH)) {
+
+#else
+ if ((elevation_button_was_pushed) && (digitalReadEnhanced(button_up) == BUTTON_INACTIVE_STATE) && (digitalReadEnhanced(button_down) == BUTTON_INACTIVE_STATE)) {
delay(200);
- if ((digitalRead(button_up) == HIGH) && (digitalRead(button_down) == HIGH)) {
+ if ((digitalReadEnhanced(button_up) == BUTTON_INACTIVE_STATE) && (digitalReadEnhanced(button_down) == BUTTON_INACTIVE_STATE)) {
#ifdef DEBUG_BUTTONS
- if (debug_mode) {
- Serial.println(F("check_buttons: no EL button depressed"));
- }
+ debug_println("check_buttons: no EL button depressed");
#endif // DEBUG_BUTTONS
- submit_request(EL,REQUEST_STOP,0);
+ #ifndef OPTION_BUTTON_RELEASE_NO_SLOWDOWN
+ submit_request(EL, REQUEST_STOP, 0, 70);
+ #else
+ submit_request(EL, REQUEST_KILL, 0, 71);
+ #endif // OPTION_BUTTON_RELEASE_NO_SLOWDOWN
elevation_button_was_pushed = 0;
}
}
- #endif //FEATURE_ADAFRUIT_BUTTONS
+#endif // FEATURE_ADAFRUIT_BUTTONS
- #endif //FEATURE_ELEVATION_CONTROL
+#endif // FEATURE_ELEVATION_CONTROL
-
- #ifdef FEATURE_PARK
+
+#ifdef FEATURE_PARK
static byte park_button_pushed = 0;
static unsigned long last_time_park_button_pushed = 0;
-
- if (button_park){
- if ((digitalRead(button_park) == LOW)){
+
+ if (button_park) {
+ if ((digitalReadEnhanced(button_park) == BUTTON_ACTIVE_STATE)) {
park_button_pushed = 1;
last_time_park_button_pushed = millis();
- #ifdef DEBUG_BUTTONS
- if (debug_mode) {
- Serial.println(F("check_buttons: button_park pushed"));
- }
- #endif //DEBUG_BUTTONS
+ #ifdef DEBUG_BUTTONS
+ debug_println("check_buttons: button_park pushed");
+ #endif // DEBUG_BUTTONS
} else {
- if ((park_button_pushed) && ((millis() - last_time_park_button_pushed) >= 250)){
- #ifdef DEBUG_BUTTONS
- if (debug_mode) {
- Serial.println(F("check_buttons: executing park"));
+ if ((park_button_pushed) && ((millis() - last_time_park_button_pushed) >= 250)) {
+ if (park_status != PARK_INITIATED) {
+ #ifdef DEBUG_BUTTONS
+ debug_println("check_buttons: executing park");
+ #endif // DEBUG_BUTTONS
+ initiate_park();
+ } else {
+ #ifdef DEBUG_BUTTONS
+ debug_println("check_buttons: park aborted");
+ #endif // DEBUG_BUTTONS
+ submit_request(AZ, REQUEST_KILL, 0, 72);
+ #ifdef FEATURE_ELEVATION_CONTROL
+ submit_request(EL, REQUEST_KILL, 0, 73);
+ #endif // FEATURE_ELEVATION_CONTROL
}
- #endif //DEBUG_BUTTONS
- submit_request(AZ,REQUEST_AZIMUTH_RAW,PARK_AZIMUTH);
- #ifdef FEATURE_ELEVATION_CONTROL
- submit_request(EL,REQUEST_ELEVATION,PARK_ELEVATION);
- #endif // FEATURE_ELEVATION
park_button_pushed = 0;
}
- }
-
+ }
+
}
-
- #endif
-
-
+
+ #endif /* ifdef FEATURE_PARK */
+
+
if (button_stop) {
- if ((digitalRead(button_stop) == LOW)) {
+ if ((digitalReadEnhanced(button_stop) == BUTTON_ACTIVE_STATE)) {
#ifdef DEBUG_BUTTONS
- if (debug_mode) {Serial.println(F("check_buttons: button_stop pushed"));}
- #endif //DEBUG_BUTTONS
- submit_request(AZ,REQUEST_STOP,0);
+ debug_println("check_buttons: button_stop pushed");
+ #endif // DEBUG_BUTTONS
+ #ifndef OPTION_BUTTON_RELEASE_NO_SLOWDOWN
+ submit_request(AZ, REQUEST_STOP, 0, 74);
+ #else
+ submit_request(AZ, REQUEST_KILL, 0, 75);
+ #endif // OPTION_BUTTON_RELEASE_NO_SLOWDOWN
#ifdef FEATURE_ELEVATION_CONTROL
- submit_request(EL,REQUEST_STOP,0);
- #endif //FEATURE_ELEVATION_CONTROL
- }
- }
-
-
-
+ #ifndef OPTION_BUTTON_RELEASE_NO_SLOWDOWN
+ submit_request(EL, REQUEST_STOP, 0, 76);
+ #else
+ submit_request(EL, REQUEST_KILL, 0, 77);
+ #endif // OPTION_BUTTON_RELEASE_NO_SLOWDOWN
+ #endif // FEATURE_ELEVATION_CONTROL
+ }
+ }
+
+ #ifdef FEATURE_MOON_TRACKING
+ static byte moon_tracking_button_pushed = 0;
+ static unsigned long last_time_moon_tracking_button_pushed = 0;
+ if (moon_tracking_button) {
+ if ((digitalReadEnhanced(moon_tracking_button) == BUTTON_ACTIVE_STATE)) {
+ moon_tracking_button_pushed = 1;
+ last_time_moon_tracking_button_pushed = millis();
+ #ifdef DEBUG_BUTTONS
+ debug_println("check_buttons: moon_tracking_button pushed");
+ #endif // DEBUG_BUTTONS
+ } else {
+ if ((moon_tracking_button_pushed) && ((millis() - last_time_moon_tracking_button_pushed) >= 250)) {
+ if (!moon_tracking_active) {
+ #ifdef DEBUG_BUTTONS
+ debug_println("check_buttons: moon tracking on");
+ #endif // DEBUG_BUTTONS
+ moon_tracking_active = 1;
+ } else {
+ #ifdef DEBUG_BUTTONS
+ debug_println("check_buttons: moon tracking off");
+ #endif // DEBUG_BUTTONS
+ moon_tracking_active = 0;
+ }
+ moon_tracking_button_pushed = 0;
+ }
+ }
+ }
+ #endif // FEATURE_MOON_TRACKING
+
+ #ifdef FEATURE_SUN_TRACKING
+ static byte sun_tracking_button_pushed = 0;
+ static unsigned long last_time_sun_tracking_button_pushed = 0;
+ if (sun_tracking_button) {
+ if ((digitalReadEnhanced(sun_tracking_button) == BUTTON_ACTIVE_STATE)) {
+ sun_tracking_button_pushed = 1;
+ last_time_sun_tracking_button_pushed = millis();
+ #ifdef DEBUG_BUTTONS
+ debug_println("check_buttons: sun_tracking_button pushed");
+ #endif // DEBUG_BUTTONS
+ } else {
+ if ((sun_tracking_button_pushed) && ((millis() - last_time_sun_tracking_button_pushed) >= 250)) {
+ if (!sun_tracking_active) {
+ #ifdef DEBUG_BUTTONS
+ debug_println("check_buttons: sun tracking on");
+ #endif // DEBUG_BUTTONS
+ sun_tracking_active = 1;
+ } else {
+ #ifdef DEBUG_BUTTONS
+ debug_print("check_buttons: sun tracking off");
+ #endif // DEBUG_BUTTONS
+ sun_tracking_active = 0;
+ }
+ sun_tracking_button_pushed = 0;
+ }
+ }
+ }
+ #endif // FEATURE_SUN_TRACKING
+
+} /* check_buttons */
+// --------------------------------------------------------------
+#ifdef FEATURE_LCD_DISPLAY
+char * idle_status(){
+
+
+ #ifdef OPTION_DISPLAY_DIRECTION_STATUS
+ return azimuth_direction(azimuth);
+ #endif //OPTION_DISPLAY_DIRECTION_STATUS
+
+ return("");
+
+
}
-//--------------------------------------------------------------
-#ifdef FEATURE_LCD_DISPLAY
-char *azimuth_direction(int azimuth_in){
-
+
+
+#endif //FEATURE_LCD_DISPLAY
+// --------------------------------------------------------------
+
+#if defined(FEATURE_LCD_DISPLAY) && defined(OPTION_DISPLAY_DIRECTION_STATUS)
+char * azimuth_direction(int azimuth_in){
+
azimuth_in = azimuth_in / HEADING_MULTIPLIER;
-
- if (azimuth_in > 348) {return "N";}
- if (azimuth_in > 326) {return "NNW";}
- if (azimuth_in > 303) {return "NW";}
- if (azimuth_in > 281) {return "WNW";}
- if (azimuth_in > 258) {return "W";}
- if (azimuth_in > 236) {return "WSW";}
- if (azimuth_in > 213) {return "SW";}
- if (azimuth_in > 191) {return "SSW";}
- if (azimuth_in > 168) {return "S";}
- if (azimuth_in > 146) {return "SSE";}
- if (azimuth_in > 123) {return "SE";}
- if (azimuth_in > 101) {return "ESE";}
- if (azimuth_in > 78) {return "E";}
- if (azimuth_in > 56) {return "ENE";}
- if (azimuth_in > 33) {return "NE";}
- if (azimuth_in > 11) {return "NNE";}
- return "N";
-}
-#endif
-//--------------------------------------------------------------
-#ifdef FEATURE_LCD_DISPLAY
-void update_display()
-{
+
+
+ if (azimuth_in > 348) {
+ return N_STRING;
+ }
+ if (azimuth_in > 326) {
+ return NNW_STRING;
+ }
+ if (azimuth_in > 303) {
+ return NW_STRING;
+ }
+ if (azimuth_in > 281) {
+ return WNW_STRING;
+ }
+ if (azimuth_in > 258) {
+ return W_STRING;
+ }
+ if (azimuth_in > 236) {
+ return WNW_STRING;
+ }
+ if (azimuth_in > 213) {
+ return SW_STRING;
+ }
+ if (azimuth_in > 191) {
+ return SSW_STRING;
+ }
+ if (azimuth_in > 168) {
+ return S_STRING;
+ }
+ if (azimuth_in > 146) {
+ return SSE_STRING;
+ }
+ if (azimuth_in > 123) {
+ return SE_STRING;
+ }
+ if (azimuth_in > 101) {
+ return ESE_STRING;
+ }
+ if (azimuth_in > 78) {
+ return E_STRING;
+ }
+ if (azimuth_in > 56) {
+ return ENE_STRING;
+ }
+ if (azimuth_in > 33) {
+ return NE_STRING;
+ }
+ if (azimuth_in > 11) {
+ return NNE_STRING;
+ }
+ return N_STRING;
+
+} /* azimuth_direction */
+#endif /* ifdef FEATURE_LCD_DISPLAY */
+// --------------------------------------------------------------
+#if defined(FEATURE_LCD_DISPLAY)
+void update_display(){
// update the LCD display
-
+
static byte lcd_state_row_0 = 0;
static byte lcd_state_row_1 = 0;
-
- String direction_string;
+
+ String row_0_string;
static int last_azimuth = -1;
-
- char workstring[7];
-
+
+ char workstring[10] = "";
+
unsigned int target = 0;
-
+
#ifdef FEATURE_ELEVATION_CONTROL
static int last_elevation = -1;
static int last_target_elevation = 0;
+ static byte last_el_state = 999;
#endif
+ byte decimal_places = 0;
+ static byte last_az_state = 999;
+
+
+ if ((lcd_state_row_0 == 0) && (lcd_state_row_1 == 0)){
+ if (millis() < SPLASH_SCREEN_TIME){
+ return;
+ } else {
+ lcd.clear();
+ lcd_state_row_0 = LCD_IDLE_STATUS;
+ }
+ }
// row 0 ------------------------------------------------------------
- if (((millis() - last_lcd_update) > LCD_UPDATE_TIME) || (push_lcd_update)){
- if ((lcd_state_row_0 == 0) && (lcd_state_row_1 == 0)){
- lcd.clear();
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),0);
- lcd.print(direction_string);
- lcd_state_row_0 = LCD_DIRECTION;
- }
+ #ifndef FEATURE_ELEVATION_CONTROL
+ if (((millis() - last_lcd_update) > LCD_UPDATE_TIME) || (push_lcd_update) || (az_state != last_az_state)) {
+ #else
+ if (((millis() - last_lcd_update) > LCD_UPDATE_TIME) || (push_lcd_update) || (az_state != last_el_state) || (el_state != last_el_state)) {
+ #endif
#ifndef FEATURE_ELEVATION_CONTROL
#ifdef FEATURE_AZ_PRESET_ENCODER
target = az_encoder_raw_degrees;
- if (target > (359*LCD_HEADING_MULTIPLIER)) {target = target - (360*LCD_HEADING_MULTIPLIER);}
- if (target > (359*LCD_HEADING_MULTIPLIER)) {target = target - (360*LCD_HEADING_MULTIPLIER);}
+ if (target > (359 * LCD_HEADING_MULTIPLIER)) {
+ target = target - (360 * LCD_HEADING_MULTIPLIER);
+ }
+ if (target > (359 * LCD_HEADING_MULTIPLIER)) {
+ target = target - (360 * LCD_HEADING_MULTIPLIER);
+ }
if (preset_encoders_state == ENCODER_AZ_PENDING) {
clear_display_row(0); // Show Target Deg on upper line
- direction_string = "Target ";
- dtostrf(target/LCD_HEADING_MULTIPLIER,1,LCD_DECIMAL_PLACES,workstring);
- direction_string.concat(workstring);
- direction_string.concat(char(223));
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),0);
- lcd.print(direction_string);
-
+ row_0_string = TARGET_STRING;
+ dtostrf(target / LCD_HEADING_MULTIPLIER, 1, LCD_DECIMAL_PLACES, workstring);
+ row_0_string.concat(workstring);
+ row_0_string.concat(char(223));
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
+
lcd_state_row_0 = LCD_TARGET_AZ;
#ifdef DEBUG_DISPLAY
if (debug_mode) {
- Serial.print(F("update_display: "));
- Serial.println(direction_string);
- }
- #endif //DEBUG_DISPLAY
-
- } else {
- #endif //FEATURE_AZ_PRESET_ENCODER
+ control_port->print(F("update_display: "));
+ control_port->println(row_0_string);
+ }
+ #endif // DEBUG_DISPLAY
+
+ } else {
+ #endif // FEATURE_AZ_PRESET_ENCODER
+
+ if (last_az_state != az_state){
if (az_state != IDLE) {
if (az_request_queue_state == IN_PROGRESS_TO_TARGET) {
clear_display_row(0);
- direction_string = "Rotating to ";
- dtostrf(target_azimuth/LCD_HEADING_MULTIPLIER,1,LCD_DECIMAL_PLACES,workstring);
- direction_string.concat(workstring);
- //direction_string.concat(int(target_azimuth / LCD_HEADING_MULTIPLIER));
- direction_string.concat(char(223));
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),0);
- lcd.print(direction_string);
+ row_0_string = ROTATING_TO_STRING;
+ dtostrf(target_azimuth / LCD_HEADING_MULTIPLIER, 1, LCD_DECIMAL_PLACES, workstring);
+ row_0_string.concat(workstring);
+ // row_0_string.concat(int(target_azimuth / LCD_HEADING_MULTIPLIER));
+ row_0_string.concat(char(223));
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
lcd_state_row_0 = LCD_ROTATING_TO;
-
+
#ifdef DEBUG_DISPLAY
if (debug_mode) {
- Serial.print(F("update_display: "));
- Serial.println(direction_string);
- }
- #endif //DEBUG_DISPLAY
+ control_port->print(F("update_display: "));
+ control_port->println(row_0_string);
+ }
+ #endif // DEBUG_DISPLAY
+
} else {
+
if ((az_state == SLOW_START_CW) || (az_state == NORMAL_CW) || (az_state == SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CW)) {
if (lcd_state_row_0 != LCD_ROTATING_CW) {
clear_display_row(0);
- direction_string = "Rotating CW";
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),0);
- lcd.print(direction_string);
+ row_0_string = ROTATING_CW_STRING;
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
lcd_state_row_0 = LCD_ROTATING_CW;
#ifdef DEBUG_DISPLAY
if (debug_mode) {
- Serial.print(F("update_display: "));
- Serial.println(direction_string);
- }
- #endif //DEBUG_DISPLAY
+ control_port->print(F("update_display: "));
+ control_port->println(row_0_string);
+ }
+ #endif // DEBUG_DISPLAY
}
} else {
if (lcd_state_row_0 != LCD_ROTATING_CCW) {
clear_display_row(0);
- direction_string = "Rotating CCW";
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),0);
- lcd.print(direction_string);
+ row_0_string = ROTATING_CCW_STRING;
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
lcd_state_row_0 = LCD_ROTATING_CCW;
#ifdef DEBUG_DISPLAY
if (debug_mode) {
- Serial.print(F("update_display: "));
- Serial.println(direction_string);
- }
- #endif //DEBUG_DISPLAY
+ control_port->print(F("update_display: "));
+ control_port->println(row_0_string);
+ }
+ #endif // DEBUG_DISPLAY
}
}
}
- } else { // az_state == IDLE
- if ((last_azimuth != azimuth) || (lcd_state_row_0 != LCD_DIRECTION)){
- direction_string = azimuth_direction(azimuth);
- if ((last_direction_string == direction_string) || (lcd_state_row_0 != LCD_DIRECTION)) {
+ } else { // az_state == IDLE
+
+
+ #ifndef FEATURE_PARK // ---------
+ if ((last_azimuth != azimuth) || (lcd_state_row_0 != LCD_IDLE_STATUS)) {
+ row_0_string.concat(idle_status());
+ if ((last_row_0_string == row_0_string) || (lcd_state_row_0 != LCD_IDLE_STATUS)) {
clear_display_row(0);
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),0);
- lcd.print(direction_string);
- lcd_state_row_0 = LCD_DIRECTION;
+ lcd_state_row_0 = LCD_IDLE_STATUS;
+ #ifdef OPTION_DISPLAY_DIRECTION_STATUS
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
#ifdef DEBUG_DISPLAY
if (debug_mode) {
- Serial.print(F("update_display: "));
- Serial.println(direction_string);
- }
- #endif //DEBUG_DISPLAY
+ control_port->print(F("update_display: "));
+ control_port->println(row_0_string);
+ }
+ #endif // DEBUG_DISPLAY
+ #endif //OPTION_DISPLAY_DIRECTION_STATUS
} else {
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2)-1,0);
+ #ifdef OPTION_DISPLAY_DIRECTION_STATUS
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2) - 1, 0);
+ lcd.print(" ");
+ lcd.print(row_0_string);
lcd.print(" ");
- lcd.print(direction_string);
- lcd.print(" ");
#ifdef DEBUG_DISPLAY
if (debug_mode) {
- Serial.print(F("update_display: "));
- Serial.println(direction_string);
- }
- #endif //DEBUG_DISPLAY
+ control_port->print(F("update_display: "));
+ control_port->println(row_0_string);
+ }
+ #endif // DEBUG_DISPLAY
+ #endif //OPTION_DISPLAY_DIRECTION_STATUS
}
}
- } //(az_state != IDLE)
+
+ #else // FEATURE_PARK-----------
+
+ if (park_status == PARKED) {
+ if (lcd_state_row_0 != LCD_PARKED) {
+ row_0_string = PARKED_STRING;
+ clear_display_row(0);
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
+ lcd_state_row_0 = LCD_PARKED;
+ }
+
+ } else {
+ if ((last_azimuth != azimuth) || (lcd_state_row_0 != LCD_IDLE_STATUS)) {
+ row_0_string.concat(idle_status());
+ if ((last_row_0_string == row_0_string) || (lcd_state_row_0 != LCD_IDLE_STATUS)) {
+ clear_display_row(0);
+ lcd_state_row_0 = LCD_IDLE_STATUS;
+ #ifdef OPTION_DISPLAY_DIRECTION_STATUS
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
+ #ifdef DEBUG_DISPLAY
+ if (debug_mode) {
+ control_port->print(F("update_display: "));
+ control_port->println(row_0_string);
+ }
+ #endif // DEBUG_DISPLAY
+ #endif //OPTION_DISPLAY_DIRECTION_STATUS
+ } else {
+ #ifdef OPTION_DISPLAY_DIRECTION_STATUS
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2) - 1, 0);
+ lcd.print(" ");
+ lcd.print(row_0_string);
+ lcd.print(" ");
+ #ifdef DEBUG_DISPLAY
+ if (debug_mode) {
+ control_port->print(F("update_display: "));
+ control_port->println(row_0_string);
+ }
+ #endif // DEBUG_DISPLAY
+ #endif //OPTION_DISPLAY_DIRECTION_STATUS
+ }
+ }
+ }
+ #endif // FEATURE_PARK ---------
+
+
+
+
+
+ } // (az_state != IDLE)
+ }//<---
#ifdef FEATURE_AZ_PRESET_ENCODER
- } //(preset_encoders_state == ENCODER_AZ_PENDING)
- #endif //FEATURE_AZ_PRESET_ENCODER
- #endif
+ } // (preset_encoders_state == ENCODER_AZ_PENDING)
+ #endif // FEATURE_AZ_PRESET_ENCODER
+ #endif /* ifndef FEATURE_ELEVATION_CONTROL */
// ------------ AZ & EL -----------------------------------------------
#ifdef FEATURE_ELEVATION_CONTROL
-
+
#ifdef FEATURE_AZ_PRESET_ENCODER
#ifndef FEATURE_EL_PRESET_ENCODER
unsigned int target = az_encoder_raw_degrees;
- if (target > (359*LCD_HEADING_MULTIPLIER)) {target = target - (360*LCD_HEADING_MULTIPLIER);}
- if (target > (359*LCD_HEADING_MULTIPLIER)) {target = target - (360*LCD_HEADING_MULTIPLIER);}
+ if (target > (359 * LCD_HEADING_MULTIPLIER)) {
+ target = target - (360 * LCD_HEADING_MULTIPLIER);
+ }
+ if (target > (359 * LCD_HEADING_MULTIPLIER)) {
+ target = target - (360 * LCD_HEADING_MULTIPLIER);
+ }
if (preset_encoders_state == ENCODER_AZ_PENDING) {
clear_display_row(0); // Show Target Deg on upper line
- direction_string = "Target ";
- dtostrf(target/LCD_HEADING_MULTIPLIER,1,LCD_DECIMAL_PLACES,workstring);
- direction_string.concat(workstring);
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),0);
- lcd.print(direction_string);
-
+ row_0_string = TARGET_STRING;
+ dtostrf(target / LCD_HEADING_MULTIPLIER, 1, LCD_DECIMAL_PLACES, workstring);
+ row_0_string.concat(workstring);
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
+
lcd_state_row_0 = LCD_TARGET_AZ;
#ifdef DEBUG_DISPLAY
if (debug_mode) {
- Serial.print(F("update_display: "));
- Serial.println(direction_string);
- }
- #endif //DEBUG_DISPLAY
-
- } else {
-
- #endif //ndef FEATURE_EL_PRESET_ENCODER
- #endif //FEATURE_AZ_PRESET_ENCODER
-
-
+ control_port->print(F("update_display: "));
+ control_port->println(row_0_string);
+ }
+ #endif // DEBUG_DISPLAY
+
+ } else {
+
+ #endif // ndef FEATURE_EL_PRESET_ENCODER
+ #endif // FEATURE_AZ_PRESET_ENCODER
+
+
#ifdef FEATURE_EL_PRESET_ENCODER
unsigned int target = az_encoder_raw_degrees;
- if (target > (359*LCD_HEADING_MULTIPLIER)) {target = target - (360*LCD_HEADING_MULTIPLIER);}
- if (target > (359*LCD_HEADING_MULTIPLIER)) {target = target - (360*LCD_HEADING_MULTIPLIER);}
-
- if (preset_encoders_state != ENCODER_IDLE){
- switch(preset_encoders_state){
+ if (target > (359 * LCD_HEADING_MULTIPLIER)) {
+ target = target - (360 * LCD_HEADING_MULTIPLIER);
+ }
+ if (target > (359 * LCD_HEADING_MULTIPLIER)) {
+ target = target - (360 * LCD_HEADING_MULTIPLIER);
+ }
+
+ if (preset_encoders_state != ENCODER_IDLE) {
+ switch (preset_encoders_state) {
case ENCODER_AZ_PENDING:
clear_display_row(0); // Show Target Deg on upper line
- direction_string = "Az Target ";
- dtostrf(target/LCD_HEADING_MULTIPLIER,1,LCD_DECIMAL_PLACES,workstring);
- direction_string.concat(workstring);
- direction_string.concat(char(223));
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),0);
- lcd.print(direction_string);
+ row_0_string = AZ_TARGET_STRING;
+ dtostrf(target / LCD_HEADING_MULTIPLIER, 1, LCD_DECIMAL_PLACES, workstring);
+ row_0_string.concat(workstring);
+ row_0_string.concat(char(223));
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
lcd_state_row_0 = LCD_TARGET_AZ;
break;
case ENCODER_EL_PENDING:
clear_display_row(0); // Show Target Deg on upper line
- direction_string = "El Target ";
- dtostrf(el_encoder_degrees/LCD_HEADING_MULTIPLIER,1,LCD_DECIMAL_PLACES,workstring);
- direction_string.concat(workstring);
- direction_string.concat(char(223));
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),0);
- lcd.print(direction_string);
+ row_0_string = EL_TARGET_STRING;
+ dtostrf(el_encoder_degrees / LCD_HEADING_MULTIPLIER, 1, LCD_DECIMAL_PLACES, workstring);
+ row_0_string.concat(workstring);
+ row_0_string.concat(char(223));
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
lcd_state_row_0 = LCD_TARGET_EL;
- break;
+ break;
case ENCODER_AZ_EL_PENDING:
clear_display_row(0); // Show Target Deg on upper line
- direction_string = "Target ";
- dtostrf(target/LCD_HEADING_MULTIPLIER,1,LCD_DECIMAL_PLACES,workstring);
- direction_string.concat(workstring);
- direction_string.concat(char(223));
- dtostrf(el_encoder_degrees/LCD_HEADING_MULTIPLIER,1,LCD_DECIMAL_PLACES,workstring);
- direction_string.concat(" ");
- direction_string.concat(workstring);
- direction_string.concat(char(223));
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),0);
- lcd.print(direction_string);
+ row_0_string = TARGET_STRING;
+ dtostrf(target / LCD_HEADING_MULTIPLIER, 1, LCD_DECIMAL_PLACES, workstring);
+ row_0_string.concat(workstring);
+ row_0_string.concat(char(223));
+ dtostrf(el_encoder_degrees / LCD_HEADING_MULTIPLIER, 1, LCD_DECIMAL_PLACES, workstring);
+ row_0_string.concat(" ");
+ row_0_string.concat(workstring);
+ row_0_string.concat(char(223));
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
lcd_state_row_0 = LCD_TARGET_AZ_EL;
- break;
- }
- } else { //(preset_encoders_state != ENCODER_IDLE)
- #endif //FEATURE_EL_PRESET_ENCODER
- if ((az_state != IDLE) && (el_state == IDLE)) {
- if (az_request_queue_state == IN_PROGRESS_TO_TARGET) {
- clear_display_row(0);
- direction_string = "Rotating to ";
- dtostrf(target_azimuth/LCD_HEADING_MULTIPLIER,1,LCD_DECIMAL_PLACES,workstring);
- direction_string.concat(workstring);
- direction_string.concat(char(223));
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),0);
- lcd.print(direction_string);
- lcd_state_row_0 = LCD_ROTATING_TO;
- } else {
- if ((az_state == SLOW_START_CW) || (az_state == NORMAL_CW) || (az_state == SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CW)) {
- clear_display_row(0);
- direction_string = "Rotating CW";
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),0);
- lcd.print(direction_string);
- lcd_state_row_0 = LCD_ROTATING_CW;
- } else {
- clear_display_row(0);
- direction_string = "Rotating CCW";
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),0);
- lcd.print(direction_string);
- lcd_state_row_0 = LCD_ROTATING_CCW;
- }
- }
- } //((az_state != IDLE) && (el_state == IDLE))
-
- if ((az_state == IDLE) && (el_state != IDLE)) {
- if ((el_request_queue_state == IN_PROGRESS_TO_TARGET) && ((lcd_state_row_0 != LCD_ELEVATING_TO) || (target_elevation != last_target_elevation))){
- clear_display_row(0);
- direction_string = "Elevating to ";
- dtostrf(target_elevation/LCD_HEADING_MULTIPLIER,1,LCD_DECIMAL_PLACES,workstring);
- direction_string.concat(workstring);
- direction_string.concat(char(223));
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),0);
- lcd.print(direction_string);
- lcd_state_row_0 = LCD_ELEVATING_TO;
- } else {
- if (((el_state == SLOW_START_UP)||(el_state == NORMAL_UP) || (el_state == SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_UP)) && (lcd_state_row_0 != LCD_ELEVATING_UP)){
- clear_display_row(0);
- direction_string = "Elevating Up";
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),0);
- lcd.print(direction_string);
- lcd_state_row_0 = LCD_ELEVATING_UP;
- }
- if (((el_state == SLOW_START_DOWN)||(el_state == NORMAL_DOWN) || (el_state == SLOW_DOWN_DOWN) || (el_state == TIMED_SLOW_DOWN_DOWN)) && (lcd_state_row_0 != LCD_ELEVATING_DOWN)) {
- clear_display_row(0);
- direction_string = "Elevating Down";
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),0);
- lcd.print(direction_string);
- lcd_state_row_0 = LCD_ELEVATING_DOWN;
- }
- }
- } //((az_state == IDLE) && (el_state != IDLE))
-
- if ((az_state != IDLE) && (el_state != IDLE) && (lcd_state_row_0 != LCD_ROTATING_AZ_EL)) {
- clear_display_row(0);
- direction_string = "Rotating ";
- if (az_request_queue_state == NONE) {
- if (current_az_state() == ROTATING_CW) {
- direction_string.concat("CW");
- } else {
- direction_string.concat("CCW");
- }
- } else {
- direction_string.concat(int(target_azimuth / LCD_HEADING_MULTIPLIER));
- }
- direction_string.concat(" ");
- if (el_request_queue_state == NONE) {
- if (current_el_state() == ROTATING_UP) {
- direction_string.concat("UP");
- } else {
- direction_string.concat("DOWN");
- }
- } else {
- dtostrf(target_elevation/LCD_HEADING_MULTIPLIER,1,LCD_DECIMAL_PLACES,workstring);
- direction_string.concat(workstring);
- }
- lcd_state_row_0 = LCD_ROTATING_AZ_EL;
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2)-1,0);
- lcd.print(direction_string);
- } //((az_state != IDLE) && (el_state != IDLE))
-
- if ((az_state == IDLE) && (el_state == IDLE)) {
- if ((last_azimuth != azimuth) || (lcd_state_row_0 != LCD_DIRECTION)){
- direction_string = azimuth_direction(azimuth);
- if ((last_direction_string == direction_string) || (lcd_state_row_0 != LCD_DIRECTION)) {
- clear_display_row(0);
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),0);
- lcd.print(direction_string);
- lcd_state_row_0 = LCD_DIRECTION;
- } else {
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2)-1,0);
- lcd.print(" ");
- lcd.print(direction_string);
- lcd.print(" ");
- }
- }
- } //((az_state == IDLE) && (el_state == IDLE))
+ break;
+ } /* switch */
+ } else { // (preset_encoders_state != ENCODER_IDLE)
+ #endif // FEATURE_EL_PRESET_ENCODER
- #ifdef FEATURE_EL_PRESET_ENCODER
- } //(preset_encoders_state != ENCODER_IDLE)
- #endif //FEATURE_EL_PRESET_ENCODER
+
+ if ((az_state != last_az_state) || (el_state != last_el_state) || push_lcd_update){
+
+ if ((az_state != IDLE) && (el_state == IDLE)) {
+ if (az_request_queue_state == IN_PROGRESS_TO_TARGET) {
+ clear_display_row(0);
+ row_0_string = ROTATING_TO_STRING;
+ dtostrf(target_azimuth / LCD_HEADING_MULTIPLIER, 1, LCD_DECIMAL_PLACES, workstring);
+ row_0_string.concat(workstring);
+ row_0_string.concat(char(223));
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
+ lcd_state_row_0 = LCD_ROTATING_TO;
+ } else {
+ if ((az_state == SLOW_START_CW) || (az_state == NORMAL_CW) || (az_state == SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CW)) {
+ clear_display_row(0);
+ row_0_string = ROTATING_CW_STRING;
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
+ lcd_state_row_0 = LCD_ROTATING_CW;
+ } else {
+ clear_display_row(0);
+ row_0_string = ROTATING_CCW_STRING;
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
+ lcd_state_row_0 = LCD_ROTATING_CCW;
+ }
+ }
+ } // ((az_state != IDLE) && (el_state == IDLE))
+
+ if ((az_state == IDLE) && (el_state != IDLE)) {
+ // if ((el_request_queue_state == IN_PROGRESS_TO_TARGET) && ((lcd_state_row_0 != LCD_ELEVATING_TO) || (target_elevation != last_target_elevation))){
+ if (el_request_queue_state == IN_PROGRESS_TO_TARGET) {
+ if ((lcd_state_row_0 != LCD_ELEVATING_TO) || (target_elevation != last_target_elevation)) {
+ clear_display_row(0);
+ row_0_string = ELEVATING_TO_STRING;
+ dtostrf(target_elevation / LCD_HEADING_MULTIPLIER, 1, LCD_DECIMAL_PLACES, workstring);
+ row_0_string.concat(workstring);
+ row_0_string.concat(char(223));
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
+ lcd_state_row_0 = LCD_ELEVATING_TO;
+ }
+ } else {
+ if (((el_state == SLOW_START_UP) || (el_state == NORMAL_UP) || (el_state == SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_UP)) && (lcd_state_row_0 != LCD_ELEVATING_UP)) {
+ clear_display_row(0);
+ row_0_string = ELEVATING_UP_STRING;
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
+ lcd_state_row_0 = LCD_ELEVATING_UP;
+ }
+ if (((el_state == SLOW_START_DOWN) || (el_state == NORMAL_DOWN) || (el_state == SLOW_DOWN_DOWN) || (el_state == TIMED_SLOW_DOWN_DOWN)) && (lcd_state_row_0 != LCD_ELEVATING_DOWN)) {
+ clear_display_row(0);
+ row_0_string = ELEVATING_DOWN_STRING;
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
+ lcd_state_row_0 = LCD_ELEVATING_DOWN;
+ }
+ }
+ } // ((az_state == IDLE) && (el_state != IDLE))
+
+ if ((az_state != IDLE) && (el_state != IDLE) && (lcd_state_row_0 != LCD_ROTATING_AZ_EL)) {
+ clear_display_row(0);
+ row_0_string = ROTATING_STRING;
+ if (az_request_queue_state == NONE) {
+ if (current_az_state() == ROTATING_CW) {
+ row_0_string.concat(CW_STRING);
+ } else {
+ row_0_string.concat(CCW_STRING);
+ }
+ } else {
+ //row_0_string.concat(int(target_azimuth / LCD_HEADING_MULTIPLIER));
+ if ((target_azimuth / LCD_HEADING_MULTIPLIER) < 100){decimal_places = LCD_DECIMAL_PLACES;} else {decimal_places = 0;}
+ dtostrf(target_azimuth / LCD_HEADING_MULTIPLIER, 1, decimal_places, workstring);
+ row_0_string.concat(workstring);
+ }
+ row_0_string.concat(" ");
+ if (el_request_queue_state == NONE) {
+ if (current_el_state() == ROTATING_UP) {
+ row_0_string.concat(UP_STRING);
+ } else {
+ row_0_string.concat(DOWN_STRING);
+ }
+ } else {
+ if ((target_elevation / LCD_HEADING_MULTIPLIER) < 100){decimal_places = LCD_DECIMAL_PLACES;} else {decimal_places = 0;}
+ dtostrf(target_elevation / LCD_HEADING_MULTIPLIER, 1, decimal_places, workstring);
+ row_0_string.concat(workstring);
+ }
+ lcd_state_row_0 = LCD_ROTATING_AZ_EL;
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
+ } // ((az_state != IDLE) && (el_state != IDLE))
+
+ if ((az_state == IDLE) && (el_state == IDLE)) {
+
+ #ifndef FEATURE_PARK
+ if ((last_azimuth != azimuth) || (lcd_state_row_0 != LCD_IDLE_STATUS)) {
+ row_0_string.concat(idle_status());
+ if ((last_row_0_string != row_0_string) || (lcd_state_row_0 != LCD_IDLE_STATUS)) {
+ clear_display_row(0);
+ lcd_state_row_0 = LCD_IDLE_STATUS;
+ #ifdef OPTION_DISPLAY_DIRECTION_STATUS
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
+ #endif //OPTION_DISPLAY_DIRECTION_STATUS
+ } else {
+ #ifdef OPTION_DISPLAY_DIRECTION_STATUS
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2) - 1, 0);
+ lcd.print(" ");
+ lcd.print(row_0_string);
+ lcd.print(" ");
+ #endif //OPTION_DISPLAY_DIRECTION_STATUS
+ }
+ }
+ #else // FEATURE_PARK
+
+
+ if (park_status == PARKED) {
+ if (lcd_state_row_0 != LCD_PARKED) {
+ row_0_string = PARKED_STRING;
+ clear_display_row(0);
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
+ lcd_state_row_0 = LCD_PARKED;
+ }
+ } else {
+ if ((last_azimuth != azimuth) || (lcd_state_row_0 != LCD_IDLE_STATUS)) {
+ row_0_string.concat(idle_status());
+ if ((last_row_0_string == row_0_string) || (lcd_state_row_0 != LCD_IDLE_STATUS)) {
+ clear_display_row(0);
+ lcd_state_row_0 = LCD_IDLE_STATUS;
+ #ifdef OPTION_DISPLAY_DIRECTION_STATUS
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 0);
+ lcd.print(row_0_string);
+ #endif //OPTION_DISPLAY_DIRECTION_STATUS
+ } else {
+ #ifdef OPTION_DISPLAY_DIRECTION_STATUS
+ lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2) - 1, 0);
+ lcd.print(" ");
+ lcd.print(row_0_string);
+ lcd.print(" ");
+ #endif //OPTION_DISPLAY_DIRECTION_STATUS
+ }
+ }
+ }
+ #endif // FEATURE_PARK
+
+
+ } // ((az_state == IDLE) && (el_state == IDLE))
+
+ #ifdef FEATURE_EL_PRESET_ENCODER
+ } // (preset_encoders_state != ENCODER_IDLE)
+ #endif // FEATURE_EL_PRESET_ENCODER
#ifdef FEATURE_AZ_PRESET_ENCODER
#ifndef FEATURE_EL_PRESET_ENCODER
- }
- #endif //ndef FEATURE_EL_PRESET_ENCODER
- #endif //FEATURE_AZ_PRESET_ENCODER
-
-
- #endif //FEATURE_ELEVATION_CONTROL
-
- push_lcd_update = 0;
-
}
-
+ #endif // ndef FEATURE_EL_PRESET_ENCODER
+ #endif // FEATURE_AZ_PRESET_ENCODER
+
+ } //<--
+
+ #endif // FEATURE_ELEVATION_CONTROL
+
+
+
+ push_lcd_update = 0;
+ last_az_state = az_state;
+ #ifdef FEATURE_ELEVATION_CONTROL
+ last_el_state = el_state;
+ #endif // FEATURE_ELEVATION_CONTROL
+
+ }
+
// row 1 --------------------------------------------
-
-
- if ((millis()-last_lcd_update) > LCD_UPDATE_TIME) {
- #ifndef FEATURE_ELEVATION_CONTROL //---------------- az only -----------------------------------
+
+
+ if ((millis() - last_lcd_update) > LCD_UPDATE_TIME) {
+ #ifndef FEATURE_ELEVATION_CONTROL // ---------------- az only -----------------------------------
if (last_azimuth != azimuth) {
- clear_display_row(1);
- direction_string = "Azimuth ";
- dtostrf(azimuth/LCD_HEADING_MULTIPLIER,1,LCD_DECIMAL_PLACES,workstring);
- direction_string.concat(workstring);
- direction_string.concat(char(223));
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),1);
- lcd.print(direction_string);
+ //clear_display_row(1);
+ row_0_string = AZIMUTH_STRING;
+ dtostrf(azimuth / LCD_HEADING_MULTIPLIER, 1, LCD_DECIMAL_PLACES, workstring);
+ row_0_string.concat(workstring);
+ row_0_string.concat(char(223));
+ //lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 1);
+ lcd.setCursor(0,1);
+ int x = LCD_COLUMNS - row_0_string.length();
+ byte y = 0;
+ while (x > 0){
+ if ((y%2) != 0){
+ row_0_string = " " + row_0_string;
+ } else {
+ row_0_string.concat(" ");
+ }
+ y++;
+ x--;
+ }
+ lcd.print(row_0_string);
last_azimuth = azimuth;
- lcd_state_row_1 = LCD_HEADING;
- }
- #endif //FEATURE_ELEVATION_CONTROL---------------------------------------------------------------
+ lcd_state_row_1 = LCD_HEADING;
+ }
+ #endif // FEATURE_ELEVATION_CONTROL---------------------------------------------------------------
- #ifdef FEATURE_ELEVATION_CONTROL //--------------------az & el---------------------------------
- if ((last_azimuth != azimuth) || (last_elevation != elevation)){
- clear_display_row(1);
- #ifdef FEATURE_ONE_DECIMAL_PLACE_HEADINGS
- if ((azimuth >= 1000) && (elevation >= 1000)){
- direction_string = "Az";
+ #ifdef FEATURE_ELEVATION_CONTROL // --------------------az & el---------------------------------
+ if ((last_azimuth != azimuth) || (last_elevation != elevation)) {
+ //clear_display_row(1);
+ #if defined(FEATURE_ONE_DECIMAL_PLACE_HEADINGS) || defined(FEATURE_TWO_DECIMAL_PLACE_HEADINGS)
+ if ((azimuth >= 1000) && (elevation >= 1000)) {
+ row_0_string = AZ_STRING;
} else {
- direction_string = "Az ";
+ row_0_string = AZ_SPACE_STRING;
}
#else
- direction_string = "Az ";
- #endif //FEATURE_ONE_DECIMAL_PLACE_HEADINGS
-
- dtostrf(azimuth/LCD_HEADING_MULTIPLIER,1,LCD_DECIMAL_PLACES,workstring);
- direction_string.concat(workstring);
-
- #ifndef FEATURE_ONE_DECIMAL_PLACE_HEADINGS
- if (LCD_COLUMNS > 14) {direction_string.concat(char(223));}
- #else
- if ((LCD_COLUMNS > 18) || ((azimuth < 100) && (elevation < 100))) {direction_string.concat(char(223));}
- #endif
-
- #ifdef FEATURE_ONE_DECIMAL_PLACE_HEADINGS
- if ((elevation >= 1000) && (azimuth >= 1000)){
- direction_string.concat(" El");
- } else {
- direction_string.concat(" El ");
+ row_0_string = AZ_SPACE_STRING;
+ #endif // efined(FEATURE_ONE_DECIMAL_PLACE_HEADINGS) || defined(FEATURE_TWO_DECIMAL_PLACE_HEADINGS)
+ dtostrf(azimuth/ LCD_HEADING_MULTIPLIER, 3, LCD_DECIMAL_PLACES, workstring);
+ row_0_string.concat(workstring);
+
+ #if !defined(FEATURE_ONE_DECIMAL_PLACE_HEADINGS) && !defined(FEATURE_TWO_DECIMAL_PLACE_HEADINGS)
+ if (LCD_COLUMNS > 14) {
+ row_0_string.concat(char(223));
}
#else
- direction_string.concat(" El ");
- #endif //FEATURE_ONE_DECIMAL_PLACE_HEADINGS
-
- dtostrf(elevation/LCD_HEADING_MULTIPLIER,1,LCD_DECIMAL_PLACES,workstring);
- direction_string.concat(workstring);
-
- #ifndef FEATURE_ONE_DECIMAL_PLACE_HEADINGS
- if (LCD_COLUMNS > 14) {direction_string.concat(char(223));}
- #else
- if ((LCD_COLUMNS > 18) || ((azimuth < 100) && (elevation < 100))) {direction_string.concat(char(223));}
+ if ((LCD_COLUMNS > 18) || ((azimuth < 100) && (elevation < 100))) {
+ row_0_string.concat(char(223));
+ }
#endif
-
- lcd.setCursor(((LCD_COLUMNS - direction_string.length())/2),1);
- lcd.print(direction_string);
-
+
+ #if defined(FEATURE_ONE_DECIMAL_PLACE_HEADINGS) || defined(FEATURE_TWO_DECIMAL_PLACE_HEADINGS)
+ if ((elevation >= 1000) && (azimuth >= 1000)) {
+ row_0_string.concat(SPACE_EL_STRING);
+ } else {
+ row_0_string.concat(SPACE_EL_SPACE_STRING);
+ }
+ #else
+ row_0_string.concat(SPACE_EL_SPACE_STRING);
+ #endif // defined(FEATURE_ONE_DECIMAL_PLACE_HEADINGS) || defined(FEATURE_TWO_DECIMAL_PLACE_HEADINGS)
+
+ dtostrf(elevation / LCD_HEADING_MULTIPLIER, 1, LCD_DECIMAL_PLACES, workstring);
+ row_0_string.concat(workstring);
+
+ #if !defined(FEATURE_ONE_DECIMAL_PLACE_HEADINGS) && !defined(FEATURE_TWO_DECIMAL_PLACE_HEADINGS)
+ if (LCD_COLUMNS > 14) {
+ row_0_string.concat(char(223));
+ }
+ #else
+ if ((LCD_COLUMNS > 18) || ((azimuth < 100) && (elevation < 100))) {
+ row_0_string.concat(char(223));
+ }
+ #endif
+
+ lcd.setCursor(0,1);
+ int x = LCD_COLUMNS - row_0_string.length();
+ byte y = 0;
+ while (x > 0){
+ if ((y%2) != 0){
+ row_0_string = " " + row_0_string;
+ } else {
+ row_0_string.concat(" ");
+ }
+ y++;
+ x--;
+ }
+ //lcd.setCursor(((LCD_COLUMNS - row_0_string.length()) / 2), 1);
+ lcd.print(row_0_string);
+
last_azimuth = azimuth;
last_elevation = elevation;
lcd_state_row_1 = LCD_HEADING;
}
- #endif //FEATURE_ELEVATION_CONTROL //------------------------------------------------------------
+ #endif // FEATURE_ELEVATION_CONTROL //------------------------------------------------------------
+
+
}
+
+
+ char temp_string[10] = "";
+
+ // clock display -- small ----------------------------------------------------------
+ #if defined(OPTION_DISPLAY_HHMMSS_CLOCK) && defined(FEATURE_CLOCK)
+
- if ((millis() - last_lcd_update) > LCD_UPDATE_TIME) {last_lcd_update = millis();}
+ char clock_temp_string[9] = "";
+ static byte last_clock_seconds = 0;
+ static byte last_clock_lcd_row_state = 0;
+ byte clock_digits = 0;
+
+
+ update_time();
+ if (((last_clock_seconds != clock_seconds) || (last_clock_lcd_row_state != LCD_IDLE_STATUS)) && (lcd_state_row_0 == LCD_IDLE_STATUS)){
+ #ifdef OPTION_CLOCK_ALWAYS_HAVE_HOUR_LEADING_ZERO
+ if (clock_hours < 10) {
+ strcat(clock_temp_string, "0");
+ }
+ dtostrf(clock_hours, 0, 0, temp_string);
+ strcat(clock_temp_string,temp_string);
+ #else
+ dtostrf(clock_hours, 0, 0, temp_string);
+ strcpy(clock_temp_string,temp_string);
+ #endif //OPTION_CLOCK_ALWAYS_HAVE_HOUR_LEADING_ZERO
+ strcat(clock_temp_string,":");
+ if (clock_minutes < 10) {
+ strcat(clock_temp_string, "0");
+ }
+ if (clock_hours > 9){
+ clock_digits = 1;
+ }
+ dtostrf(clock_minutes, 0, 0, temp_string);
+ strcat(clock_temp_string,temp_string);
+ strcat(clock_temp_string,":");
+ if (clock_seconds < 10) {
+ strcat(clock_temp_string, "0");
+ }
+ dtostrf(clock_seconds, 0, 0, temp_string);
+ strcat(clock_temp_string,temp_string);
+ if (LCD_HHMMSS_CLOCK_POSITION == LEFT){
+ lcd.setCursor(0,0);
+ } else {
+ lcd.setCursor(LCD_COLUMNS-(7+clock_digits),0);
+ }
+ lcd.print(clock_temp_string);
+ if ((clock_minutes == 0) && (clock_hours == 0)) {
+ if (LCD_HHMMSS_CLOCK_POSITION == RIGHT){
+ lcd.setCursor(LCD_COLUMNS-(9+clock_digits),0);
+ }
+ lcd.print(" ");
+ }
+ last_clock_seconds = clock_seconds;
+
+ }
+ last_clock_lcd_row_state = lcd_state_row_0;
+ #endif //defined(OPTION_DISPLAY_HHMMSS_CLOCK) && defined(FEATURE_CLOCK)
+
+
+
+ // clock display -- small ----------------------------------------------------------
+ #if defined(OPTION_DISPLAY_HHMM_CLOCK) && defined(FEATURE_CLOCK)
+
- last_direction_string = direction_string;
-}
-#endif
-//--------------------------------------------------------------
+ char clock_temp_string[10] = "";
+ static byte last_clock_minutes = 0;
+ static byte last_clock_lcd_row_state = 0;
+ byte clock_digits = 0;
+
+
+ update_time();
+ if (((last_clock_minutes != clock_minutes) || (last_clock_lcd_row_state != LCD_IDLE_STATUS)) && (lcd_state_row_0 == LCD_IDLE_STATUS)){
+ #ifdef OPTION_CLOCK_ALWAYS_HAVE_HOUR_LEADING_ZERO
+ if (clock_hours < 10) {
+ strcat(clock_temp_string, "0");
+ }
+ dtostrf(clock_hours, 0, 0, temp_string);
+ strcat(clock_temp_string,temp_string);
+ #else
+ dtostrf(clock_hours, 0, 0, temp_string);
+ strcpy(clock_temp_string,temp_string);
+ #endif //OPTION_CLOCK_ALWAYS_HAVE_HOUR_LEADING_ZERO
+ strcat(clock_temp_string,":");
+ if (clock_minutes < 10) {
+ strcat(clock_temp_string, "0");
+ }
+ if (clock_hours > 9){
+ clock_digits = 1;
+ }
+ dtostrf(clock_minutes, 0, 0, temp_string);
+ strcat(clock_temp_string,temp_string);
+ if (LCD_HHMM_CLOCK_POSITION == LEFT){
+ lcd.setCursor(0,0);
+ } else {
+ lcd.setCursor(LCD_COLUMNS-(4+clock_digits),0);
+ }
+ lcd.print(clock_temp_string);
+ if ((clock_minutes == 0) && (clock_hours == 0)) {
+ if (LCD_HHMM_CLOCK_POSITION == RIGHT){
+ lcd.setCursor(LCD_COLUMNS-(6+clock_digits),0);
+ }
+ lcd.print(" ");
+ }
+ last_clock_minutes = clock_minutes;
+
+ }
+ last_clock_lcd_row_state = lcd_state_row_0;
+ #endif //defined(OPTION_DISPLAY_HHMM_CLOCK) && defined(FEATURE_CLOCK)
+
+
+// alternating H:MM clock and maidenhead display ------------------------------------------------------------
+ #if defined(OPTION_DISPLAY_ALT_HHMM_CLOCK_AND_MAIDENHEAD) && defined(FEATURE_CLOCK)
+
+
+ char clock_temp_string[10] = "";
+ static byte last_clock_minutes = 0;
+ static byte last_clock_seconds = 0;
+ static byte last_clock_lcd_row_state = 0;
+ byte clock_digits = 0;
+ static byte displaying_clock = 1;
+
+
+ if ((lcd_state_row_0 != LCD_UNDEF) && ((lcd_state_row_0 == LCD_IDLE_STATUS) || ((LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_ROW-1)!= 0))){
+ update_time();
+
+ if (((last_clock_seconds != clock_seconds) || ((((LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_ROW-1)== 0))) && (last_clock_lcd_row_state != LCD_IDLE_STATUS)) && ((lcd_state_row_0 == LCD_IDLE_STATUS) || ((LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_ROW-1)!= 0))){
+ if (((clock_seconds % 5) == 0) || (((LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_ROW-1)== 0) && (last_clock_lcd_row_state != LCD_IDLE_STATUS))) {
+ if (displaying_clock){
+ if (LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_POSITION == LEFT){
+ lcd.setCursor(0,LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_ROW-1);
+ } else {
+ lcd.setCursor(LCD_COLUMNS-6,LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_ROW-1);
+ }
+ lcd.print(coordinates_to_maidenhead(latitude,longitude));
+ displaying_clock = 0;
+ } else {
+ displaying_clock = 2; // switch to the clock (2 == print the clock regardless of time)
+ }
+
+ }
+ last_clock_seconds = clock_seconds;
+ }
+
+
+ if (((displaying_clock && (last_clock_minutes != clock_minutes)) || (displaying_clock == 2)) && ((lcd_state_row_0 == LCD_IDLE_STATUS) || ((LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_ROW-1)!= 0))){
+ #ifdef OPTION_CLOCK_ALWAYS_HAVE_HOUR_LEADING_ZERO
+ if (clock_hours < 10) {
+ strcpy(clock_temp_string, "0");
+ }
+ dtostrf(clock_hours, 0, 0, temp_string);
+ strcat(clock_temp_string,temp_string);
+ #else
+ dtostrf(clock_hours, 0, 0, temp_string);
+ strcpy(clock_temp_string,temp_string);
+ #endif //OPTION_CLOCK_ALWAYS_HAVE_HOUR_LEADING_ZERO
+ strcat(clock_temp_string,":");
+ if (clock_minutes < 10) {
+ strcat(clock_temp_string, "0");
+ }
+ if (clock_hours > 9){
+ clock_digits = 1;
+ }
+ dtostrf(clock_minutes, 0, 0, temp_string);
+ strcat(clock_temp_string,temp_string);
+ if (LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_POSITION == LEFT){
+ lcd.setCursor(0,LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_ROW-1);
+ } else {
+ lcd.setCursor(LCD_COLUMNS-(4+clock_digits),LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_ROW-1);
+ }
+ lcd.print(clock_temp_string);
+ if (LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_POSITION == RIGHT){
+ lcd.setCursor(LCD_COLUMNS-(6+clock_digits),LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_ROW-1);
+ }
+ lcd.print(" ");
+ last_clock_minutes = clock_minutes;
+ displaying_clock = 1;
+ }
+ last_clock_lcd_row_state = lcd_state_row_0;
+ }
+ #endif //defined(OPTION_DISPLAY_ALT_HHMM_CLOCK_AND_MAIDENHEAD) && defined(FEATURE_CLOCK)
+
+ // constant HH:MM:SS clock and maidenhead display ----------------------------------------------------------
+ #if defined(OPTION_DISPLAY_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD) && defined(FEATURE_CLOCK)
+
+
+ char clock_temp_string[14] = "";
+ static byte last_clock_minutes = 0;
+ static byte last_clock_seconds = 0;
+ static byte last_clock_lcd_row_state = 0;
+ byte clock_digits = 0;
+
+
+ if ((lcd_state_row_0 != LCD_UNDEF) && ((lcd_state_row_0 == LCD_IDLE_STATUS) || ((LCD_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD_ROW-1)!= 0))){
+ update_time();
+
+ if (((last_clock_seconds != clock_seconds) || ((((LCD_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD_ROW-1)== 0))) && (last_clock_lcd_row_state != LCD_IDLE_STATUS)) && ((lcd_state_row_0 == LCD_IDLE_STATUS) || ((LCD_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD_ROW-1)!= 0))){
+ if (LCD_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD_POSITION == LEFT){
+ lcd.setCursor(0,LCD_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD_ROW-1);
+ } else {
+ lcd.setCursor(LCD_COLUMNS-14,LCD_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD_ROW-1);
+ }
+ #ifdef OPTION_CLOCK_ALWAYS_HAVE_HOUR_LEADING_ZERO
+ if (clock_hours < 10) {
+ strcpy(clock_temp_string, "0");
+ }
+ dtostrf(clock_hours, 0, 0, temp_string);
+ strcat(clock_temp_string,temp_string);
+ #else
+ dtostrf(clock_hours, 0, 0, temp_string);
+ strcpy(clock_temp_string,temp_string);
+ #endif //OPTION_CLOCK_ALWAYS_HAVE_HOUR_LEADING_ZERO
+ strcat(clock_temp_string,":");
+ if (clock_minutes < 10) {
+ strcat(clock_temp_string, "0");
+ }
+ if (clock_hours > 9){
+ clock_digits = 1;
+ }
+ dtostrf(clock_minutes, 0, 0, temp_string);
+ strcat(clock_temp_string,temp_string);
+ strcat(clock_temp_string,":");
+ if (clock_seconds < 10) {
+ strcat(clock_temp_string, "0");
+ }
+ dtostrf(clock_seconds, 0, 0, temp_string);
+ strcat(clock_temp_string,temp_string);
+ lcd.print(clock_temp_string);
+ lcd.print(" ");
+ lcd.print(coordinates_to_maidenhead(latitude,longitude));
+ last_clock_seconds = clock_seconds;
+ }
+
+
+ last_clock_lcd_row_state = lcd_state_row_0;
+ }
+ #endif //defined(OPTION_DISPLAY_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD) && defined(FEATURE_CLOCK)
+
+ // gps indicator -------------------------------------------------------------------------
+ #if defined(OPTION_DISPLAY_GPS_INDICATOR) && defined(FEATURE_GPS) && defined(FEATURE_CLOCK)
+ static byte last_clock_status = FREE_RUNNING;
+ static byte last_gps_lcd_row_state = 0;
+
+ if ((lcd_state_row_0 != LCD_UNDEF) && ((lcd_state_row_0 == LCD_IDLE_STATUS) || ((LCD_GPS_INDICATOR_ROW-1)!= 0))){
+ if ((last_clock_status != clock_status) || ((LCD_GPS_INDICATOR_ROW == 1) && (last_gps_lcd_row_state != lcd_state_row_0))) {
+ if (LCD_GPS_INDICATOR_POSITION == LEFT){
+ lcd.setCursor(0,LCD_GPS_INDICATOR_ROW-1);
+ } else {
+ lcd.setCursor(LCD_COLUMNS-3,LCD_GPS_INDICATOR_ROW-1);
+ }
+ if (clock_status == GPS_SYNC){
+ lcd.print(GPS_STRING);
+ } else {
+ lcd.print(" ");
+ }
+ }
+ last_clock_status = clock_status;
+ }
+ last_gps_lcd_row_state = lcd_state_row_0;
+ #endif //defined(OPTION_DISPLAY_GPS_INDICATOR) && defined(FEATURE_GPS) && defined(FEATURE_CLOCK)
+
+
+
+
+ #if (defined(OPTION_DISPLAY_MOON_TRACKING_CONTINUOUSLY) && defined(FEATURE_MOON_TRACKING)) || (defined(OPTION_DISPLAY_SUN_TRACKING_CONTINUOUSLY) && defined(FEATURE_SUN_TRACKING)) || defined(OPTION_DISPLAY_MOON_OR_SUN_TRACKING_CONDITIONAL)
+ char trackingstring[LCD_COLUMNS+2] = "";
+ char temptrackingstring[LCD_COLUMNS+2] = "";
+ #endif
+
+ // moon tracking ----------------------------------------------------------
+ #if defined(OPTION_DISPLAY_MOON_TRACKING_CONTINUOUSLY) && defined(FEATURE_MOON_TRACKING)
+
+ static unsigned long last_moon_tracking_check_time = 0;
+ static byte last_strlen_moon = 0;
+
+ if ((lcd_state_row_0 != 0) && (lcd_state_row_1 != 0) && ((millis()-last_moon_tracking_check_time) > LCD_MOON_TRACKING_UPDATE_INTERVAL)) {
+ update_moon_position();
+ strcpy(trackingstring,"");
+ if (moon_tracking_active){
+ if (moon_visible){
+ strcat(trackingstring,TRACKING_ACTIVE_CHAR);
+ } else {
+ strcat(trackingstring,"-");
+ }
+ }
+ strcat(trackingstring,MOON_STRING);
+ dtostrf(moon_azimuth,0,LCD_DECIMAL_PLACES,temp_string);
+ strcat(trackingstring,temp_string);
+ if ((LCD_COLUMNS>16) && ((moon_azimuth < 100) || (abs(moon_elevation)<100))) {strcat(trackingstring,"\xDF");}
+ strcat(trackingstring," ");
+ dtostrf(moon_elevation,0,LCD_DECIMAL_PLACES,temp_string);
+ strcat(trackingstring,temp_string);
+ if ((LCD_COLUMNS>16) && ((moon_azimuth < 100) || (abs(moon_elevation)<100))) {strcat(trackingstring,"\xDF");}
+ if (moon_tracking_active){
+ if (moon_visible){
+ strcat(trackingstring,TRACKING_ACTIVE_CHAR);
+ } else {
+ strcat(trackingstring,TRACKING_INACTIVE_CHAR);
+ }
+ }
+ // if (strlen(trackingstring) < last_strlen_moon){
+ // clear_display_row(LCD_MOON_TRACKING_ROW-1);
+ // }
+ // last_strlen_moon = strlen(trackingstring);
+ // lcd.setCursor((LCD_COLUMNS-strlen(trackingstring))/2,LCD_MOON_TRACKING_ROW-1);
+
+ lcd.setCursor(0,LCD_MOON_TRACKING_ROW-1);
+ int x = LCD_COLUMNS - strlen(trackingstring);
+ byte y = 0;
+ while (x > 0){
+ if ((y%2) != 0){
+ strcpy(temptrackingstring," ");
+ strcat(temptrackingstring,trackingstring);
+ strcpy(trackingstring,temptrackingstring);
+ } else {
+ strcat(trackingstring," ");
+ }
+ y++;
+ x--;
+ }
+
+
+
+ lcd.print(trackingstring);
+ last_moon_tracking_check_time = millis();
+ }
+ #endif //defined(OPTION_DISPLAY_MOON_TRACKING_CONTINUOUSLY) && defined(FEATURE_MOON_TRACKING)
+
+
+ // sun tracking ----------------------------------------------------------
+ #if defined(OPTION_DISPLAY_SUN_TRACKING_CONTINUOUSLY) && defined(FEATURE_SUN_TRACKING)
+
+ static unsigned long last_sun_tracking_check_time = 0;
+ static byte last_strlen_sun = 0;
+
+ if ((lcd_state_row_0 != 0) && (lcd_state_row_1 != 0) && ((millis()-last_sun_tracking_check_time) > LCD_SUN_TRACKING_UPDATE_INTERVAL)) {
+ update_sun_position();
+ strcpy(trackingstring,"");
+ if (sun_tracking_active){
+ if (sun_visible){
+ strcat(trackingstring,TRACKING_ACTIVE_CHAR);
+ } else {
+ strcat(trackingstring,TRACKING_INACTIVE_CHAR);
+ }
+ }
+ strcat(trackingstring,SUN_STRING);
+ dtostrf(sun_azimuth,0,LCD_DECIMAL_PLACES,temp_string);
+ strcat(trackingstring,temp_string);
+ if ((LCD_COLUMNS>16) && ((sun_azimuth < 100) || (abs(sun_elevation)<100))) {strcat(trackingstring,"\xDF");}
+ strcat(trackingstring," ");
+ dtostrf(sun_elevation,0,LCD_DECIMAL_PLACES,temp_string);
+ strcat(trackingstring,temp_string);
+ if ((LCD_COLUMNS>16) && ((sun_azimuth < 100) || (abs(sun_elevation)<100))) {strcat(trackingstring,"\xDF");}
+ if (sun_tracking_active){
+ if (sun_visible){
+ strcat(trackingstring,TRACKING_ACTIVE_CHAR);
+ } else {
+ strcat(trackingstring,TRACKING_INACTIVE_CHAR);
+ }
+ }
+ // if (strlen(trackingstring) < last_strlen_sun){
+ // clear_display_row(LCD_SUN_TRACKING_ROW-1);
+ // }
+ // last_strlen_sun = strlen(trackingstring);
+ // lcd.setCursor((LCD_COLUMNS-strlen(trackingstring))/2,LCD_SUN_TRACKING_ROW-1);
+
+ lcd.setCursor(0,LCD_SUN_TRACKING_ROW-1);
+ int x = LCD_COLUMNS - strlen(trackingstring);
+ byte y = 0;
+ while (x > 0){
+ if ((y%2) != 0){
+ strcpy(temptrackingstring," ");
+ strcat(temptrackingstring,trackingstring);
+ strcpy(trackingstring,temptrackingstring);
+ } else {
+ strcat(trackingstring," ");
+ }
+ y++;
+ x--;
+ }
+
+
+
+ lcd.print(trackingstring);
+ last_sun_tracking_check_time = millis();
+ }
+ #endif //defined(OPTION_DISPLAY_SUN_TRACKING_CONTINUOUSLY) && defined(FEATURE_SUN_TRACKING)
+
+
+
+
+
+
+ // moon and/or sun tracking conditional ------------------------------------------------------------------------
+ #ifdef OPTION_DISPLAY_MOON_OR_SUN_TRACKING_CONDITIONAL
+
+ // moon tracking ----
+ #if defined(FEATURE_MOON_TRACKING)
+
+ static unsigned long last_moon_tracking_check_time = 0;
+ static byte last_strlen_moon = 0;
+ static byte last_moon_tracking_state = 0;
+
+ if ((lcd_state_row_0 != 0) && (lcd_state_row_1 != 0) && ((millis()-last_moon_tracking_check_time) > LCD_MOON_TRACKING_UPDATE_INTERVAL) && moon_tracking_active) {
+ update_moon_position();
+ strcpy(trackingstring,"");
+ strcat(trackingstring,MOON_STRING);
+ dtostrf(moon_azimuth,0,LCD_DECIMAL_PLACES,temp_string);
+ strcat(trackingstring,temp_string);
+ if ((LCD_COLUMNS>16) && ((moon_azimuth < 100) || (abs(moon_elevation)<100))) {strcat(trackingstring,"\xDF");}
+ strcat(trackingstring," ");
+ dtostrf(moon_elevation,0,LCD_DECIMAL_PLACES,temp_string);
+ strcat(trackingstring,temp_string);
+ if ((LCD_COLUMNS>16) && ((moon_azimuth < 100) || (abs(moon_elevation)<100))) {strcat(trackingstring,"\xDF");}
+ if (strlen(trackingstring) < last_strlen_moon){
+ clear_display_row(LCD_MOON_OR_SUN_TRACKING_CONDITIONAL_ROW-1);
+ }
+ last_strlen_moon = strlen(trackingstring);
+ lcd.setCursor((LCD_COLUMNS-strlen(trackingstring))/2,LCD_MOON_OR_SUN_TRACKING_CONDITIONAL_ROW-1);
+ lcd.print(trackingstring);
+ last_moon_tracking_check_time = millis();
+ last_moon_tracking_state = 1;
+ }
+
+ if (!moon_tracking_active && last_moon_tracking_state){
+ clear_display_row(LCD_MOON_OR_SUN_TRACKING_CONDITIONAL_ROW-1);
+ last_moon_tracking_state = 0;
+ }
+
+ #endif //defined(OPTION_DISPLAY_MOON_TRACKING_CONTINUOUSLY) && defined(FEATURE_MOON_TRACKING)
+
+
+ // sun tracking ----------------------------------------------------------
+ #if defined(FEATURE_SUN_TRACKING)
+
+ static unsigned long last_sun_tracking_check_time = 0;
+ static byte last_strlen_sun = 0;
+ static byte last_sun_tracking_state = 0;
+
+ if ((lcd_state_row_0 != 0) && (lcd_state_row_1 != 0) && ((millis()-last_sun_tracking_check_time) > LCD_SUN_TRACKING_UPDATE_INTERVAL) && sun_tracking_active) {
+ update_sun_position();
+ strcpy(trackingstring,"");
+ strcat(trackingstring,SUN_STRING);
+ dtostrf(sun_azimuth,0,LCD_DECIMAL_PLACES,temp_string);
+ strcat(trackingstring,temp_string);
+ if ((LCD_COLUMNS>16) && ((sun_azimuth < 100) || (abs(sun_elevation)<100))) {strcat(trackingstring,"\xDF");}
+ strcat(trackingstring," ");
+ dtostrf(sun_elevation,0,LCD_DECIMAL_PLACES,temp_string);
+ strcat(trackingstring,temp_string);
+ if ((LCD_COLUMNS>16) && ((sun_azimuth < 100) || (abs(sun_elevation)<100))) {strcat(trackingstring,"\xDF");}
+ if (strlen(trackingstring) < last_strlen_sun){
+ clear_display_row(LCD_MOON_OR_SUN_TRACKING_CONDITIONAL_ROW-1);
+ }
+ last_strlen_sun = strlen(trackingstring);
+ lcd.setCursor((LCD_COLUMNS-strlen(trackingstring))/2,LCD_MOON_OR_SUN_TRACKING_CONDITIONAL_ROW-1);
+ lcd.print(trackingstring);
+ last_sun_tracking_check_time = millis();
+ last_sun_tracking_state = 1;
+ }
+
+
+ if (!sun_tracking_active && last_sun_tracking_state){
+ clear_display_row(LCD_MOON_OR_SUN_TRACKING_CONDITIONAL_ROW-1);
+ last_sun_tracking_state = 0;
+ }
+
+ #endif //defined(FEATURE_SUN_TRACKING)
+
+ #endif //OPTION_DISPLAY_MOON_OR_SUN_TRACKING_CONDITIONAL
+
+ // end of moon and/or sun conditional -----
+
+ if ((millis() - last_lcd_update) > LCD_UPDATE_TIME) {
+ last_lcd_update = millis();
+ }
+
+ last_row_0_string = row_0_string;
+
+
+
+
+
+
+ // clock display --- big clock ---------------------------------------------------------
+ /* this is outside the normal LCD refresh timing so the seconds update as soon as possible */
+ #if defined(OPTION_DISPLAY_BIG_CLOCK) && defined(FEATURE_CLOCK)
+
+ char clock_big_temp_string[22] = "";
+ static byte last_clock_big_seconds = 0;
+ static byte last_clock_big_minutes = 0;
+ static byte printed_z = 0;
+
+
+ update_time();
+ if ((last_clock_big_seconds != clock_seconds) && (lcd_state_row_0 != 0) && (lcd_state_row_1 != 0)){
+ sprintf(clock_big_temp_string, "%s", clock_string());
+ //clock_big_temp_string[20]
+ if (last_clock_big_minutes == clock_minutes){ // if the minutes didn't change, don't send the whole string to the LCD
+
+ if ((int(float(last_clock_big_seconds)/10.0)) != (int(float(clock_seconds)/10.0))){
+ lcd.setCursor(((LCD_COLUMNS-20)/2)+17,LCD_BIG_CLOCK_ROW-1);
+ lcd.print(clock_big_temp_string[17]);
+ } else {
+ lcd.setCursor(((LCD_COLUMNS-20)/2)+18,LCD_BIG_CLOCK_ROW-1);
+ }
+ lcd.print(clock_big_temp_string[18]);
+ last_clock_big_seconds = clock_seconds;
+
+
+
+ } else { // print the whole clock
+ lcd.setCursor((LCD_COLUMNS-20)/2,LCD_BIG_CLOCK_ROW-1);
+ if (!printed_z){clock_big_temp_string[20] = 0;} // I put this in to fix mysterious characters that appear at 0,0 for no reason
+ lcd.print(clock_big_temp_string);
+ last_clock_big_seconds = clock_seconds;
+ last_clock_big_minutes = clock_minutes;
+ printed_z = 1;
+ }
+ }
+ #endif //defined(OPTION_DISPLAY_BIG_CLOCK) && defined(FEATURE_CLOCK)
+ // end clock display --- big clock ---------------------------------------------------------
+
+
+
+} /* update_display */
+#endif /* ifdef FEATURE_LCD_DISPLAY */
+
+
+// --------------------------------------------------------------
#ifdef FEATURE_LCD_DISPLAY
-void clear_display_row(byte row_number)
-{
- lcd.setCursor(0,row_number);
+void clear_display_row(byte row_number){
+ lcd.setCursor(0, row_number);
for (byte x = 0; x < LCD_COLUMNS; x++) {
lcd.print(" ");
}
}
#endif
-//--------------------------------------------------------------
-void get_keystroke()
-{
- while (Serial.available() == 0) {}
- while (Serial.available() > 0) {
- incoming_serial_byte = Serial.read();
- }
-}
-
-//--------------------------------------------------------------
-
-#ifdef FEATURE_YAESU_EMULATION
-void yaesu_x_command() {
-
- if (serial0_buffer_index > 1) {
- switch (serial0_buffer[1]) {
- case '4':
- normal_az_speed_voltage = PWM_SPEED_VOLTAGE_X4;
- update_az_variable_outputs(PWM_SPEED_VOLTAGE_X4);
- #if defined(FEATURE_ELEVATION_CONTROL) && defined(OPTION_EL_SPEED_FOLLOWS_AZ_SPEED)
- normal_el_speed_voltage = PWM_SPEED_VOLTAGE_X4;
- update_el_variable_outputs(PWM_SPEED_VOLTAGE_X4);
- #endif
- Serial.print(F("Speed X4\r\n"));
- break;
- case '3':
- normal_az_speed_voltage = PWM_SPEED_VOLTAGE_X3;
- update_az_variable_outputs(PWM_SPEED_VOLTAGE_X3);
- #if defined(FEATURE_ELEVATION_CONTROL) && defined(OPTION_EL_SPEED_FOLLOWS_AZ_SPEED)
- normal_el_speed_voltage = PWM_SPEED_VOLTAGE_X3;
- update_el_variable_outputs(PWM_SPEED_VOLTAGE_X3);
- #endif
- Serial.print(F("Speed X3\r\n"));
- break;
- case '2':
- normal_az_speed_voltage = PWM_SPEED_VOLTAGE_X2;
- update_az_variable_outputs(PWM_SPEED_VOLTAGE_X2);
- #if defined(FEATURE_ELEVATION_CONTROL) && defined(OPTION_EL_SPEED_FOLLOWS_AZ_SPEED)
- normal_el_speed_voltage = PWM_SPEED_VOLTAGE_X2;
- update_el_variable_outputs(PWM_SPEED_VOLTAGE_X2);
- #endif
- Serial.print(F("Speed X2\r\n"));
- break;
- case '1':
- normal_az_speed_voltage = PWM_SPEED_VOLTAGE_X1;
- update_az_variable_outputs(PWM_SPEED_VOLTAGE_X1);
- #if defined(FEATURE_ELEVATION_CONTROL) && defined(OPTION_EL_SPEED_FOLLOWS_AZ_SPEED)
- normal_el_speed_voltage = PWM_SPEED_VOLTAGE_X1;
- update_el_variable_outputs(PWM_SPEED_VOLTAGE_X1);
- #endif
- Serial.print(F("Speed X1\r\n"));
- break;
- default: Serial.println(F("?>")); break;
- }
- } else {
- Serial.println(F("?>"));
- }
-}
-#endif //FEATURE_YAESU_EMULATION
-
-//--------------------------------------------------------------
-#ifdef FEATURE_YAESU_EMULATION
-#ifdef OPTION_GS_232B_EMULATION
-void yaesu_p_command()
-{
- if ((serial0_buffer[1] == '3') && (serial0_buffer_index > 2)) { // P36 command
- configuration.azimuth_rotation_capability = 360;
- Serial.print(F("Mode 360 degree\r\n"));
- write_settings_to_eeprom();
- } else {
- if ((serial0_buffer[1] == '4') && (serial0_buffer_index > 2)) { // P45 command
- configuration.azimuth_rotation_capability = 450;
- Serial.print(F("Mode 450 degree\r\n"));
- write_settings_to_eeprom();
- } else {
- Serial.println(F("?>"));
- }
+// --------------------------------------------------------------
+#if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
+void get_keystroke(){
+ while (control_port->available() == 0) {
}
-
+ while (control_port->available() > 0)
+ incoming_serial_byte = control_port->read();
}
-#endif //OPTION_GS_232B_EMULATION
-#endif //FEATURE_YAESU_EMULATION
-//--------------------------------------------------------------
+#endif // defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
-#ifdef FEATURE_YAESU_EMULATION
-void yaesu_o_command()
-{
-
- #ifdef FEATURE_ELEVATION_CONTROL
- if ((serial0_buffer[1] == '2') && (serial0_buffer_index > 1)) { // did we get the O2 command?
- yaesu_o2_command();
- return;
- }
- #endif
-
- clear_serial_buffer();
-
- Serial.println(F("Rotate to full CCW and send keystroke..."));
- get_keystroke();
- read_azimuth();
- configuration.analog_az_full_ccw = analog_az;
- write_settings_to_eeprom();
- print_wrote_to_memory();
-}
-#endif //FEATURE_YAESU_EMULATION
-//--------------------------------------------------------------
+// --------------------------------------------------------------
#ifdef FEATURE_YAESU_EMULATION
void print_wrote_to_memory(){
- Serial.println(F("Wrote to memory"));
+ control_port->println(F("Wrote to memory"));
}
-#endif //FEATURE_YAESU_EMULATION
-//--------------------------------------------------------------
+#endif // FEATURE_YAESU_EMULATION
+// --------------------------------------------------------------
#ifdef FEATURE_YAESU_EMULATION
void clear_serial_buffer(){
-
+
delay(200);
- while (Serial.available()) {incoming_serial_byte = Serial.read();}
-
+ while (control_port->available()) incoming_serial_byte = control_port->read();
}
-#endif //FEATURE_YAESU_EMULATION
-//--------------------------------------------------------------
-
-#ifdef FEATURE_YAESU_EMULATION
-void yaesu_f_command()
-{
-
- #ifdef FEATURE_ELEVATION_CONTROL
- if ((serial0_buffer[1] == '2') && (serial0_buffer_index > 1)) { // did we get the F2 command?
- yaesu_f2_command();
- return;
- }
- #endif
-
- clear_serial_buffer();
-
- Serial.println(F("Rotate to full CW and send keystroke..."));
- get_keystroke();
- read_azimuth();
- configuration.analog_az_full_cw = analog_az;
- write_settings_to_eeprom();
- print_wrote_to_memory();
-}
-#endif //FEATURE_YAESU_EMULATION
-//--------------------------------------------------------------
-#if defined(FEATURE_YAESU_EMULATION) && defined(FEATURE_ELEVATION_CONTROL)
-void yaesu_o2_command()
-{
- clear_serial_buffer();
- Serial.println(F("Elevate to 0 degrees and send keystroke..."));
- get_keystroke();
- read_elevation();
- configuration.analog_el_0_degrees = analog_el;
- write_settings_to_eeprom();
- print_wrote_to_memory();
-}
-#endif //defined(FEATURE_YAESU_EMULATION) && defined(FEATURE_ELEVATION_CONTROL)
+#endif // FEATURE_YAESU_EMULATION
+// --------------------------------------------------------------
-//--------------------------------------------------------------
-#if defined(FEATURE_YAESU_EMULATION) && defined(FEATURE_ELEVATION_CONTROL)
-void yaesu_f2_command()
-{
- clear_serial_buffer();
- Serial.println(F("Elevate to 180 (or max elevation) and send keystroke..."));
- get_keystroke();
- read_elevation();
- configuration.analog_el_max_elevation = analog_el;
- write_settings_to_eeprom();
- print_wrote_to_memory();
-}
-#endif //defined(FEATURE_YAESU_EMULATION) && defined(FEATURE_ELEVATION_CONTROL)
+void read_settings_from_eeprom(){
-//--------------------------------------------------------------
-
-void read_settings_from_eeprom()
-{
-
- //EEPROM_readAnything(0,configuration);
-
- byte* p = (byte*)(void*)&configuration;
+ byte * p = (byte *)(void *)&configuration;
unsigned int i;
int ee = 0;
- for (i = 0; i < sizeof(configuration); i++){
- *p++ = EEPROM.read(ee++);
+
+ for (i = 0; i < sizeof(configuration); i++) {
+ *p++ = EEPROM.read(ee++);
}
-
- if (configuration.magic_number == EEPROM_MAGIC_NUMBER) {
+
+ if (configuration.magic_number == EEPROM_MAGIC_NUMBER) {
#ifdef DEBUG_EEPROM
if (debug_mode) {
- Serial.print(F("read_settings_from_eeprom: reading settings from eeprom: "));
- Serial.print("analog_az_full_ccw");
- Serial.println(configuration.analog_az_full_ccw,DEC);
- Serial.print("analog_az_full_cw");
- Serial.println(configuration.analog_az_full_cw,DEC);
- Serial.print("analog_el_0_degrees");
- Serial.println(configuration.analog_el_0_degrees,DEC);
- Serial.print("analog_el_max_elevation");
- Serial.println(configuration.analog_el_max_elevation,DEC);
- Serial.print("azimuth_starting_point");
- Serial.println(configuration.azimuth_starting_point,DEC);
- Serial.print("azimuth_rotation_capability");
- Serial.println(configuration.azimuth_rotation_capability,DEC);
- Serial.print("last_azimuth:");
- Serial.println(configuration.last_azimuth,1);
- Serial.print("last_elevation");
- Serial.println(configuration.last_elevation,1);
+ debug_println("read_settings_from_eeprom: reading settings from eeprom: ");
+ debug_print("\nanalog_az_full_ccw");
+ debug_print_int(configuration.analog_az_full_ccw);
+ debug_print("\nanalog_az_full_cw");
+ debug_print_int(configuration.analog_az_full_cw);
+ debug_print("\nanalog_el_0_degrees");
+ debug_print_int(configuration.analog_el_0_degrees);
+ debug_print("\nanalog_el_max_elevation");
+ debug_print_int(configuration.analog_el_max_elevation);
+ debug_print("\nlast_azimuth:");
+ debug_print_float(configuration.last_azimuth, 1);
+ debug_print("\nlast_elevation:");
+ debug_print_float(configuration.last_elevation, 1);
+ debug_print("\nlast_az_incremental_encoder_position:");
+ debug_print_int(configuration.last_az_incremental_encoder_position);
+ debug_print("\nlast_el_incremental_encoder_position:");
+ debug_print_int(configuration.last_el_incremental_encoder_position);
+ debug_print("\naz_offset:");
+ debug_print_float(configuration.azimuth_offset,2);
+ debug_print("\nel_offset:");
+ debug_print_float(configuration.elevation_offset,2);
+ debug_println("");
}
- #endif //DEBUG_EEPROM
-
- #ifdef FEATURE_AZ_POSITION_ROTARY_ENCODER
- raw_azimuth = int(configuration.last_azimuth*HEADING_MULTIPLIER);
- if (raw_azimuth >= (360*HEADING_MULTIPLIER)){
- azimuth = raw_azimuth - (360*HEADING_MULTIPLIER);
+ #endif // DEBUG_EEPROM
+
+
+ #if defined(FEATURE_AZ_POSITION_INCREMENTAL_ENCODER)
+ az_incremental_encoder_position = configuration.last_az_incremental_encoder_position;
+ #endif
+
+ #if defined(FEATURE_ELEVATION_CONTROL) && defined(FEATURE_EL_POSITION_INCREMENTAL_ENCODER)
+ el_incremental_encoder_position = configuration.last_el_incremental_encoder_position;
+ #endif
+
+
+ #if defined(FEATURE_AZ_POSITION_ROTARY_ENCODER)
+ raw_azimuth = int(configuration.last_azimuth * HEADING_MULTIPLIER);
+ if (raw_azimuth >= (360 * HEADING_MULTIPLIER)) {
+ azimuth = raw_azimuth - (360 * HEADING_MULTIPLIER);
} else {
azimuth = raw_azimuth;
}
- #endif //FEATURE_AZ_POSITION_ROTARY_ENCODER
-
- #ifdef FEATURE_EL_POSITION_ROTARY_ENCODER
- elevation = int(configuration.last_elevation*HEADING_MULTIPLIER);
- #endif //FEATURE_EL_POSITION_ROTARY_ENCODER
-
-
-
+ #endif // defined(FEATURE_AZ_POSITION_ROTARY_ENCODER)
+
+ #if defined(FEATURE_ELEVATION_CONTROL) && defined(FEATURE_EL_POSITION_ROTARY_ENCODER)
+ elevation = int(configuration.last_elevation * HEADING_MULTIPLIER);
+ #endif // defined(FEATURE_EL_POSITION_ROTARY_ENCODER)
+
+
+
#ifdef FEATURE_AZ_POSITION_PULSE_INPUT
- raw_azimuth = int(configuration.last_azimuth*HEADING_MULTIPLIER);
- if (raw_azimuth >= (360*HEADING_MULTIPLIER)){
- azimuth = raw_azimuth - (360*HEADING_MULTIPLIER);
+ raw_azimuth = int(configuration.last_azimuth * HEADING_MULTIPLIER);
+ if (raw_azimuth >= (360 * HEADING_MULTIPLIER)) {
+ azimuth = raw_azimuth - (360 * HEADING_MULTIPLIER);
} else {
azimuth = raw_azimuth;
}
az_position_pulse_input_azimuth = configuration.last_azimuth;
- #endif //FEATURE_AZ_POSITION_PULSE_INPUT
-
- #ifdef FEATURE_EL_POSITION_PULSE_INPUT
- elevation = int(configuration.last_elevation*HEADING_MULTIPLIER);
+ #endif // FEATURE_AZ_POSITION_PULSE_INPUT
+
+ #if defined(FEATURE_ELEVATION_CONTROL) && defined(FEATURE_EL_POSITION_PULSE_INPUT)
+ elevation = int(configuration.last_elevation * HEADING_MULTIPLIER);
el_position_pulse_input_elevation = configuration.last_elevation;
- #endif //FEATURE_EL_POSITION_PULSE_INPUT
-
-// #ifdef FEATURE_AZ_POSITION_PULSE_INPUT
-// volatile float az_position_pulse_azimuth = 0;
-// #endif //FEATURE_AZ_POSITION_PULSE_INPUT a
+ #endif // FEATURE_EL_POSITION_PULSE_INPUT
+
+ #if defined(FEATURE_AZ_POSITION_PULSE_INPUT) || defined(FEATURE_AZ_POSITION_ROTARY_ENCODER)
+ configuration.azimuth_offset = 0;
+ #endif
+
+ #if defined(FEATURE_EL_POSITION_PULSE_INPUT) || defined(FEATURE_EL_POSITION_ROTARY_ENCODER)
+ configuration.elevation_offset = 0;
+ #endif
+
+
} else { // initialize eeprom with default values
#ifdef DEBUG_EEPROM
- if (debug_mode) {
- Serial.println(F("read_settings_from_eeprom: uninitialized eeprom, calling initialize_eeprom_with_defaults()"));
- }
- #endif //DEBUG_EEPROM
+ debug_println("read_settings_from_eeprom: uninitialized eeprom, calling initialize_eeprom_with_defaults()");
+ #endif // DEBUG_EEPROM
initialize_eeprom_with_defaults();
}
-}
-//--------------------------------------------------------------
+} /* read_settings_from_eeprom */
+// --------------------------------------------------------------
void initialize_eeprom_with_defaults(){
#ifdef DEBUG_EEPROM
- if (debug_mode) {
- Serial.println(F("initialize_eeprom_with_defaults: writing eeprom"));
- }
- #endif //DEBUG_EEPROM
+ debug_println("initialize_eeprom_with_defaults: writing eeprom");
+ #endif // DEBUG_EEPROM
configuration.analog_az_full_ccw = ANALOG_AZ_FULL_CCW;
configuration.analog_az_full_cw = ANALOG_AZ_FULL_CW;
configuration.analog_el_0_degrees = ANALOG_EL_0_DEGREES;
- configuration.analog_el_max_elevation = ANALOG_EL_MAX_ELEVATION;
- configuration.azimuth_starting_point = AZIMUTH_STARTING_POINT_DEFAULT;
- configuration.azimuth_rotation_capability = AZIMUTH_ROTATION_CAPABILITY_DEFAULT;
+ configuration.analog_el_max_elevation = ANALOG_EL_MAX_ELEVATION;
+ // azimuth_starting_point = AZIMUTH_STARTING_POINT_DEFAULT;
+ // azimuth_rotation_capability = AZIMUTH_ROTATION_CAPABILITY_DEFAULT;
configuration.last_azimuth = raw_azimuth;
+ configuration.last_az_incremental_encoder_position = 0;
+ configuration.last_el_incremental_encoder_position = 0;
+ configuration.azimuth_offset = 0;
+ configuration.elevation_offset = 0;
#ifdef FEATURE_ELEVATION_CONTROL
- configuration.last_elevation = elevation;
- #else
+ configuration.last_elevation = elevation;
+ #else
configuration.last_elevation = 0;
#endif
-
+
write_settings_to_eeprom();
-
-}
+
+} /* initialize_eeprom_with_defaults */
-//--------------------------------------------------------------
-void write_settings_to_eeprom()
-{
+// --------------------------------------------------------------
+void write_settings_to_eeprom(){
#ifdef DEBUG_EEPROM
- if (debug_mode) {
- Serial.print(F("write_settings_to_eeprom: writing settings to eeprom\n"));
- }
- #endif //DEBUG_EEPROM
-
+ debug_println("write_settings_to_eeprom: writing settings to eeprom");
+ #endif // DEBUG_EEPROM
+
configuration.magic_number = EEPROM_MAGIC_NUMBER;
-
- const byte* p = (const byte*)(const void*)&configuration;
+
+ const byte * p = (const byte *)(const void *)&configuration;
unsigned int i;
int ee = 0;
- for (i = 0; i < sizeof(configuration); i++){
- EEPROM.write(ee++, *p++);
+ for (i = 0; i < sizeof(configuration); i++) {
+ EEPROM.write(ee++, *p++);
}
-
- //EEPROM_writeAnything(0,configuration);
+
+ // EEPROM_writeAnything(0,configuration);
configuration_dirty = 0;
-
+
}
-//--------------------------------------------------------------
+// --------------------------------------------------------------
-void az_check_operation_timeout()
-{
+void az_check_operation_timeout(){
// check if the last executed rotation operation has been going on too long
if (((millis() - az_last_rotate_initiation) > OPERATION_TIMEOUT) && (az_state != IDLE)) {
- submit_request(AZ,REQUEST_KILL,0);
+ submit_request(AZ, REQUEST_KILL, 0, 78);
#ifdef DEBUG_AZ_CHECK_OPERATION_TIMEOUT
- if (debug_mode) {Serial.println(F("az_check_operation_timeout: timeout reached, aborting rotation"));}
- #endif //DEBUG_AZ_CHECK_OPERATION_TIMEOUT
+ debug_println("az_check_operation_timeout: timeout reached, aborting rotation");
+ #endif // DEBUG_AZ_CHECK_OPERATION_TIMEOUT
}
}
-//--------------------------------------------------------------
+// --------------------------------------------------------------
#ifdef FEATURE_TIMED_BUFFER
-void clear_timed_buffer()
-{
+void clear_timed_buffer(){
timed_buffer_status = EMPTY;
timed_buffer_number_entries_loaded = 0;
timed_buffer_entry_pointer = 0;
}
-#endif //FEATURE_TIMED_BUFFER
-//--------------------------------------------------------------
-void yaesu_m_command(){
-
- int parsed_azimuth = 0;
-
- // parse out M command
- if (serial0_buffer_index > 4) { // if there are more than 4 characters in the command buffer, we got a timed interval command
- #ifdef FEATURE_TIMED_BUFFER
- yaesu_az_load_timed_intervals();
- #else
- Serial.println(F("Feature not activated ?>"));
- #endif //FEATURE_TIMED_BUFFER
- return;
- } else { // if there are four characters, this is just a single direction setting
- if (serial0_buffer_index == 4){
- parsed_azimuth = ((int(serial0_buffer[1])-48)*100) + ((int(serial0_buffer[2])-48)*10) + (int(serial0_buffer[3])-48);
- #ifdef FEATURE_TIMED_BUFFER
- clear_timed_buffer();
- #endif //FEATURE_TIMED_BUFFER
- if ((parsed_azimuth > -1) && (parsed_azimuth <= (configuration.azimuth_starting_point + configuration.azimuth_rotation_capability))) {
- submit_request(AZ,REQUEST_AZIMUTH,(parsed_azimuth*HEADING_MULTIPLIER));
- return;
- }
- }
- }
-
- Serial.println(F("?>"));
+#endif // FEATURE_TIMED_BUFFER
+// --------------------------------------------------------------
+// #ifdef FEATURE_YAESU_EMULATION
+// void yaesu_m_command(){
-}
+// int parsed_azimuth = 0;
+// // parse out M command
+// if (control_port_buffer_index > 4) { // if there are more than 4 characters in the command buffer, we got a timed interval command
+// #ifdef FEATURE_TIMED_BUFFER
+// yaesu_az_load_timed_intervals();
+// #else
+// control_port->println(F("Feature not activated ?>"));
+// #endif // FEATURE_TIMED_BUFFER
+// return;
+// } else { // if there are four characters, this is just a single direction setting
+// if (control_port_buffer_index == 4) {
+// parsed_azimuth = ((int(control_port_buffer[1]) - 48) * 100) + ((int(control_port_buffer[2]) - 48) * 10) + (int(control_port_buffer[3]) - 48);
+// #ifdef FEATURE_TIMED_BUFFER
+// clear_timed_buffer();
+// #endif // FEATURE_TIMED_BUFFER
+// if ((parsed_azimuth > -1) && (parsed_azimuth <= (azimuth_starting_point + azimuth_rotation_capability))) {
+// submit_request(AZ, REQUEST_AZIMUTH, (parsed_azimuth * HEADING_MULTIPLIER));
+// return;
+// }
+// }
+// }
-//--------------------------------------------------------------
+// control_port->println(F("?>"));
+
+// } /* yaesu_m_command */
+// #endif // FEATURE_YAESU_EMULATION
+// --------------------------------------------------------------
#ifdef FEATURE_TIMED_BUFFER
-void initiate_timed_buffer()
-{
+void initiate_timed_buffer(byte source_port){
if (timed_buffer_status == LOADED_AZIMUTHS) {
timed_buffer_status = RUNNING_AZIMUTHS;
- submit_request(AZ,REQUEST_AZIMUTH,timed_buffer_azimuths[1]);
+ submit_request(AZ, REQUEST_AZIMUTH, timed_buffer_azimuths[1], 79);
last_timed_buffer_action_time = millis();
timed_buffer_entry_pointer = 2;
#ifdef DEBUG_TIMED_BUFFER
- if (debug_mode) {Serial.println(F("initiate_timed_buffer: changing state to RUNNING_AZIMUTHS"));}
- #endif //DEBUG_TIMED_BUFFER
+ debug_println("initiate_timed_buffer: changing state to RUNNING_AZIMUTHS");
+ #endif // DEBUG_TIMED_BUFFER
} else {
#ifdef FEATURE_ELEVATION_CONTROL
if (timed_buffer_status == LOADED_AZIMUTHS_ELEVATIONS) {
timed_buffer_status = RUNNING_AZIMUTHS_ELEVATIONS;
- submit_request(AZ,REQUEST_AZIMUTH,timed_buffer_azimuths[1]);
- submit_request(EL,REQUEST_ELEVATION,timed_buffer_elevations[1]);
+ submit_request(AZ, REQUEST_AZIMUTH, timed_buffer_azimuths[1], 80);
+ submit_request(EL, REQUEST_ELEVATION, timed_buffer_elevations[1], 81);
last_timed_buffer_action_time = millis();
timed_buffer_entry_pointer = 2;
#ifdef DEBUG_TIMED_BUFFER
- if (debug_mode) {Serial.println(F("initiate_timed_buffer: changing state to RUNNING_AZIMUTHS_ELEVATIONS"));}
- #endif //DEBUG_TIMED_BUFFER
+ debug_println("initiate_timed_buffer: changing state to RUNNING_AZIMUTHS_ELEVATIONS");
+ #endif // DEBUG_TIMED_BUFFER
} else {
- Serial.println(">"); // error
+ print_to_port(">",source_port); // error
}
#endif
}
-}
-#endif //FEATURE_TIMED_BUFFER
-//--------------------------------------------------------------
+} /* initiate_timed_buffer */
+#endif // FEATURE_TIMED_BUFFER
+// --------------------------------------------------------------
#ifdef FEATURE_TIMED_BUFFER
void print_timed_buffer_empty_message(){
-
+
#ifdef DEBUG_TIMED_BUFFER
- if (debug_mode) {Serial.println(F("check_timed_interval: completed timed buffer; changing state to EMPTY"));}
- #endif //DEBUG_TIMED_BUFFER
-
+ debug_println("check_timed_interval: completed timed buffer; changing state to EMPTY");
+ #endif // DEBUG_TIMED_BUFFER
+
}
-#endif //FEATURE_TIMED_BUFFER
-//--------------------------------------------------------------
+#endif // FEATURE_TIMED_BUFFER
+// --------------------------------------------------------------
#ifdef FEATURE_TIMED_BUFFER
-void check_timed_interval()
-{
+void check_timed_interval(){
- if ((timed_buffer_status == RUNNING_AZIMUTHS) && (((millis() - last_timed_buffer_action_time)/1000) > timed_buffer_interval_value_seconds)) {
+ if ((timed_buffer_status == RUNNING_AZIMUTHS) && (((millis() - last_timed_buffer_action_time) / 1000) > timed_buffer_interval_value_seconds)) {
timed_buffer_entry_pointer++;
#ifdef DEBUG_TIMED_BUFFER
- if (debug_mode) {Serial.println(F("check_timed_interval: executing next timed interval step - azimuths"));}
- #endif //DEBUG_TIMED_BUFFER
- submit_request(AZ,REQUEST_AZIMUTH,timed_buffer_azimuths[timed_buffer_entry_pointer-1]);
+ debug_println("check_timed_interval: executing next timed interval step - azimuths");
+ #endif // DEBUG_TIMED_BUFFER
+ submit_request(AZ, REQUEST_AZIMUTH, timed_buffer_azimuths[timed_buffer_entry_pointer - 1], 82);
last_timed_buffer_action_time = millis();
if (timed_buffer_entry_pointer == timed_buffer_number_entries_loaded) {
clear_timed_buffer();
@@ -3554,100 +4123,76 @@ void check_timed_interval()
}
}
#ifdef FEATURE_ELEVATION_CONTROL
- if ((timed_buffer_status == RUNNING_AZIMUTHS_ELEVATIONS) && (((millis() - last_timed_buffer_action_time)/1000) > timed_buffer_interval_value_seconds)) {
+ if ((timed_buffer_status == RUNNING_AZIMUTHS_ELEVATIONS) && (((millis() - last_timed_buffer_action_time) / 1000) > timed_buffer_interval_value_seconds)) {
timed_buffer_entry_pointer++;
#ifdef DEBUG_TIMED_BUFFER
- if (debug_mode) {Serial.println(F("check_timed_interval: executing next timed interval step - az and el"));}
- #endif //DEBUG_TIMED_BUFFER
- submit_request(AZ,REQUEST_AZIMUTH,timed_buffer_azimuths[timed_buffer_entry_pointer-1]);
- submit_request(EL,REQUEST_ELEVATION,timed_buffer_elevations[timed_buffer_entry_pointer-1]);
+ debug_println("check_timed_interval: executing next timed interval step - az and el");
+ #endif // DEBUG_TIMED_BUFFER
+ submit_request(AZ, REQUEST_AZIMUTH, timed_buffer_azimuths[timed_buffer_entry_pointer - 1], 83);
+ submit_request(EL, REQUEST_ELEVATION, timed_buffer_elevations[timed_buffer_entry_pointer - 1], 84);
last_timed_buffer_action_time = millis();
if (timed_buffer_entry_pointer == timed_buffer_number_entries_loaded) {
clear_timed_buffer();
print_timed_buffer_empty_message();
-
+
}
}
#endif
-}
-#endif //FEATURE_TIMED_BUFFER
-//--------------------------------------------------------------
-#ifdef FEATURE_TIMED_BUFFER
-void yaesu_az_load_timed_intervals()
-{
- int parsed_value = 0;
+} /* check_timed_interval */
+#endif // FEATURE_TIMED_BUFFER
- clear_timed_buffer();
- parsed_value = ((int(serial0_buffer[1])-48)*100) + ((int(serial0_buffer[2])-48)*10) + (int(serial0_buffer[3])-48);
- if ((parsed_value > 0) && (parsed_value < 1000)) {
- timed_buffer_interval_value_seconds = parsed_value;
- for (int x = 5; x < serial0_buffer_index; x = x + 4) {
- parsed_value = ((int(serial0_buffer[x])-48)*100) + ((int(serial0_buffer[x+1])-48)*10) + (int(serial0_buffer[x+2])-48);
- if ((parsed_value > -1) && (parsed_value < 361)) { // is it a valid azimuth?
- timed_buffer_azimuths[timed_buffer_number_entries_loaded] = parsed_value * HEADING_MULTIPLIER;
- timed_buffer_number_entries_loaded++;
- timed_buffer_status = LOADED_AZIMUTHS;
- if (timed_buffer_number_entries_loaded > TIMED_INTERVAL_ARRAY_SIZE) { // is the array full?
- submit_request(AZ,REQUEST_AZIMUTH,timed_buffer_azimuths[0]); // array is full, go to the first azimuth
- timed_buffer_entry_pointer = 1;
- return;
- }
- } else { // we hit an invalid bearing
- timed_buffer_status = EMPTY;
- timed_buffer_number_entries_loaded = 0;
- Serial.println(F("?>")); // error
- return;
- }
- }
- submit_request(AZ,REQUEST_AZIMUTH,timed_buffer_azimuths[0]); // go to the first azimuth
- timed_buffer_entry_pointer = 1;
+// --------------------------------------------------------------
- } else {
- Serial.println(F("?>")); // error
- }
+void read_azimuth(byte force_read){
-}
-#endif //FEATURE_TIMED_BUFFER
-
-//--------------------------------------------------------------
-
-void read_azimuth(){
-
unsigned int previous_raw_azimuth = raw_azimuth;
static unsigned long last_measurement_time = 0;
+ #ifdef FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
+ static unsigned int incremental_encoder_previous_raw_azimuth = raw_azimuth;
+ #endif // FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
+
+ if (heading_reading_inhibit_pin) {
+ if (digitalReadEnhanced(heading_reading_inhibit_pin)) {
+ return;
+ }
+ }
+
#ifdef DEBUG_HEADING_READING_TIME
static unsigned long last_time = 0;
static unsigned long last_print_time = 0;
static float average_read_time = 0;
- #endif //DEBUG_HEADING_READING_TIME
+ #endif // DEBUG_HEADING_READING_TIME
+
+ #ifdef DEBUG_HH12
+ static unsigned long last_hh12_debug = 0;
+ #endif
#ifndef FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT
- if ((millis() - last_measurement_time) > AZIMUTH_MEASUREMENT_FREQUENCY_MS){
+ if (((millis() - last_measurement_time) > AZIMUTH_MEASUREMENT_FREQUENCY_MS) || (force_read)) {
#else
- if (1){
+ if (1) {
#endif
-
+
#ifdef FEATURE_AZ_POSITION_POTENTIOMETER
- // read analog input and convert it to degrees; this gets funky because of 450 degree rotation
- // Bearings: 180-------359-0--------270
- // Voltage: 0----------------------5
-
- analog_az = analogRead(rotator_analog_az);
- raw_azimuth = (map(analog_az, configuration.analog_az_full_ccw, configuration.analog_az_full_cw, (configuration.azimuth_starting_point*HEADING_MULTIPLIER), ((configuration.azimuth_starting_point + configuration.azimuth_rotation_capability)*HEADING_MULTIPLIER)));
+ analog_az = analogReadEnhanced(rotator_analog_az);
+ raw_azimuth = map(analog_az, configuration.analog_az_full_ccw, configuration.analog_az_full_cw, (azimuth_starting_point * HEADING_MULTIPLIER), ((azimuth_starting_point + azimuth_rotation_capability) * HEADING_MULTIPLIER));
+ //raw_azimuth = map(analog_az* HEADING_MULTIPLIER, configuration.analog_az_full_ccw* HEADING_MULTIPLIER, configuration.analog_az_full_cw* HEADING_MULTIPLIER, (azimuth_starting_point * HEADING_MULTIPLIER), ((azimuth_starting_point + azimuth_rotation_capability) * HEADING_MULTIPLIER));
+
#ifdef FEATURE_AZIMUTH_CORRECTION
- raw_azimuth = (correct_azimuth(raw_azimuth/HEADING_MULTIPLIER)*HEADING_MULTIPLIER);
- #endif //FEATURE_AZIMUTH_CORRECTION
+ raw_azimuth = (correct_azimuth(raw_azimuth / HEADING_MULTIPLIER) * HEADING_MULTIPLIER);
+ #endif // FEATURE_AZIMUTH_CORRECTION
+ raw_azimuth = raw_azimuth + (configuration.azimuth_offset * HEADING_MULTIPLIER);
if (AZIMUTH_SMOOTHING_FACTOR > 0) {
- raw_azimuth = (raw_azimuth*(1-(AZIMUTH_SMOOTHING_FACTOR/100))) + (previous_raw_azimuth*(AZIMUTH_SMOOTHING_FACTOR/100));
- }
+ raw_azimuth = (raw_azimuth * (1 - (AZIMUTH_SMOOTHING_FACTOR / 100.))) + (previous_raw_azimuth * (AZIMUTH_SMOOTHING_FACTOR / 100.));
+ }
if (raw_azimuth >= (360 * HEADING_MULTIPLIER)) {
azimuth = raw_azimuth - (360 * HEADING_MULTIPLIER);
- if (azimuth >= (360 * HEADING_MULTIPLIER)) {
- azimuth = azimuth - (360 * HEADING_MULTIPLIER);
- }
+ if (azimuth >= (360 * HEADING_MULTIPLIER)) {
+ azimuth = azimuth - (360 * HEADING_MULTIPLIER);
+ }
} else {
if (raw_azimuth < 0) {
azimuth = raw_azimuth + (360 * HEADING_MULTIPLIER);
@@ -3655,108 +4200,107 @@ void read_azimuth(){
azimuth = raw_azimuth;
}
}
- #endif //FEATURE_AZ_POSITION_POTENTIOMETER
-
+ #endif // FEATURE_AZ_POSITION_POTENTIOMETER
+
#ifdef FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT
+ #if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
static unsigned long last_remote_unit_az_query_time = 0;
-
-
-
// do we have a command result waiting for us?
if (remote_unit_command_results_available == REMOTE_UNIT_AZ_COMMAND) {
#ifdef DEBUG_HEADING_READING_TIME
- average_read_time = (average_read_time + (millis()-last_time))/2.0;
+ average_read_time = (average_read_time + (millis() - last_time)) / 2.0;
last_time = millis();
-
- if (debug_mode){
- if ((millis()-last_print_time) > 1000){
- Serial.print(F("read_azimuth: avg read frequency: "));
- Serial.println(average_read_time,2);
- last_print_time = millis();
+
+ if (debug_mode) {
+ if ((millis() - last_print_time) > 1000) {
+ debug_println("read_azimuth: avg read frequency: ");
+ debug_print_float(average_read_time, 2);
+ debug_println("");
+ last_print_time = millis();
}
}
- #endif //DEBUG_HEADING_READING_TIME
+ #endif // DEBUG_HEADING_READING_TIME
raw_azimuth = remote_unit_command_result_float * HEADING_MULTIPLIER;
-
+
+
#ifdef FEATURE_AZIMUTH_CORRECTION
- raw_azimuth = (correct_azimuth(raw_azimuth/HEADING_MULTIPLIER)*HEADING_MULTIPLIER);
- #endif //FEATURE_AZIMUTH_CORRECTION
-
+ raw_azimuth = (correct_azimuth(raw_azimuth / HEADING_MULTIPLIER) * HEADING_MULTIPLIER);
+ #endif // FEATURE_AZIMUTH_CORRECTION
+
+ raw_azimuth = raw_azimuth + (configuration.azimuth_offset * HEADING_MULTIPLIER);
+
if (AZIMUTH_SMOOTHING_FACTOR > 0) {
- raw_azimuth = (raw_azimuth*(1-(AZIMUTH_SMOOTHING_FACTOR/100))) + (previous_raw_azimuth*(AZIMUTH_SMOOTHING_FACTOR/100));
- }
+ raw_azimuth = (raw_azimuth * (1 - (AZIMUTH_SMOOTHING_FACTOR / 100))) + (previous_raw_azimuth * (AZIMUTH_SMOOTHING_FACTOR / 100));
+ }
if (raw_azimuth >= (360 * HEADING_MULTIPLIER)) {
azimuth = raw_azimuth - (360 * HEADING_MULTIPLIER);
- if (azimuth >= (360 * HEADING_MULTIPLIER)) {
- azimuth = azimuth - (360 * HEADING_MULTIPLIER);
- }
+ if (azimuth >= (360 * HEADING_MULTIPLIER)) {
+ azimuth = azimuth - (360 * HEADING_MULTIPLIER);
+ }
} else {
if (raw_azimuth < 0) {
azimuth = raw_azimuth + (360 * HEADING_MULTIPLIER);
} else {
azimuth = raw_azimuth;
}
- }
- remote_unit_command_results_available = 0;
+ }
+ remote_unit_command_results_available = 0;
} else {
-
// is it time to request the azimuth?
- if ((millis() - last_remote_unit_az_query_time) > AZ_REMOTE_UNIT_QUERY_TIME_MS){
- if (submit_remote_command(REMOTE_UNIT_AZ_COMMAND)) {
+ if ((millis() - last_remote_unit_az_query_time) > AZ_REMOTE_UNIT_QUERY_TIME_MS) {
+ if (submit_remote_command(REMOTE_UNIT_AZ_COMMAND, 0, 0)) {
last_remote_unit_az_query_time = millis();
}
}
-
}
-
-
- #endif //FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT
-
-
-
+ #endif // defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+ #endif // FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT
+
+
+
#ifdef FEATURE_AZ_POSITION_ROTARY_ENCODER
static byte az_position_encoder_state = 0;
-
- az_position_encoder_state = ttable[az_position_encoder_state & 0xf][((digitalRead(az_rotary_position_pin2) << 1) | digitalRead(az_rotary_position_pin1))];
+ az_position_encoder_state = ttable[az_position_encoder_state & 0xf][((digitalReadEnhanced(az_rotary_position_pin2) << 1) | digitalReadEnhanced(az_rotary_position_pin1))];
byte az_position_encoder_result = az_position_encoder_state & 0x30;
if (az_position_encoder_result) {
if (az_position_encoder_result == DIR_CW) {
configuration.last_azimuth = configuration.last_azimuth + AZ_POSITION_ROTARY_ENCODER_DEG_PER_PULSE;
#ifdef DEBUG_POSITION_ROTARY_ENCODER
- if (debug_mode){Serial.println(F("read_azimuth: AZ_POSITION_ROTARY_ENCODER: CW"));}
- #endif //DEBUG_POSITION_ROTARY_ENCODER
+ debug_println("read_azimuth: AZ_POSITION_ROTARY_ENCODER: CW");
+ #endif // DEBUG_POSITION_ROTARY_ENCODER
}
if (az_position_encoder_result == DIR_CCW) {
configuration.last_azimuth = configuration.last_azimuth - AZ_POSITION_ROTARY_ENCODER_DEG_PER_PULSE;
#ifdef DEBUG_POSITION_ROTARY_ENCODER
- if (debug_mode){Serial.println(F("read_azimuth: AZ_POSITION_ROTARY_ENCODER: CCW"));}
- #endif //DEBUG_POSITION_ROTARY_ENCODER
+ debug_println("read_azimuth: AZ_POSITION_ROTARY_ENCODER: CCW");
+ #endif // DEBUG_POSITION_ROTARY_ENCODER
}
-
+
#ifdef OPTION_AZ_POSITION_ROTARY_ENCODER_HARD_LIMIT
- if (configuration.last_azimuth < configuration.azimuth_starting_point){
- configuration.last_azimuth = configuration.azimuth_starting_point;
+ if (configuration.last_azimuth < azimuth_starting_point) {
+ configuration.last_azimuth = azimuth_starting_point;
+ }
+ if (configuration.last_azimuth > (azimuth_starting_point + azimuth_rotation_capability)) {
+ configuration.last_azimuth = (azimuth_starting_point + azimuth_rotation_capability);
}
- if (configuration.last_azimuth > (configuration.azimuth_starting_point + configuration.azimuth_rotation_capability)){
- configuration.last_azimuth = (configuration.azimuth_starting_point + configuration.azimuth_rotation_capability);
- }
#else
- if (configuration.last_azimuth < 0){
+ if (configuration.last_azimuth < 0) {
configuration.last_azimuth += 360;
}
- if (configuration.last_azimuth >= 360){
+ if (configuration.last_azimuth >= 360) {
configuration.last_azimuth -= 360;
- }
- #endif //OPTION_AZ_POSITION_ROTARY_ENCODER_HARD_LIMIT
-
-
+ }
+ #endif // OPTION_AZ_POSITION_ROTARY_ENCODER_HARD_LIMIT
+
+
raw_azimuth = int(configuration.last_azimuth * HEADING_MULTIPLIER);
-
+
+
#ifdef FEATURE_AZIMUTH_CORRECTION
- raw_azimuth = (correct_azimuth(raw_azimuth/HEADING_MULTIPLIER)*HEADING_MULTIPLIER);
- #endif //FEATURE_AZIMUTH_CORRECTION
-
+ raw_azimuth = (correct_azimuth(raw_azimuth / HEADING_MULTIPLIER) * HEADING_MULTIPLIER);
+ #endif // FEATURE_AZIMUTH_CORRECTION
+
if (raw_azimuth >= (360 * HEADING_MULTIPLIER)) {
azimuth = raw_azimuth - (360 * HEADING_MULTIPLIER);
} else {
@@ -3764,22 +4308,33 @@ void read_azimuth(){
}
configuration_dirty = 1;
}
- #endif //FEATURE_AZ_POSITION_ROTARY_ENCODER
-
+ #endif // FEATURE_AZ_POSITION_ROTARY_ENCODER
+
#ifdef FEATURE_AZ_POSITION_HMC5883L
- MagnetometerScaled scaled = compass.ReadScaledAxis(); //scaled values from compass.
+ MagnetometerScaled scaled = compass.ReadScaledAxis(); // scaled values from compass.
+
+ #ifdef DEBUG_HMC5883L
+ debug_print("read_azimuth: HMC5883L x:");
+ debug_print_float(scaled.XAxis,4);
+ debug_print(" y:");
+ debug_print_float(scaled.YAxis,4);
+ debug_println("");
+ #endif //DEBUG_HMC5883L
+
+
float heading = atan2(scaled.YAxis, scaled.XAxis);
// heading += declinationAngle;
// Correct for when signs are reversed.
- if(heading < 0) heading += 2*PI;
- if(heading > 2*PI) heading -= 2*PI;
- raw_azimuth = (heading * RAD_TO_DEG) * HEADING_MULTIPLIER; //radians to degree
+ if (heading < 0) heading += 2 * PI;
+ if (heading > 2 * PI) heading -= 2 * PI;
+ raw_azimuth = (heading * RAD_TO_DEG) * HEADING_MULTIPLIER; // radians to degree
if (AZIMUTH_SMOOTHING_FACTOR > 0) {
- raw_azimuth = (raw_azimuth*(1-(AZIMUTH_SMOOTHING_FACTOR/100))) + (previous_raw_azimuth*(AZIMUTH_SMOOTHING_FACTOR/100));
- }
+ raw_azimuth = (raw_azimuth * (1 - (AZIMUTH_SMOOTHING_FACTOR / 100))) + (previous_raw_azimuth * (AZIMUTH_SMOOTHING_FACTOR / 100));
+ }
#ifdef FEATURE_AZIMUTH_CORRECTION
- raw_azimuth = (correct_azimuth(raw_azimuth/HEADING_MULTIPLIER)*HEADING_MULTIPLIER);
- #endif //FEATURE_AZIMUTH_CORRECTION
+ raw_azimuth = (correct_azimuth(raw_azimuth / HEADING_MULTIPLIER) * HEADING_MULTIPLIER);
+ #endif // FEATURE_AZIMUTH_CORRECTION
+ raw_azimuth = raw_azimuth + (configuration.azimuth_offset * HEADING_MULTIPLIER);
azimuth = raw_azimuth;
#endif // FEATURE_AZ_POSITION_HMC5883L
@@ -3789,2333 +4344,3345 @@ void read_azimuth(){
#ifdef FEATURE_AZ_POSITION_LSM303
lsm.read();
- float heading = atan2(lsm.magData.y,lsm.magData.x);
+ float heading = atan2(lsm.magData.y, lsm.magData.x);
// heading += declinationAngle;
// Correct for when signs are reversed.
- if(heading < 0) heading += 2*PI;
- if(heading > 2*PI) heading -= 2*PI;
- raw_azimuth = (heading * RAD_TO_DEG) * HEADING_MULTIPLIER; //radians to degree
- if (AZIMUTH_SMOOTHING_FACTOR > 0) {
- raw_azimuth = (raw_azimuth*(1-(AZIMUTH_SMOOTHING_FACTOR/100))) + (previous_raw_azimuth*(AZIMUTH_SMOOTHING_FACTOR/100));
- }
+ if (heading < 0) heading += 2 * PI;
+ if (heading > 2 * PI) heading -= 2 * PI;
+ raw_azimuth = (heading * RAD_TO_DEG) * HEADING_MULTIPLIER; // radians to degree
#ifdef FEATURE_AZIMUTH_CORRECTION
- raw_azimuth = (correct_azimuth(raw_azimuth/HEADING_MULTIPLIER)*HEADING_MULTIPLIER);
- #endif //FEATURE_AZIMUTH_CORRECTION
+ raw_azimuth = (correct_azimuth(raw_azimuth / HEADING_MULTIPLIER) * HEADING_MULTIPLIER);
+ #endif // FEATURE_AZIMUTH_CORRECTION
+ raw_azimuth = raw_azimuth + (configuration.azimuth_offset * HEADING_MULTIPLIER);
+ if (AZIMUTH_SMOOTHING_FACTOR > 0) {
+ raw_azimuth = (raw_azimuth * (1 - (AZIMUTH_SMOOTHING_FACTOR / 100))) + (previous_raw_azimuth * (AZIMUTH_SMOOTHING_FACTOR / 100));
+ }
azimuth = raw_azimuth;
#endif // FEATURE_AZ_POSITION_LSM303
-
+
#ifdef FEATURE_AZ_POSITION_PULSE_INPUT
#ifdef DEBUG_POSITION_PULSE_INPUT
// if (az_position_pule_interrupt_handler_flag) {
-// Serial.print(F("read_azimuth: az_position_pusle_interrupt_handler_flag: "));
-// Serial.println(az_position_pule_interrupt_handler_flag);
+// control_port->print(F("read_azimuth: az_position_pusle_interrupt_handler_flag: "));
+// control_port->println(az_position_pule_interrupt_handler_flag);
// az_position_pule_interrupt_handler_flag = 0;
// }
- #endif //DEBUG_POSITION_PULSE_INPUT
-
- //dddd
-
+ #endif // DEBUG_POSITION_PULSE_INPUT
static float last_az_position_pulse_input_azimuth = az_position_pulse_input_azimuth;
-
- if (az_position_pulse_input_azimuth != last_az_position_pulse_input_azimuth){
- #ifdef DEBUG_POSITION_PULSE_INPUT
+ if (az_position_pulse_input_azimuth != last_az_position_pulse_input_azimuth) {
+ #ifdef DEBUG_POSITION_PULSE_INPUT
// if (debug_mode){
-// Serial.print(F("read_azimuth: last_az_position_pulse_input_azimuth:"));
-// Serial.print(last_az_position_pulse_input_azimuth);
-// Serial.print(F(" az_position_pulse_input_azimuth:"));
-// Serial.print(az_position_pulse_input_azimuth);
-// Serial.print(F(" az_pulse_counter:"));
-// Serial.println(az_pulse_counter);
-// }
- #endif //DEBUG_POSITION_PULSE_INPUT
- configuration.last_azimuth = az_position_pulse_input_azimuth;
- configuration_dirty = 1;
- last_az_position_pulse_input_azimuth = az_position_pulse_input_azimuth;
- raw_azimuth = int(configuration.last_azimuth * HEADING_MULTIPLIER);
- #ifdef FEATURE_AZIMUTH_CORRECTION
- raw_azimuth = (correct_azimuth(raw_azimuth/HEADING_MULTIPLIER)*HEADING_MULTIPLIER);
- #endif //FEATURE_AZIMUTH_CORRECTION
- if (raw_azimuth >= (360 * HEADING_MULTIPLIER)) {
- azimuth = raw_azimuth - (360 * HEADING_MULTIPLIER);
- } else {
+// control_port->print(F("read_azimuth: last_az_position_pulse_input_azimuth:"));
+// control_port->print(last_az_position_pulse_input_azimuth);
+// control_port->print(F(" az_position_pulse_input_azimuth:"));
+// control_port->print(az_position_pulse_input_azimuth);
+// control_port->print(F(" az_pulse_counter:"));
+// control_port->println(az_pulse_counter);
+// }
+ #endif // DEBUG_POSITION_PULSE_INPUT
+ configuration.last_azimuth = az_position_pulse_input_azimuth;
+ configuration_dirty = 1;
+ last_az_position_pulse_input_azimuth = az_position_pulse_input_azimuth;
+ raw_azimuth = int(configuration.last_azimuth * HEADING_MULTIPLIER);
+ #ifdef FEATURE_AZIMUTH_CORRECTION
+ raw_azimuth = (correct_azimuth(raw_azimuth / HEADING_MULTIPLIER) * HEADING_MULTIPLIER);
+ #endif // FEATURE_AZIMUTH_CORRECTION
+ raw_azimuth = raw_azimuth + (configuration.azimuth_offset * HEADING_MULTIPLIER);
+ if (raw_azimuth >= (360 * HEADING_MULTIPLIER)) {
+ azimuth = raw_azimuth - (360 * HEADING_MULTIPLIER);
+ } else {
azimuth = raw_azimuth;
- }
+ }
}
- #endif //FEATURE_AZ_POSITION_PULSE_INPUT
-
+ #endif // FEATURE_AZ_POSITION_PULSE_INPUT
+
+ #ifdef FEATURE_AZ_POSITION_HH12_AS5045_SSI
+ raw_azimuth = int(azimuth_hh12.heading() * HEADING_MULTIPLIER);
+ #ifdef DEBUG_HH12
+ if ((millis() - last_hh12_debug) > 5000) {
+ control_port->print(F("read_azimuth: HH-12 raw: "));
+ control_port->println(raw_azimuth);
+ last_hh12_debug = millis();
+ }
+ #endif // DEBUG_HH12
+ #ifdef FEATURE_AZIMUTH_CORRECTION
+ raw_azimuth = (correct_azimuth(raw_azimuth / HEADING_MULTIPLIER) * HEADING_MULTIPLIER);
+ #endif // FEATURE_AZIMUTH_CORRECTION
+ raw_azimuth = raw_azimuth + (configuration.azimuth_offset * HEADING_MULTIPLIER);
+ azimuth = raw_azimuth;
+ #endif // FEATURE_AZ_POSITION_HH12_AS5045_SSI
+
+ #ifdef FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
+ if (AZIMUTH_STARTING_POINT_DEFAULT == 0) {
+ raw_azimuth = (((((az_incremental_encoder_position) / (AZ_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.)) * 360.0)) * HEADING_MULTIPLIER);
+ } else {
+ if (az_incremental_encoder_position > (AZ_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.)) {
+ raw_azimuth = (((((az_incremental_encoder_position - (AZ_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.)) / (AZ_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.)) * 360.0)) * HEADING_MULTIPLIER);
+ } else {
+ raw_azimuth = (((((az_incremental_encoder_position + (AZ_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.)) / (AZ_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.)) * 360.0)) * HEADING_MULTIPLIER);
+ }
+ }
+ #ifdef FEATURE_AZIMUTH_CORRECTION
+ raw_azimuth = (correct_azimuth(raw_azimuth / HEADING_MULTIPLIER) * HEADING_MULTIPLIER);
+ #endif // FEATURE_AZIMUTH_CORRECTION
+ raw_azimuth = raw_azimuth + (configuration.azimuth_offset * HEADING_MULTIPLIER);
+ if (raw_azimuth >= (360 * HEADING_MULTIPLIER)) {
+ azimuth = raw_azimuth - (360 * HEADING_MULTIPLIER);
+ } else {
+ azimuth = raw_azimuth;
+ }
+ if (raw_azimuth != incremental_encoder_previous_raw_azimuth) {
+ configuration.last_az_incremental_encoder_position = az_incremental_encoder_position;
+ configuration_dirty = 1;
+ incremental_encoder_previous_raw_azimuth = raw_azimuth;
+ }
+ #endif // FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
+
+
+
+
last_measurement_time = millis();
}
-
-}
-//--------------------------------------------------------------
+} /* read_azimuth */
+
+// --------------------------------------------------------------
+
+void output_debug(){
+
+ #ifdef DEBUG_DUMP
+
+ char tempstring[32] = "";
+
+ #if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
-void output_debug()
-{
-
-
if (((millis() - last_debug_output_time) >= 3000) && (debug_mode)) {
- Serial.flush();
- Serial.print("debug: \t");
- Serial.print(CODE_VERSION);
- Serial.print("\t\t");
- Serial.print(millis()/1000);
- Serial.print("\t\t");
+
+ #ifdef DEBUG_GPS_SERIAL
+ debug_println("");
+ #endif //DEBUG_GPS_SERIAL
+
+ //port_flush();
+
+ debug_print("debug: \t");
+ debug_print(CODE_VERSION);
+ debug_print("\t\t");
+
+ #ifdef FEATURE_CLOCK
+ update_time();
+ sprintf(tempstring, "%s", clock_string());
+ debug_print(tempstring);
+ #else // FEATURE_CLOCK
+ dtostrf((millis() / 1000),0,0,tempstring);
+ debug_print(tempstring);
+ #endif // FEATURE_CLOCK
+
+ #if defined(FEATURE_GPS) || defined(FEATURE_RTC) || (defined(FEATURE_CLOCK) && defined(OPTION_SYNC_MASTER_CLOCK_TO_SLAVE))
+ debug_print("\t");
+ debug_print(clock_status_string());
+ #endif // defined(FEATURE_GPS) || defined(FEATURE_RTC) || (defined(FEATURE_CLOCK) && defined(OPTION_SYNC_MASTER_CLOCK_TO_SLAVE))
+
+ #if defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)
+ debug_print("\t");
+ sprintf(tempstring, "%s", coordinate_string());
+ debug_print(tempstring);
+ debug_print(" ");
+ debug_print(coordinates_to_maidenhead(latitude,longitude));
+ #endif
+
+ debug_print("\t\t");
#ifdef DEBUG_MEMORY
- void* HP = malloc(4);
- if (HP) {
- free (HP);
- }
+ void * HP = malloc(4);
+ if (HP) {free(HP);}
unsigned long free = (unsigned long)SP - (unsigned long)HP;
-// if (free > 2048) {
-// free = 0;
-// }
- Serial.print((unsigned long)free,DEC);
- Serial.print(F("b free"));
- #endif
-
+ sprintf(tempstring,"%lu",(unsigned long)free);
+ debug_print(tempstring);
+ debug_print("b free");
+ #endif //DEBUG_MEMORY
+
#ifdef FEATURE_YAESU_EMULATION
- Serial.print(F("\t\tGS-232"));
+ debug_print("\t\tGS-232");
#ifdef OPTION_GS_232B_EMULATION
- Serial.print(F("B"));
+ debug_print("B");
+ #else
+ debug_print("A");
#endif
- #ifndef OPTION_GS_232B_EMULATION
- Serial.print(F("A"));
- #endif
- #endif //FEATURE_YAESU_EMULATIO
+ #endif // FEATURE_YAESU_EMULATION
- Serial.println();
-
- Serial.print(F("\tAZ: "));
+ #ifdef FEATURE_PARK
+ switch (park_status) {
+ case NOT_PARKED: debug_print("\tNOT_PARKED"); break;
+ case PARK_INITIATED: debug_print("\tPARK_INITIATED"); break;
+ case PARKED: debug_print("\tPARKED"); break;
+ }
+ #endif // FEATURE_PARK
+
+
+ debug_print("\n");
+
+ debug_print("\tAZ: ");
switch (az_state) {
- case IDLE: Serial.print(F("IDLE")); break;
- case SLOW_START_CW: Serial.print(F("SLOW_START_CW")); break;
- case SLOW_START_CCW: Serial.print(F("SLOW_START_CCW")); break;
- case NORMAL_CW: Serial.print(F("NORMAL_CW")); break;
- case NORMAL_CCW: Serial.print(F("NORMAL_CCW")); break;
- case SLOW_DOWN_CW: Serial.print(F("SLOW_DOWN_CW")); break;
- case SLOW_DOWN_CCW: Serial.print(F("SLOW_DOWN_CCW")); break;
- case INITIALIZE_SLOW_START_CW: Serial.print(F("INITIALIZE_SLOW_START_CW")); break;
- case INITIALIZE_SLOW_START_CCW: Serial.print(F("INITIALIZE_SLOW_START_CCW")); break;
- case INITIALIZE_TIMED_SLOW_DOWN_CW: Serial.print(F("INITIALIZE_TIMED_SLOW_DOWN_CW")); break;
- case INITIALIZE_TIMED_SLOW_DOWN_CCW: Serial.print(F("INITIALIZE_TIMED_SLOW_DOWN_CCW")); break;
- case TIMED_SLOW_DOWN_CW: Serial.print(F("TIMED_SLOW_DOWN_CW")); break;
- case TIMED_SLOW_DOWN_CCW: Serial.print(F("TIMED_SLOW_DOWN_CCW")); break;
+ case IDLE: debug_print("IDLE"); break;
+ #ifndef HARDWARE_EA4TX_ARS_USB
+ case SLOW_START_CW: debug_print("SLOW_START_CW"); break;
+ case SLOW_START_CCW: debug_print("SLOW_START_CCW"); break;
+ #endif //ifndef HARDWARE_EA4TX_ARS_USB
+ case NORMAL_CW: debug_print("NORMAL_CW"); break;
+ case NORMAL_CCW: debug_print("NORMAL_CCW"); break;
+ #ifndef HARDWARE_EA4TX_ARS_USB
+ case SLOW_DOWN_CW: debug_print("SLOW_DOWN_CW"); break;
+ case SLOW_DOWN_CCW: debug_print("SLOW_DOWN_CCW"); break;
+ case INITIALIZE_SLOW_START_CW: debug_print("INITIALIZE_SLOW_START_CW"); break;
+ case INITIALIZE_SLOW_START_CCW: debug_print("INITIALIZE_SLOW_START_CCW"); break;
+ case INITIALIZE_TIMED_SLOW_DOWN_CW: debug_print("INITIALIZE_TIMED_SLOW_DOWN_CW"); break;
+ case INITIALIZE_TIMED_SLOW_DOWN_CCW: debug_print("INITIALIZE_TIMED_SLOW_DOWN_CCW"); break;
+ case TIMED_SLOW_DOWN_CW: debug_print("TIMED_SLOW_DOWN_CW"); break;
+ case TIMED_SLOW_DOWN_CCW: debug_print("TIMED_SLOW_DOWN_CCW"); break;
+ case INITIALIZE_DIR_CHANGE_TO_CW: debug_print("INITIALIZE_DIR_CHANGE_TO_CW"); break;
+ case INITIALIZE_DIR_CHANGE_TO_CCW: debug_print("INITIALIZE_DIR_CHANGE_TO_CCW"); break;
+ case INITIALIZE_NORMAL_CW: debug_print("INITIALIZE_NORMAL_CW"); break;
+ case INITIALIZE_NORMAL_CCW: debug_print("INITIALIZE_NORMAL_CCW"); break;
+ #endif //ifndef HARDWARE_EA4TX_ARS_USB
}
-
- Serial.print(F("\tQ: "));
- switch(az_request_queue_state){
- case NONE: Serial.print(F("-")); break;
- case IN_QUEUE: Serial.print(F("IN_QUEUE")); break;
- case IN_PROGRESS_TIMED: Serial.print(F("IN_PROGRESS_TIMED")); break;
- case IN_PROGRESS_TO_TARGET: Serial.print(F("IN_PROGRESS_TO_TARGET")); break;
+
+ debug_print("\tQ: ");
+ switch (az_request_queue_state) {
+ case NONE: debug_print("-"); break;
+ case IN_QUEUE: debug_print("IN_QUEUE"); break;
+ case IN_PROGRESS_TIMED: debug_print("IN_PROGRESS_TIMED"); break;
+ case IN_PROGRESS_TO_TARGET: debug_print("IN_PROGRESS_TO_TARGET"); break;
}
-
- Serial.print(F("\tAZ: "));
- Serial.print(azimuth/LCD_HEADING_MULTIPLIER,LCD_DECIMAL_PLACES);
- Serial.print(F(" (raw: "));
- Serial.print(raw_azimuth/LCD_HEADING_MULTIPLIER,LCD_DECIMAL_PLACES);
- Serial.print(")");
-
-
- Serial.print(F("\tTarget: "));
- Serial.print(target_azimuth/LCD_HEADING_MULTIPLIER,LCD_DECIMAL_PLACES);
-
- Serial.print(F(" (raw: "));
- Serial.print(target_raw_azimuth/LCD_HEADING_MULTIPLIER,LCD_DECIMAL_PLACES);
- Serial.print(")");
+ debug_print(" AZ: ");
+ debug_print_float((azimuth / LCD_HEADING_MULTIPLIER), LCD_DECIMAL_PLACES);
+ debug_print(" (raw: ");
+ debug_print_float((raw_azimuth / LCD_HEADING_MULTIPLIER), LCD_DECIMAL_PLACES);
+ debug_print(")");
+
+
+ if (az_state != IDLE) {
+ debug_print(" Target: ");
+ debug_print_float((target_azimuth / LCD_HEADING_MULTIPLIER), LCD_DECIMAL_PLACES);
+
+
+ debug_print(" (raw: ");
+
+ debug_print_float((target_raw_azimuth / LCD_HEADING_MULTIPLIER), LCD_DECIMAL_PLACES);
+ debug_print(")");
+
+ debug_print(" Secs_left: ");
+ debug_print_int((OPERATION_TIMEOUT - (millis() - az_last_rotate_initiation)) / 1000);
+ }
-
#ifdef FEATURE_AZ_POSITION_POTENTIOMETER
- Serial.print(F("\tAnalog: "));
- Serial.println(analog_az);
- #endif //FEATURE_AZ_POSITION_POTENTIOMETER
-
- //if (azimuth_speed_voltage) {
- Serial.print(F("\tAZ Speed Norm: "));
- Serial.print(normal_az_speed_voltage, DEC);
- //}
-
- Serial.print(F(" Current: "));
- Serial.print(current_az_speed_voltage,DEC);
-
+ debug_print(" Analog: ");
+ dtostrf(analog_az,0,0,tempstring);
+ debug_print(tempstring);
+ debug_print(" (");
+ dtostrf(configuration.analog_az_full_ccw,0,0,tempstring);
+ debug_print(tempstring);
+ debug_print("-");
+ dtostrf(configuration.analog_az_full_cw,0,0,tempstring);
+ debug_print(tempstring);
+ debug_print(") ");
+ #endif // FEATURE_AZ_POSITION_POTENTIOMETER
+
+ debug_print("\t[");
+ debug_print_int(azimuth_starting_point);
+ debug_print("+");
+ debug_print_int(azimuth_rotation_capability);
+ debug_print("]");
+
+ #ifndef HARDWARE_EA4TX_ARS_USB
+ debug_print(" AZ Speed Norm: ");
+ debug_print_int(normal_az_speed_voltage);
+
+ debug_print(" Current: ");
+ debug_print_int(current_az_speed_voltage);
+
+
if (az_speed_pot) {
- Serial.print(F("\tAZ Speed Pot: "));
- Serial.print(analogRead(az_speed_pot));
- }
- if (az_preset_pot) {
- Serial.print(F("\tAZ Preset Pot Analog: "));
- Serial.print(analogRead(az_preset_pot));
- Serial.print(F("\tAZ Preset Pot Setting: "));
- Serial.print(map(analogRead(az_preset_pot), AZ_PRESET_POT_FULL_CW, AZ_PRESET_POT_FULL_CCW, AZ_PRESET_POT_FULL_CW_MAP, AZ_PRESET_POT_FULL_CCW_MAP));
+ debug_print(" AZ Speed Pot: ");
+ debug_print_int(analogReadEnhanced(az_speed_pot));
}
-
-
- Serial.println();
+ if (az_preset_pot) {
+ debug_print(" AZ Preset Pot Analog: ");
+ debug_print_int(analogReadEnhanced(az_preset_pot));
+ debug_print(" AZ Preset Pot Setting: ");
+ dtostrf((map(analogReadEnhanced(az_preset_pot), AZ_PRESET_POT_FULL_CW, AZ_PRESET_POT_FULL_CCW, AZ_PRESET_POT_FULL_CW_MAP, AZ_PRESET_POT_FULL_CCW_MAP)),0,0,tempstring);
+ debug_print(tempstring);
+ }
+
+ debug_print("\tOffset: ");
+ dtostrf(configuration.azimuth_offset,0,2,tempstring);
+ debug_print(tempstring);
+ #endif // ndef HARDWARE_EA4TX_ARS_USB
+ debug_println("");
+
#ifdef FEATURE_ELEVATION_CONTROL
- Serial.print(F("\tEL: "));
+ debug_print("\tEL: ");
switch (el_state) {
- case IDLE: Serial.print(F("IDLE")); break;
- case SLOW_START_UP: Serial.print(F("SLOW_START_UP")); break;
- case SLOW_START_DOWN: Serial.print(F("SLOW_START_DOWN")); break;
- case NORMAL_UP: Serial.print(F("NORMAL_UP")); break;
- case NORMAL_DOWN: Serial.print(F("NORMAL_DOWN")); break;
- case SLOW_DOWN_DOWN: Serial.print(F("SLOW_DOWN_DOWN")); break;
- case SLOW_DOWN_UP: Serial.print(F("SLOW_DOWN_UP")); break;
- case TIMED_SLOW_DOWN_UP: Serial.print(F("TIMED_SLOW_DOWN_UP")); break;
- case TIMED_SLOW_DOWN_DOWN: Serial.print(F("TIMED_SLOW_DOWN_DOWN")); break;
- }
-
- Serial.print(F("\tQ: "));
- switch (el_request_queue_state) {
- case NONE: Serial.print(F("-")); break;
- case IN_QUEUE: Serial.print(F("IN_QUEUE")); break;
- case IN_PROGRESS_TIMED: Serial.print(F("IN_PROGRESS_TIMED")); break;
- case IN_PROGRESS_TO_TARGET: Serial.print(F("IN_PROGRESS_TO_TARGET")); break;
+ case IDLE: debug_print("IDLE"); break;
+ #ifndef HARDWARE_EA4TX_ARS_USB
+ case SLOW_START_UP: debug_print("SLOW_START_UP"); break;
+ case SLOW_START_DOWN: debug_print("SLOW_START_DOWN"); break;
+ #endif //ifndef HARDWARE_EA4TX_ARS_USB
+ case NORMAL_UP: debug_print("NORMAL_UP"); break;
+ case NORMAL_DOWN: debug_print("NORMAL_DOWN"); break;
+ #ifndef HARDWARE_EA4TX_ARS_USB
+ case SLOW_DOWN_DOWN: debug_print("SLOW_DOWN_DOWN"); break;
+ case SLOW_DOWN_UP: debug_print("SLOW_DOWN_UP"); break;
+ case TIMED_SLOW_DOWN_UP: debug_print("TIMED_SLOW_DOWN_UP"); break;
+ case TIMED_SLOW_DOWN_DOWN: debug_print("TIMED_SLOW_DOWN_DOWN"); break;
+ #endif //ifndef HARDWARE_EA4TX_ARS_USB
}
+
+ debug_print("\tQ: ");
+ switch (el_request_queue_state) {
+ case NONE: debug_print("-"); break;
+ case IN_QUEUE: debug_print("IN_QUEUE"); break;
+ case IN_PROGRESS_TIMED: debug_print("IN_PROGRESS_TIMED"); break;
+ case IN_PROGRESS_TO_TARGET: debug_print("IN_PROGRESS_TO_TARGET"); break;
+ }
+ debug_print(" EL: ");
+ dtostrf(elevation / LCD_HEADING_MULTIPLIER, 0, LCD_DECIMAL_PLACES,tempstring);
+ debug_print(tempstring);
+ if (el_state != IDLE) {
+ debug_print("\tTarget: ");
+ dtostrf(target_elevation / LCD_HEADING_MULTIPLIER, 0, LCD_DECIMAL_PLACES,tempstring);
+ debug_print(tempstring);
+ }
+
#ifdef FEATURE_EL_POSITION_POTENTIOMETER
- Serial.print(F("\tEL Analog: "));
- Serial.print(analog_el);
- #endif //FEATURE_EL_POSITION_POTENTIOMETER
- Serial.print(F("\tEL: "));
- Serial.print(elevation/LCD_HEADING_MULTIPLIER,LCD_DECIMAL_PLACES);
- Serial.print(F("\tTarget: "));
- Serial.println(target_elevation/LCD_HEADING_MULTIPLIER,LCD_DECIMAL_PLACES);
- #endif //FEATURE_EL_POSITION_POTENTIOMETER
+ debug_print("\tEL Analog: ");
+ dtostrf(analog_el,0,0,tempstring);
+ debug_print(tempstring);
+ debug_print(" (");
+ dtostrf(configuration.analog_el_0_degrees,0,0,tempstring);
+ debug_print(tempstring);
+ debug_print("-");
+ dtostrf(configuration.analog_el_max_elevation,0,0,tempstring);
+ debug_print(tempstring);
+ debug_print(") ");
+ #endif // FEATURE_EL_POSITION_POTENTIOMETER
+
+ #ifndef HARDWARE_EA4TX_ARS_USB
+ debug_print(" EL Speed Norm: ");
+ debug_print_int(normal_el_speed_voltage);
+
+
+ debug_print(" Current: ");
+ debug_print_int(current_el_speed_voltage);
+
+ debug_print("\tOffset: ");
+ debug_print_float(configuration.elevation_offset, 2);
+ #endif //ifndef HARDWARE_EA4TX_ARS_USB
+ debug_println("");
+ #endif // FEATURE_ELEVATION_CONTROL
+
+ //port_flush();
#ifdef FEATURE_TIMED_BUFFER
if (timed_buffer_status != EMPTY) {
- Serial.print(F("\tTimed interval buff: "));
+ debug_print("\tTimed interval buff: ");
switch (timed_buffer_status) {
- //case EMPTY: Serial.print(F("EMPTY")); break;
- case LOADED_AZIMUTHS: Serial.print(F("LOADED_AZIMUTHS")); break;
- case RUNNING_AZIMUTHS: Serial.print(F("RUNNING_AZIMUTHS")); break;
+ // case EMPTY: debug_print("EMPTY"); break;
+ case LOADED_AZIMUTHS: debug_print("LOADED_AZIMUTHS"); break;
+ case RUNNING_AZIMUTHS: debug_print("RUNNING_AZIMUTHS"); break;
#ifdef FEATURE_ELEVATION_CONTROL
- case LOADED_AZIMUTHS_ELEVATIONS: Serial.print(F("LOADED_AZIMUTHS_ELEVATIONS")); break;
- case RUNNING_AZIMUTHS_ELEVATIONS: Serial.print(F("RUNNING_AZIMUTHS_ELEVATIONS")); break;
+ case LOADED_AZIMUTHS_ELEVATIONS: debug_print("LOADED_AZIMUTHS_ELEVATIONS"); break;
+ case RUNNING_AZIMUTHS_ELEVATIONS: debug_print("RUNNING_AZIMUTHS_ELEVATIONS"); break;
#endif
}
-
- Serial.print(F("\tInterval (secs): "));
- Serial.print(timed_buffer_interval_value_seconds,DEC);
- Serial.print(F("\tEntries: "));
- Serial.print(timed_buffer_number_entries_loaded,DEC);
- Serial.print(F("\tEntry ptr: "));
- Serial.print(timed_buffer_entry_pointer,DEC);
- Serial.print(F("\tSecs since last action: "));
- Serial.println((millis()-last_timed_buffer_action_time)/1000);
-
+
+ debug_print("\tInterval (secs): ");
+ debug_print_int(timed_buffer_interval_value_seconds);
+ debug_print("\tEntries: ");
+ debug_print_int(timed_buffer_number_entries_loaded);
+ debug_print("\tEntry ptr: ");
+ debug_print_int(timed_buffer_entry_pointer);
+ debug_print("\tSecs since last action: ");
+ debug_print_int((millis() - last_timed_buffer_action_time) / 1000);
+
if (timed_buffer_number_entries_loaded > 0) {
- for (int x = 0;x < timed_buffer_number_entries_loaded; x++) {
- Serial.print(x+1);
- Serial.print(F("\t:"));
- Serial.print(timed_buffer_azimuths[x]/HEADING_MULTIPLIER);
- #ifdef FEATURE_ELEVATION_CONTROL
- Serial.print(F("\t- "));
- Serial.print(timed_buffer_elevations[x]/HEADING_MULTIPLIER);
- #endif
- Serial.println();
+ for (int x = 0; x < timed_buffer_number_entries_loaded; x++) {
+ debug_print_int(x + 1);
+ debug_print("\t:");
+ debug_print_int(timed_buffer_azimuths[x] / HEADING_MULTIPLIER);
+ #ifdef FEATURE_ELEVATION_CONTROL
+ debug_print("\t- ");
+ debug_print_int(timed_buffer_elevations[x] / HEADING_MULTIPLIER);
+ #endif
+ debug_print("\n");
}
+ debug_println("");
}
- } //if (timed_buffer_status != EMPTY)
- #endif //FEATURE_TIMED_BUFFER
+ } // if (timed_buffer_status != EMPTY)
+ #endif // FEATURE_TIMED_BUFFER
+
+
+ #if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+ /*debug_print("\tRemote Slave: Command: ");
+ debug_print_int(remote_unit_command_submitted);*/
+ debug_print("\tRemote Slave: Good: ");
+ debug_print_float(remote_unit_good_results,0);
+ debug_print(" Bad: ");
+ debug_print_int(remote_unit_bad_results);
+ /*debug_print(" Index: ");
+ debug_print_int(remote_unit_port_buffer_index);*/
+ debug_print(" CmdTouts: ");
+ debug_print_int(remote_unit_command_timeouts);
+ debug_print(" BuffTouts: ");
+ debug_print_int(remote_unit_incoming_buffer_timeouts);
+ /*debug_print(" Result: ");
+ debug_print_float(remote_unit_command_result_float,2);*/
+ debug_println("");
+ #endif // defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+
+ #if defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+ debug_print("\tEthernet Slave TCP Link State: ");
+ switch(ethernetslavelinkclient0_state){
+ case ETHERNET_SLAVE_DISCONNECTED: debug_print("DIS");
+ case ETHERNET_SLAVE_CONNECTED: debug_print("CONNECTED");
+ }
+ debug_print(" Reconnects: ");
+ debug_print_int(ethernet_slave_reconnects);
+ debug_println("");
+ #endif // defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
- Serial.print(F("\tAZ: "));
- Serial.print(configuration.azimuth_starting_point);
- Serial.print(F("+"));
- Serial.print(configuration.azimuth_rotation_capability);
- Serial.print(F("\tAZ ana: "));
- Serial.print(configuration.analog_az_full_ccw);
- Serial.print(F("-"));
- Serial.print(configuration.analog_az_full_cw);
- #ifdef FEATURE_ELEVATION_CONTROL
- Serial.print(F("\tEL ana: "));
- Serial.print(configuration.analog_el_0_degrees);
- Serial.print(F("-"));
- Serial.print(configuration.analog_el_max_elevation);
- #endif
-
- #ifdef FEATURE_HOST_REMOTE_PROTOCOL
- Serial.print(F("\n\tRemote: Command: "));
- Serial.print(remote_unit_command_submitted);
- Serial.print(F(" Good: "));
- Serial.print(remote_unit_good_results);
- Serial.print(F(" Bad: "));
- Serial.print(remote_unit_bad_results);
- Serial.print(F(" Index: "));
- Serial.print(serial1_buffer_index);
- Serial.print(F(" CmdTouts: "));
- Serial.print(remote_unit_command_timeouts);
- Serial.print(F(" BuffTouts: "));
- Serial.print(remote_unit_incoming_buffer_timeouts);
- Serial.print(F(" Result: "));
- Serial.println(remote_unit_command_result_float);
- #endif //#FEATURE_HOST_REMOTE_PROTOCOL
-
#ifdef DEBUG_POSITION_PULSE_INPUT
- static unsigned long last_pulse_count_time = 0;
+ static unsigned long last_pulse_count_time = 0;
static unsigned long last_az_pulse_counter = 0;
static unsigned long last_el_pulse_counter = 0;
- Serial.print(F("\n\tPulse counters: AZ: "));
- Serial.print(az_pulse_counter);
- Serial.print(F(" AZ Ambiguous: "));
- Serial.print(az_pulse_counter_ambiguous);
- Serial.print(" EL: ");
- Serial.print(el_pulse_counter);
- Serial.print(F(" EL Ambiguous: "));
- Serial.print(el_pulse_counter_ambiguous);
- Serial.print(F(" Rate per sec: AZ: "));
- Serial.print((az_pulse_counter-last_az_pulse_counter)/((millis()-last_pulse_count_time)/1000.0));
- Serial.print(F(" EL: "));
- Serial.println((el_pulse_counter-last_el_pulse_counter)/((millis()-last_pulse_count_time)/1000.0));
+ debug_print("\tPulse counters: AZ: ");
+ debug_print_int(az_pulse_counter);
+ debug_print(" AZ Ambiguous: ");
+ debug_print_int(az_pulse_counter_ambiguous);
+ debug_print(" EL: ");
+ debug_print_int(el_pulse_counter);
+ debug_print(" EL Ambiguous: ");
+ debug_print_int(el_pulse_counter_ambiguous);
+ debug_print(" Rate per sec: AZ: ");
+ debug_print_float(((az_pulse_counter - last_az_pulse_counter) / ((millis() - last_pulse_count_time) / 1000.0)),2);
+ debug_print(" EL: ");
+ debug_print_float(((el_pulse_counter - last_el_pulse_counter) / ((millis() - last_pulse_count_time) / 1000.0)),2);
+ debug_println("");
last_az_pulse_counter = az_pulse_counter;
last_el_pulse_counter = el_pulse_counter;
last_pulse_count_time = millis();
- #endif //DEBUG_POSITION_PULSE_INPUT
-
- Serial.println(F("\n\n\n\n"));
-
- last_debug_output_time = millis();
-
- }
-
-}
-
-//--------------------------------------------------------------
+ #endif // DEBUG_POSITION_PULSE_INPUT
-void report_current_azimuth() {
-
- #ifdef FEATURE_YAESU_EMULATION
- // The C command that reports azimuth
-
- String azimuth_string;
-
- #ifndef OPTION_GS_232B_EMULATION
- Serial.print(F("+0"));
- #endif
- #ifdef OPTION_GS_232B_EMULATION
- Serial.print(F("AZ="));
- #endif
- //Serial.write("report_current_azimith: azimuth=");
- //Serial.println(azimuth);
- azimuth_string = String(int(azimuth/HEADING_MULTIPLIER), DEC);
- if (azimuth_string.length() == 1) {
- Serial.print(F("00"));
- } else {
- if (azimuth_string.length() == 2) {
- Serial.print(F("0"));
- }
- }
- Serial.print(azimuth_string);
-
- #ifdef FEATURE_ELEVATION_CONTROL
- #ifndef OPTION_C_COMMAND_SENDS_AZ_AND_EL
- if ((serial0_buffer[1] == '2') && (serial0_buffer_index > 1)) { // did we get the C2 command?
- #endif
- report_current_elevation();
- #ifndef OPTION_C_COMMAND_SENDS_AZ_AND_EL
- } else {
- Serial.println();
- }
- #endif //OPTION_C_COMMAND_SENDS_AZ_AND_EL
- #endif //FEATURE_ELEVATION_CONTROL
-
- #ifndef FEATURE_ELEVATION_CONTROL
- if ((serial0_buffer[1] == '2') && (serial0_buffer_index > 1)) { // did we get the C2 command?
- #ifndef OPTION_GS_232B_EMULATION
- Serial.println(F("+0000")); // return a dummy elevation since we don't have the elevation feature turned on
- #else
- Serial.println(F("EL=000"));
+ #if defined(FEATURE_AZ_POSITION_INCREMENTAL_ENCODER) && defined(DEBUG_AZ_POSITION_INCREMENTAL_ENCODER)
+ debug_print("\taz_position_incremental_encoder_interrupt: ");
+ debug_print_int(az_position_incremental_encoder_interrupt);
+ debug_print("\taz_incremental_encoder_position: ");
+ debug_print_int(az_incremental_encoder_position);
+ #endif // DEBUG_AZ_POSITION_INCREMENTAL_ENCODER
+ #if defined(FEATURE_EL_POSITION_INCREMENTAL_ENCODER) && defined(DEBUG_EL_POSITION_INCREMENTAL_ENCODER)
+ debug_print("\n\tel_position_incremental_encoder_interrupt: ");
+ debug_print_int(el_position_incremental_encoder_interrupt);
+ debug_print("\tel_incremental_encoder_position: ");
+ debug_print(el_incremental_encoder_position);
+ #endif // DEBUG_EL_POSITION_INCREMENTAL_ENCODER
+ #if (defined(FEATURE_AZ_POSITION_INCREMENTAL_ENCODER) && defined(DEBUG_AZ_POSITION_INCREMENTAL_ENCODER)) || (defined(FEATURE_EL_POSITION_INCREMENTAL_ENCODER) && defined(DEBUG_EL_POSITION_INCREMENTAL_ENCODER))
+ debug_println("");
#endif
- } else {
- Serial.println();
+
+
+
+
+ #ifdef FEATURE_MOON_TRACKING
+ update_moon_position();
+ debug_print(moon_status_string());
+ #endif // FEATURE_MOON_TRACKING
+
+ #ifdef FEATURE_SUN_TRACKING
+ update_sun_position();
+ debug_print(sun_status_string());
+ #endif // FEATURE_SUN_TRACKING
+
+ #if defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)
+ debug_println("");
+ #endif //defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)
+
+ #ifdef FEATURE_GPS
+ unsigned long gps_chars = 0;
+ unsigned short gps_good_sentences = 0;
+ unsigned short gps_failed_checksum = 0;
+ char gps_temp_string[12] = "";
+ float gps_lat_temp = 0;
+ float gps_long_temp = 0;
+
+ debug_print("\tGPS: satellites: ");
+ gps_chars = gps.satellites();
+ if (gps_chars == 255){gps_chars = 0;}
+ dtostrf(gps_chars,0,0,gps_temp_string);
+ debug_print(gps_temp_string);
+ unsigned long gps_fix_age_temp = 0;
+ gps.f_get_position(&gps_lat_temp,&gps_long_temp,&gps_fix_age_temp);
+ debug_print(" lat: ");
+ debug_print_float(gps_lat_temp,4);
+ debug_print(" long: ");
+ debug_print_float(gps_long_temp,4);
+ debug_print(" fix age (mS): ");
+ dtostrf(gps_fix_age_temp,0,0,gps_temp_string);
+ debug_print(gps_temp_string);
+ gps.stats(&gps_chars,&gps_good_sentences,&gps_failed_checksum);
+ debug_print(" data chars: ");
+ dtostrf(gps_chars,0,0,gps_temp_string);
+ debug_print(gps_temp_string);
+ debug_print(" good sentences: ");
+ dtostrf(gps_good_sentences,0,0,gps_temp_string);
+ debug_print(gps_temp_string);
+ debug_print(" failed checksum: ");
+ dtostrf(gps_failed_checksum,0,0,gps_temp_string);
+ debug_print(gps_temp_string);
+ debug_println("");
+ #endif //FEATURE_GPS
+
+
+
+ debug_println("\n\n\n");
+
+ //port_flush();
+
+ last_debug_output_time = millis();
+
+ #endif //DEBUG_DUMP
+
}
- #endif //FEATURE_ELEVATION_CONTROL
-
-
-
- #endif //FEATURE_YAESU_EMULATION
+ #endif // defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
+
+} /* output_debug */
+
+// --------------------------------------------------------------
+
+
+// void report_current_azimuth() {
+
+// #ifdef FEATURE_YAESU_EMULATION
+// // The C command that reports azimuth
+
+// String azimuth_string;
+
+// #ifndef OPTION_GS_232B_EMULATION
+// control_port->print(F("+0"));
+// #endif
+// #ifdef OPTION_GS_232B_EMULATION
+// control_port->print(F("AZ="));
+// #endif
+// // control_port->write("report_current_azimith: azimuth=");
+// // control_port->println(azimuth);
+// azimuth_string = String(int(azimuth / HEADING_MULTIPLIER), DEC);
+// if (azimuth_string.length() == 1) {
+// control_port->print(F("00"));
+// } else {
+// if (azimuth_string.length() == 2) {
+// control_port->print(F("0"));
+// }
+// }
+// control_port->print(azimuth_string);
+
+// #ifdef FEATURE_ELEVATION_CONTROL
+// #ifndef OPTION_C_COMMAND_SENDS_AZ_AND_EL
+// if ((control_port_buffer[1] == '2') && (control_port_buffer_index > 1)) { // did we get the C2 command?
+// #endif
+// report_current_elevation();
+// #ifndef OPTION_C_COMMAND_SENDS_AZ_AND_EL
+// } else {
+// control_port->println();
+// }
+// #endif // OPTION_C_COMMAND_SENDS_AZ_AND_EL
+// #endif // FEATURE_ELEVATION_CONTROL
+
+// #ifndef FEATURE_ELEVATION_CONTROL
+// if ((control_port_buffer[1] == '2') && (control_port_buffer_index > 1)) { // did we get the C2 command?
+// #ifndef OPTION_GS_232B_EMULATION
+// control_port->println(F("+0000")); // return a dummy elevation since we don't have the elevation feature turned on
+// #else
+// control_port->println(F("EL=000"));
+// #endif
+// } else {
+// control_port->println();
+// }
+// #endif // FEATURE_ELEVATION_CONTROL
+
+
+
+// #endif // FEATURE_YAESU_EMULATION
+// }
+
+
+// --------------------------------------------------------------
+void print_to_port(char * print_this,byte port){
+
+ switch(port){
+ case CONTROL_PORT0: control_port->println(print_this);break;
+ #ifdef FEATURE_ETHERNET
+ case ETHERNET_PORT0: ethernetclient0.print(print_this); break;
+ #ifdef ETHERNET_TCP_PORT_1
+ case ETHERNET_PORT1: ethernetclient1.print(print_this); break;
+ #endif //ETHERNET_TCP_PORT_1
+ #endif //FEATURE_ETHERNET
+ }
+
}
-//--------------------------------------------------------------
-
-void print_help(){
+// --------------------------------------------------------------
+void print_help(byte port){
// The H command
- #ifdef OPTION_SERIAL_HELP_TEXT
- #ifdef FEATURE_YAESU_EMULATION
- Serial.println(F("R Rotate Azimuth Clockwise"));
- Serial.println(F("L Rotate Azimuth Counter Clockwise"));
- Serial.println(F("A Stop"));
- Serial.println(F("C Report Azimuth in Degrees"));
- Serial.println(F("M### Rotate to ### degrees"));
- Serial.println(F("MTTT XXX XXX XXX ... Timed Interval Direction Setting (TTT = Step value in seconds, XXX = Azimuth in degrees)"));
- Serial.println(F("T Start Timed Interval Tracking"));
- Serial.println(F("N Report Total Number of M Timed Interval Azimuths"));
- Serial.println(F("X1 Horizontal Rotation Low Speed"));
- Serial.println(F("X2 Horizontal Rotation Middle 1 Speed"));
- Serial.println(F("X3 Horizontal Rotation Middle 2 Speed"));
- Serial.println(F("X4 Horizontal Rotation High Speed"));
- Serial.println(F("S Stop"));
- Serial.println(F("O Offset Calibration"));
- Serial.println(F("F Full Scale Calibration"));
+ #if defined(OPTION_SERIAL_HELP_TEXT) && defined(FEATURE_YAESU_EMULATION)
+ print_to_port("R Rotate Azimuth Clockwise\n",port);
+ print_to_port("L Rotate Azimuth Counter Clockwise\n",port);
+ print_to_port("A Stop\n",port);
+ print_to_port("C Report Azimuth in Degrees\n",port);
+ print_to_port("M### Rotate to ### degrees\n",port);
+ print_to_port("MTTT XXX XXX XXX ... Timed Interval Direction Setting (TTT = Step value in seconds, XXX = Azimuth in degrees)\n",port);
+ print_to_port("T Start Timed Interval Tracking\n",port);
+ print_to_port("N Report Total Number of M Timed Interval Azimuths\n",port);
+ print_to_port("X1 Horizontal Rotation Low Speed\n",port);
+ print_to_port("X2 Horizontal Rotation Middle 1 Speed\n",port);
+ print_to_port("X3 Horizontal Rotation Middle 2 Speed\n",port);
+ print_to_port("X4 Horizontal Rotation High Speed\n",port);
+ print_to_port("S Stop\n",port);
+ print_to_port("O Offset Calibration\n",port);
+ print_to_port("F Full Scale Calibration\n",port);
#ifdef FEATURE_ELEVATION_CONTROL
- Serial.println(F("U Rotate Elevation Up"));
- Serial.println(F("D Rotate Elevation Down"));
- Serial.println(F("E Stop Elevation Rotation"));
- Serial.println(F("B Report Elevation in Degrees"));
- Serial.println(F("Wxxx yyy Rotate Azimuth to xxx Degrees and Elevation to yyy Degrees\r\r"));
- Serial.println(F("O2 Elevation Offset Calibration (0 degrees)"));
- Serial.println(F("F2 Elevation Full Scale Calibration (180 degrees (or maximum))"));
- #endif //FEATURE_ELEVATION_CONTROL
- #endif //FEATURE_YAESU_EMULATION
- #endif //OPTION_SERIAL_HELP_TEXT
+ print_to_port("U Rotate Elevation Up\n",port);
+ print_to_port("D Rotate Elevation Down\n",port);
+ print_to_port("E Stop Elevation Rotation\n",port);
+ print_to_port("B Report Elevation in Degrees\n",port);
+ print_to_port("Wxxx yyy Rotate Azimuth to xxx Degrees and Elevation to yyy Degrees\n",port);
+ print_to_port("O2 Elevation Offset Calibration (0 degrees)\n",port);
+ print_to_port("F2 Elevation Full Scale Calibration (180 degrees (or maximum))\n",port);
+ #endif // FEATURE_ELEVATION_CONTROL
+ #endif // defined(OPTION_SERIAL_HELP_TEXT) && defined(FEATURE_YAESU_EMULATION)
-}
+} /* print_help */
-//--------------- Elevation -----------------------
+// --------------- Elevation -----------------------
#ifdef FEATURE_ELEVATION_CONTROL
-void el_check_operation_timeout()
-{
+void el_check_operation_timeout(){
// check if the last executed rotation operation has been going on too long
if (((millis() - el_last_rotate_initiation) > OPERATION_TIMEOUT) && (el_state != IDLE)) {
- submit_request(EL,REQUEST_KILL,0);
+ submit_request(EL, REQUEST_KILL, 0, 85);
#ifdef DEBUG_EL_CHECK_OPERATION_TIMEOUT
if (debug_mode) {
- Serial.println(F("el_check_operation_timeout: timeout reached, aborting rotation"));
+ control_port->println(F("el_check_operation_timeout: timeout reached, aborting rotation"));
}
- #endif //DEBUG_EL_CHECK_OPERATION_TIMEOUT
+ #endif // DEBUG_EL_CHECK_OPERATION_TIMEOUT
}
}
#endif
-//--------------------------------------------------------------
+// --------------------------------------------------------------
-//#ifdef FEATURE_ELEVATION_CONTROL
-#ifdef FEATURE_YAESU_EMULATION
-void yaesu_w_command ()
-{
- // parse out W command
- // Short Format: WXXX YYY = azimuth YYY = elevation
- // Long Format : WSSS XXX YYY SSS = timed interval XXX = azimuth YYY = elevation
-
- int parsed_elevation = 0;
- int parsed_azimuth = 0;
- //int parsed_value1 = 0;
- //int parsed_value2 = 0;
+// #ifdef FEATURE_YAESU_EMULATION
+// void yaesu_w_command(){
- if (serial0_buffer_index > 8) { // if there are more than 4 characters in the command buffer, we got a timed interval command
- #ifdef FEATURE_TIMED_BUFFER
- parsed_value1 = ((int(serial0_buffer[1])-48)*100) + ((int(serial0_buffer[2])-48)*10) + (int(serial0_buffer[3])-48);
- if ((parsed_value1 > 0) && (parsed_value1 < 1000)) {
- timed_buffer_interval_value_seconds = parsed_value1;
- for (int x = 5; x < serial0_buffer_index; x = x + 8) {
- parsed_value1 = ((int(serial0_buffer[x])-48)*100) + ((int(serial0_buffer[x+1])-48)*10) + (int(serial0_buffer[x+2])-48);
- parsed_value2 = ((int(serial0_buffer[x+4])-48)*100) + ((int(serial0_buffer[x+5])-48)*10) + (int(serial0_buffer[x+6])-48);
- if ((parsed_value1 > -1) && (parsed_value1 < 361) && (parsed_value2 > -1) && (parsed_value2 < 181)) { // is it a valid azimuth?
- timed_buffer_azimuths[timed_buffer_number_entries_loaded] = (parsed_value1 * HEADING_MULTIPLIER);
- timed_buffer_elevations[timed_buffer_number_entries_loaded] = (parsed_value2 * HEADING_MULTIPLIER);
- timed_buffer_number_entries_loaded++;
- timed_buffer_status = LOADED_AZIMUTHS_ELEVATIONS;
- if (timed_buffer_number_entries_loaded > TIMED_INTERVAL_ARRAY_SIZE) { // is the array full?
- x = serial0_buffer_index; // array is full, go to the first azimuth and elevation
+// // parse out W command
+// // Short Format: WXXX YYY = azimuth YYY = elevation
+// // Long Format : WSSS XXX YYY SSS = timed interval XXX = azimuth YYY = elevation
- }
- } else { // we hit an invalid bearing
- timed_buffer_status = EMPTY;
- timed_buffer_number_entries_loaded = 0;
- Serial.println(F("?>")); // error
- return;
- }
- }
- }
- timed_buffer_entry_pointer = 1; // go to the first bearings
- parsed_azimuth = timed_buffer_azimuths[0];
- parsed_elevation = timed_buffer_elevations[0];
- #else
- Serial.println(F("Feature not activated ?>"));
- #endif //FEATURE_TIMED_BUFFER
- } else {
- // this is a short form W command, just parse the azimuth and elevation and initiate rotation
- parsed_azimuth = (((int(serial0_buffer[1])-48)*100) + ((int(serial0_buffer[2])-48)*10) + (int(serial0_buffer[3])-48)) * HEADING_MULTIPLIER;
- parsed_elevation = (((int(serial0_buffer[5])-48)*100) + ((int(serial0_buffer[6])-48)*10) + (int(serial0_buffer[7])-48)) * HEADING_MULTIPLIER;
- }
+// int parsed_elevation = 0;
+// int parsed_azimuth = 0;
- if ((parsed_azimuth >= 0) && (parsed_azimuth <= (360*HEADING_MULTIPLIER))) {
- submit_request(AZ,REQUEST_AZIMUTH,parsed_azimuth);
- } else {
- #ifdef DEBUG_YAESU
- if (debug_mode) {Serial.println(F("yaesu_w_command: W command elevation error"));}
- #endif //DEBUG_YAESU
- Serial.println(F("?>")); // bogus elevation - return and error and don't do anything
- return;
- }
+// #ifdef FEATURE_TIMED_BUFFER
+// int parsed_value1 = 0;
+// int parsed_value2 = 0;
+// #endif //FEATURE_TIMED_BUFFER
- #ifdef FEATURE_ELEVATION_CONTROL
- if ((parsed_elevation >= 0) && (parsed_elevation <= (180 * HEADING_MULTIPLIER))) {
- submit_request(EL,REQUEST_ELEVATION,parsed_elevation);
- } else {
- #ifdef DEBUG_YAESU
- if (debug_mode) {Serial.println(F("yaesu_w_command: W command elevation error"));}
- #endif //DEBUG_YAESU
- Serial.println(F("?>")); // bogus elevation - return and error and don't do anything
- return;
- }
- #endif //FEATURE_ELEVATION_CONTROL
- Serial.println();
-
-}
-#endif //FEATURE_YAESU_EMULATION
-//#endif //FEATURE_ELEVATION_CONTROL
+// if (control_port_buffer_index > 8) { // if there are more than 4 characters in the command buffer, we got a timed interval command
+// #if defined(FEATURE_TIMED_BUFFER) && defined(FEATURE_ELEVATION_CONTROL)
+// parsed_value1 = ((int(control_port_buffer[1]) - 48) * 100) + ((int(control_port_buffer[2]) - 48) * 10) + (int(control_port_buffer[3]) - 48);
+// if ((parsed_value1 > 0) && (parsed_value1 < 1000)) {
+// timed_buffer_interval_value_seconds = parsed_value1;
+// for (int x = 5; x < control_port_buffer_index; x = x + 8) {
+// parsed_value1 = ((int(control_port_buffer[x]) - 48) * 100) + ((int(control_port_buffer[x + 1]) - 48) * 10) + (int(control_port_buffer[x + 2]) - 48);
+// parsed_value2 = ((int(control_port_buffer[x + 4]) - 48) * 100) + ((int(control_port_buffer[x + 5]) - 48) * 10) + (int(control_port_buffer[x + 6]) - 48);
+// if ((parsed_value1 > -1) && (parsed_value1 < 361) && (parsed_value2 > -1) && (parsed_value2 < 181)) { // is it a valid azimuth?
+// timed_buffer_azimuths[timed_buffer_number_entries_loaded] = (parsed_value1 * HEADING_MULTIPLIER);
+// timed_buffer_elevations[timed_buffer_number_entries_loaded] = (parsed_value2 * HEADING_MULTIPLIER);
+// timed_buffer_number_entries_loaded++;
+// timed_buffer_status = LOADED_AZIMUTHS_ELEVATIONS;
+// if (timed_buffer_number_entries_loaded > TIMED_INTERVAL_ARRAY_SIZE) { // is the array full?
+// x = control_port_buffer_index; // array is full, go to the first azimuth and elevation
-//--------------------------------------------------------------
+// }
+// } else { // we hit an invalid bearing
+// timed_buffer_status = EMPTY;
+// timed_buffer_number_entries_loaded = 0;
+// control_port->println(F("?>")); // error
+// return;
+// }
+// }
+// }
+// timed_buffer_entry_pointer = 1; // go to the first bearings
+// parsed_azimuth = timed_buffer_azimuths[0];
+// parsed_elevation = timed_buffer_elevations[0];
+// #else /* ifdef FEATURE_TIMED_BUFFER */
+// control_port->println(F("Feature not activated ?>"));
+// #endif // FEATURE_TIMED_BUFFER
+// } else {
+// // this is a short form W command, just parse the azimuth and elevation and initiate rotation
+// parsed_azimuth = (((int(control_port_buffer[1]) - 48) * 100) + ((int(control_port_buffer[2]) - 48) * 10) + (int(control_port_buffer[3]) - 48)) * HEADING_MULTIPLIER;
+// parsed_elevation = (((int(control_port_buffer[5]) - 48) * 100) + ((int(control_port_buffer[6]) - 48) * 10) + (int(control_port_buffer[7]) - 48)) * HEADING_MULTIPLIER;
+// }
+
+// if ((parsed_azimuth >= 0) && (parsed_azimuth <= (360 * HEADING_MULTIPLIER))) {
+// submit_request(AZ, REQUEST_AZIMUTH, parsed_azimuth);
+// } else {
+// #ifdef DEBUG_YAESU
+// if (debug_mode) {
+// control_port->println(F("yaesu_w_command: W command elevation error"));
+// }
+// #endif // DEBUG_YAESU
+// control_port->println(F("?>")); // bogus elevation - return and error and don't do anything
+// return;
+// }
+
+// #ifdef FEATURE_ELEVATION_CONTROL
+// if ((parsed_elevation >= 0) && (parsed_elevation <= (180 * HEADING_MULTIPLIER))) {
+// submit_request(EL, REQUEST_ELEVATION, parsed_elevation);
+// } else {
+// #ifdef DEBUG_YAESU
+// if (debug_mode) {
+// control_port->println(F("yaesu_w_command: W command elevation error"));
+// }
+// #endif // DEBUG_YAESU
+// control_port->println(F("?>")); // bogus elevation - return and error and don't do anything
+// return;
+// }
+// #endif // FEATURE_ELEVATION_CONTROL
+// control_port->println();
+
+// } /* yaesu_w_command */
+// #endif // FEATURE_YAESU_EMULATION
+
+
+// --------------------------------------------------------------
#ifdef FEATURE_ELEVATION_CONTROL
-void read_elevation()
-{
+void read_elevation(byte force_read){
// read analog input and convert it to degrees
unsigned int previous_elevation = elevation;
static unsigned long last_measurement_time = 0;
-
+
+ #ifdef FEATURE_EL_POSITION_INCREMENTAL_ENCODER
+ static unsigned int incremental_encoder_previous_elevation = elevation;
+ #endif
+
+ if (heading_reading_inhibit_pin) {
+ if (digitalReadEnhanced(heading_reading_inhibit_pin)) {
+ return;
+ }
+ }
+
#ifdef DEBUG_HEADING_READING_TIME
static unsigned long last_time = 0;
static unsigned long last_print_time = 0;
static float average_read_time = 0;
- #endif //DEBUG_HEADING_READING_TIME
-
+ #endif // DEBUG_HEADING_READING_TIME
+
+ #ifdef DEBUG_HH12
+ static unsigned long last_hh12_debug = 0;
+ #endif // DEBUG_HH12
+
#ifndef FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT
- if ((millis() - last_measurement_time) > ELEVATION_MEASUREMENT_FREQUENCY_MS){
+ if (((millis() - last_measurement_time) > ELEVATION_MEASUREMENT_FREQUENCY_MS) || (force_read)) {
#else
- if (1){
+ if (1) {
#endif
-
+
#ifdef FEATURE_EL_POSITION_POTENTIOMETER
- analog_el = analogRead(rotator_analog_el);
- elevation = (map(analog_el, configuration.analog_el_0_degrees, configuration.analog_el_max_elevation, 0, (ELEVATION_MAXIMUM_DEGREES* HEADING_MULTIPLIER))) ;
+ analog_el = analogReadEnhanced(rotator_analog_el);
+ elevation = (map(analog_el, configuration.analog_el_0_degrees, configuration.analog_el_max_elevation, 0, (ELEVATION_MAXIMUM_DEGREES * HEADING_MULTIPLIER)));
#ifdef FEATURE_ELEVATION_CORRECTION
- elevation = (correct_elevation(elevation/HEADING_MULTIPLIER)*HEADING_MULTIPLIER);
- #endif //FEATURE_ELEVATION_CORRECTION
+ elevation = (correct_elevation(elevation / HEADING_MULTIPLIER) * HEADING_MULTIPLIER);
+ #endif // FEATURE_ELEVATION_CORRECTION
+ elevation = elevation + (configuration.elevation_offset * HEADING_MULTIPLIER);
if (ELEVATION_SMOOTHING_FACTOR > 0) {
- elevation = (elevation*(1-(ELEVATION_SMOOTHING_FACTOR/100))) + (previous_elevation*(ELEVATION_SMOOTHING_FACTOR/100));
+ elevation = (elevation * (1 - (ELEVATION_SMOOTHING_FACTOR / 100))) + (previous_elevation * (ELEVATION_SMOOTHING_FACTOR / 100));
}
if (elevation < 0) {
elevation = 0;
}
- #endif //FEATURE_EL_POSITION_POTENTIOMETER
-
-
+ #endif // FEATURE_EL_POSITION_POTENTIOMETER
+
+
#ifdef FEATURE_EL_POSITION_ROTARY_ENCODER
static byte el_position_encoder_state = 0;
-
- el_position_encoder_state = ttable[el_position_encoder_state & 0xf][((digitalRead(el_rotary_position_pin2) << 1) | digitalRead(el_rotary_position_pin1))];
+ el_position_encoder_state = ttable[el_position_encoder_state & 0xf][((digitalReadEnhanced(el_rotary_position_pin2) << 1) | digitalReadEnhanced(el_rotary_position_pin1))];
byte el_position_encoder_result = el_position_encoder_state & 0x30;
if (el_position_encoder_result) {
if (el_position_encoder_result == DIR_CW) {
configuration.last_elevation = configuration.last_elevation + EL_POSITION_ROTARY_ENCODER_DEG_PER_PULSE;
#ifdef DEBUG_POSITION_ROTARY_ENCODER
- if (debug_mode){Serial.println(F("read_elevation: EL_POSITION_ROTARY_ENCODER: CW/UP"));}
- #endif //DEBUG_POSITION_ROTARY_ENCODER
+ if (debug_mode) {
+ control_port->println(F("read_elevation: EL_POSITION_ROTARY_ENCODER: CW/UP"));
+ }
+ #endif // DEBUG_POSITION_ROTARY_ENCODER
}
if (el_position_encoder_result == DIR_CCW) {
configuration.last_elevation = configuration.last_elevation - EL_POSITION_ROTARY_ENCODER_DEG_PER_PULSE;
#ifdef DEBUG_POSITION_ROTARY_ENCODER
- if (debug_mode){Serial.println(F("read_elevation: EL_POSITION_ROTARY_ENCODER: CCW/DWN"));}
- #endif //DEBUG_POSITION_ROTARY_ENCODER
+ if (debug_mode) {
+ control_port->println(F("read_elevation: EL_POSITION_ROTARY_ENCODER: CCW/DWN"));
+ }
+ #endif // DEBUG_POSITION_ROTARY_ENCODER
}
- #ifdef OPTION_EL_POSITION_ROTARY_ENCODER_HARD_LIMIT
- if (configuration.last_elevation < 0){
+ #ifdef OPTION_EL_POSITION_ROTARY_ENCODER_HARD_LIMIT
+ if (configuration.last_elevation < 0) {
configuration.last_elevation = 0;
}
- if (configuration.last_elevation > ELEVATION_MAXIMUM_DEGREES){
- configuration.last_elevation = ELEVATION_MAXIMUM_DEGREES ;
+ if (configuration.last_elevation > ELEVATION_MAXIMUM_DEGREES) {
+ configuration.last_elevation = ELEVATION_MAXIMUM_DEGREES;
}
#endif
-
-
elevation = int(configuration.last_elevation * HEADING_MULTIPLIER);
#ifdef FEATURE_ELEVATION_CORRECTION
- elevation = (correct_elevation(elevation/HEADING_MULTIPLIER)*HEADING_MULTIPLIER);
- #endif //FEATURE_ELEVATION_CORRECTION
+ elevation = (correct_elevation(elevation / HEADING_MULTIPLIER) * HEADING_MULTIPLIER);
+ #endif // FEATURE_ELEVATION_CORRECTION
configuration_dirty = 1;
}
- #endif //FEATURE_EL_POSITION_ROTARY_ENCODER
-
-
+ #endif // FEATURE_EL_POSITION_ROTARY_ENCODER
+
+
#ifdef FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB
AccelerometerRaw raw = accel.ReadRawAxis();
AccelerometerScaled scaled = accel.ReadScaledAxis();
#ifdef DEBUG_ACCEL
if (debug_mode) {
- Serial.print(F("read_elevation: raw.ZAxis: "));
- Serial.println(raw.ZAxis);
+ control_port->print(F("read_elevation: raw.ZAxis: "));
+ control_port->println(raw.ZAxis);
}
- #endif //DEBUG_ACCEL
- elevation = (atan2(scaled.YAxis,scaled.ZAxis)* 180 * HEADING_MULTIPLIER)/M_PI;
+ #endif // DEBUG_ACCEL
+ elevation = (atan2(scaled.YAxis, scaled.ZAxis) * 180 * HEADING_MULTIPLIER) / M_PI;
#ifdef FEATURE_ELEVATION_CORRECTION
- elevation = (correct_elevation(elevation/HEADING_MULTIPLIER)*HEADING_MULTIPLIER);
- #endif //FEATURE_ELEVATION_CORRECTION
+ elevation = (correct_elevation(elevation / HEADING_MULTIPLIER) * HEADING_MULTIPLIER);
+ #endif // FEATURE_ELEVATION_CORRECTION
+ elevation = elevation + (configuration.elevation_offset * HEADING_MULTIPLIER);
if (ELEVATION_SMOOTHING_FACTOR > 0) {
- elevation = (elevation*(1-(ELEVATION_SMOOTHING_FACTOR/100))) + (previous_elevation*(ELEVATION_SMOOTHING_FACTOR/100));
- }
-
- #endif //FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB
-
- #ifdef FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB
- sensors_event_t event;
+ elevation = (elevation * (1 - (ELEVATION_SMOOTHING_FACTOR / 100))) + (previous_elevation * (ELEVATION_SMOOTHING_FACTOR / 100));
+ }
+ #endif // FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB
+
+ #ifdef FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB
+ sensors_event_t event;
accel.getEvent(&event);
#ifdef DEBUG_ACCEL
if (debug_mode) {
- Serial.print(F("read_elevation: event.acceleration.z: "));
- Serial.println(event.acceleration.z);
+ control_port->print(F("read_elevation: event.acceleration.z: "));
+ control_port->println(event.acceleration.z);
}
- #endif //DEBUG_ACCEL
- elevation = (atan2(event.acceleration.y,event.acceleration.z)* 180 * HEADING_MULTIPLIER)/M_PI;
+ #endif // DEBUG_ACCEL
+ elevation = (atan2(event.acceleration.y, event.acceleration.z) * 180 * HEADING_MULTIPLIER) / M_PI;
#ifdef FEATURE_ELEVATION_CORRECTION
- elevation = (correct_elevation(elevation/HEADING_MULTIPLIER)*HEADING_MULTIPLIER);
- #endif //FEATURE_ELEVATION_CORRECTION
- #endif //FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB
-
-
-
+ elevation = (correct_elevation(elevation / HEADING_MULTIPLIER) * HEADING_MULTIPLIER);
+ #endif // FEATURE_ELEVATION_CORRECTION
+ elevation = elevation + (configuration.elevation_offset * HEADING_MULTIPLIER);
+ #endif // FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB
+
+
+
#ifdef FEATURE_EL_POSITION_LSM303
lsm.read();
#ifdef DEBUG_ACCEL
if (debug_mode) {
- Serial.print(F("read_elevation: lsm.accelData.y: "));
- Serial.print(lsm.accelData.y);
- Serial.print(F(" lsm.accelData.z: "));
- Serial.println(lsm.accelData.z);
+ control_port->print(F("read_elevation: lsm.accelData.y: "));
+ control_port->print(lsm.accelData.y);
+ control_port->print(F(" lsm.accelData.z: "));
+ control_port->println(lsm.accelData.z);
}
- #endif //DEBUG_ACCEL
- elevation = (atan2(lsm.accelData.y,lsm.accelData.z)* 180 * HEADING_MULTIPLIER)/M_PI;
+ #endif // DEBUG_ACCEL
+ elevation = (atan2(lsm.accelData.y, lsm.accelData.z) * 180 * HEADING_MULTIPLIER) / M_PI;
#ifdef FEATURE_ELEVATION_CORRECTION
- elevation = (correct_elevation(elevation/HEADING_MULTIPLIER)*HEADING_MULTIPLIER);
- #endif //FEATURE_ELEVATION_CORRECTION
- #endif //FEATURE_EL_POSITION_LSM303
-
-
-
+ elevation = (correct_elevation(elevation / HEADING_MULTIPLIER) * HEADING_MULTIPLIER);
+ #endif // FEATURE_ELEVATION_CORRECTION
+ elevation = elevation + (configuration.elevation_offset * HEADING_MULTIPLIER);
+ #endif // FEATURE_EL_POSITION_LSM303
+
+
+
#ifdef FEATURE_EL_POSITION_PULSE_INPUT
#ifdef DEBUG_POSITION_PULSE_INPUT
-// if (el_position_pule_interrupt_handler_flag) {
-// Serial.print(F("read_elevation: el_position_pule_interrupt_handler_flag: "));
-// Serial.println(el_position_pule_interrupt_handler_flag);
-// el_position_pule_interrupt_handler_flag = 0;
-// }
- #endif //DEBUG_POSITION_PULSE_INPUT
-
+ // if (el_position_pule_interrupt_handler_flag) {
+ // control_port->print(F("read_elevation: el_position_pule_interrupt_handler_flag: "));
+ // control_port->println(el_position_pule_interrupt_handler_flag);
+ // el_position_pule_interrupt_handler_flag = 0;
+ // }
+ #endif // DEBUG_POSITION_PULSE_INPUT
+
static float last_el_position_pulse_input_elevation = el_position_pulse_input_elevation;
-
- if (el_position_pulse_input_elevation != last_el_position_pulse_input_elevation){
+
+ if (el_position_pulse_input_elevation != last_el_position_pulse_input_elevation) {
#ifdef DEBUG_POSITION_PULSE_INPUT
-// if (debug_mode){
-// Serial.print(F("read_elevation: el_position_pulse_input_elevation:"));
-// Serial.println(el_position_pulse_input_elevation);
-// }
- #endif //DEBUG_POSITION_PULSE_INPUT
+ // if (debug_mode){
+ // control_port->print(F("read_elevation: el_position_pulse_input_elevation:"));
+ // control_port->println(el_position_pulse_input_elevation);
+ // }
+ #endif // DEBUG_POSITION_PULSE_INPUT
configuration.last_elevation = el_position_pulse_input_elevation;
configuration_dirty = 1;
last_el_position_pulse_input_elevation = el_position_pulse_input_elevation;
elevation = int(configuration.last_elevation * HEADING_MULTIPLIER);
-
#ifdef FEATURE_ELEVATION_CORRECTION
- elevation = (correct_elevation(elevation/HEADING_MULTIPLIER)*HEADING_MULTIPLIER);
+ elevation = (correct_elevation(elevation / HEADING_MULTIPLIER) * HEADING_MULTIPLIER);
#endif FEATURE_ELEVATION_CORRECTION
-
+ elevation = elevation + (configuration.elevation_offset * HEADING_MULTIPLIER);
}
- #endif //FEATURE_EL_POSITION_PULSE_INPUT
-
+ #endif // FEATURE_EL_POSITION_PULSE_INPUT
+
#ifdef FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT
+ #if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
static unsigned long last_remote_unit_el_query_time = 0;
-
-
-
// do we have a command result waiting for us?
if (remote_unit_command_results_available == REMOTE_UNIT_EL_COMMAND) {
-
+
#ifdef DEBUG_HEADING_READING_TIME
- average_read_time = (average_read_time + (millis()-last_time))/2.0;
+ average_read_time = (average_read_time + (millis() - last_time)) / 2.0;
last_time = millis();
-
- if (debug_mode){
- if ((millis()-last_print_time) > 1000){
- Serial.print(F("read_elevation: avg read frequency: "));
- Serial.println(average_read_time,2);
- last_print_time = millis();
+
+ if (debug_mode) {
+ if ((millis() - last_print_time) > 1000) {
+ control_port->print(F("read_elevation: avg read frequency: "));
+ control_port->println(average_read_time, 2);
+ last_print_time = millis();
}
}
- #endif //DEBUG_HEADING_READING_TIME
-
-
-
+ #endif // DEBUG_HEADING_READING_TIME
elevation = remote_unit_command_result_float * HEADING_MULTIPLIER;
-
#ifdef FEATURE_ELEVATION_CORRECTION
- elevation = (correct_elevation(elevation/HEADING_MULTIPLIER)*HEADING_MULTIPLIER);
- #endif //FEATURE_ELEVATION_CORRECTION
-
+ elevation = (correct_elevation(elevation / HEADING_MULTIPLIER) * HEADING_MULTIPLIER);
+ #endif // FEATURE_ELEVATION_CORRECTION
+ elevation = elevation + (configuration.elevation_offset * HEADING_MULTIPLIER);
if (ELEVATION_SMOOTHING_FACTOR > 0) {
- elevation = (elevation*(1-(ELEVATION_SMOOTHING_FACTOR/100))) + (previous_elevation*(ELEVATION_SMOOTHING_FACTOR/100));
- }
+ elevation = (elevation * (1 - (ELEVATION_SMOOTHING_FACTOR / 100))) + (previous_elevation * (ELEVATION_SMOOTHING_FACTOR / 100));
+ }
remote_unit_command_results_available = 0;
- } else {
-
+ } else {
// is it time to request the elevation?
- if ((millis() - last_remote_unit_el_query_time) > EL_REMOTE_UNIT_QUERY_TIME_MS){
- if (submit_remote_command(REMOTE_UNIT_EL_COMMAND)){
+ if ((millis() - last_remote_unit_el_query_time) > EL_REMOTE_UNIT_QUERY_TIME_MS) {
+ if (submit_remote_command(REMOTE_UNIT_EL_COMMAND, 0, 0)) {
last_remote_unit_el_query_time = millis();
}
}
-
}
-
-
-
- #endif //FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT
-
+ #endif // defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+ #endif // FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT
+
+
+ #ifdef FEATURE_EL_POSITION_HH12_AS5045_SSI
+ elevation = int(elevation_hh12.heading() * HEADING_MULTIPLIER);
+ #ifdef DEBUG_HH12
+ if ((millis() - last_hh12_debug) > 5000) {
+ control_port->print(F("read_elevation: HH-12 raw: "));
+ control_port->println(elevation);
+ last_hh12_debug = millis();
+ }
+ #endif // DEBUG_HH12
+ if (elevation > (180 * HEADING_MULTIPLIER)) {
+ elevation = elevation - (360 * HEADING_MULTIPLIER);
+ }
+ #ifdef FEATURE_ELEVATION_CORRECTION
+ elevation = (correct_elevation(elevation / HEADING_MULTIPLIER) * HEADING_MULTIPLIER);
+ #endif // FEATURE_ELEVATION_CORRECTION
+ elevation = elevation + (configuration.elevation_offset * HEADING_MULTIPLIER);
+ #endif // FEATURE_EL_POSITION_HH12_AS5045_SSI
+
+
+ #ifdef FEATURE_EL_POSITION_INCREMENTAL_ENCODER
+ elevation = ((((el_incremental_encoder_position) / (EL_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.)) * 360.0) * HEADING_MULTIPLIER);
+ #ifdef FEATURE_ELEVATION_CORRECTION
+ elevation = (correct_elevation(elevation / HEADING_MULTIPLIER) * HEADING_MULTIPLIER);
+ #endif // FEATURE_ELEVATION_CORRECTION
+ if (incremental_encoder_previous_elevation != elevation) {
+ configuration.last_el_incremental_encoder_position = el_incremental_encoder_position;
+ configuration_dirty = 1;
+ incremental_encoder_previous_elevation = elevation;
+ }
+ elevation = elevation + (configuration.elevation_offset * HEADING_MULTIPLIER);
+ #endif // FEATURE_EL_POSITION_INCREMENTAL_ENCODER
+
+ #ifdef FEATURE_EL_POSITION_MEMSIC_2125
+ unsigned int pulseY = pulseIn(pin_memsic_2125_y,HIGH,250000);
+ pulseY = pulseIn(pin_memsic_2125_y,HIGH,250000);
+ double Yangle = (asin(((( pulseY / 10. ) - 500.) * 8.) / 1000.0 )) * (360. / (2. * M_PI));
+ #ifdef DEBUG_MEMSIC_2125
+ debug_print("read_elevation: memsic2125 pulseY:");
+ debug_print_int(pulseY);
+ debug_println("");
+ #endif //DEBUG_MEMSIC_2125
+ elevation = Yangle * HEADING_MULTIPLIER;
+ #ifdef FEATURE_ELEVATION_CORRECTION
+ elevation = (correct_elevation(elevation / HEADING_MULTIPLIER) * HEADING_MULTIPLIER);
+ #endif //FEATURE_ELEVATION_CORRECTION
+ #endif //FEATURE_EL_POSITION_MEMSIC_2125
+
last_measurement_time = millis();
}
-
-
-
-
-}
-#endif
-//--------------------------------------------------------------
-#ifdef FEATURE_ELEVATION_CONTROL
-void report_current_elevation() {
- #ifdef FEATURE_YAESU_EMULATION
- // The C2 command that reports elevation in +0nnn format
- String elevation_string;
+} /* read_elevation */
+#endif /* ifdef FEATURE_ELEVATION_CONTROL */
- #ifndef OPTION_GS_232B_EMULATION
- if (elevation < 0){
- Serial.print(F("-0"));
- } else {
- Serial.print(F("+0"));
- }
- #endif
- #ifdef OPTION_GS_232B_EMULATION
- Serial.print(F("EL="));
- #endif
- elevation_string = String(abs(int(elevation/HEADING_MULTIPLIER)), DEC);
- if (elevation_string.length() == 1) {
- Serial.print(F("00"));
- } else {
- if (elevation_string.length() == 2) {
- Serial.print(F("0"));
- }
- }
- Serial.println(elevation_string);
- #endif //FEATURE_YAESU_EMULATION
-
-}
-#endif
-
-//--------------------------------------------------------------
+// --------------------------------------------------------------
#ifdef FEATURE_ELEVATION_CONTROL
void update_el_variable_outputs(byte speed_voltage){
-
+
#ifdef DEBUG_VARIABLE_OUTPUTS
- if (debug_mode) {
- Serial.print(F("update_el_variable_outputs: speed_voltage: "));
- Serial.print(speed_voltage);
- }
- #endif //DEBUG_VARIABLE_OUTPUTS
+ debug_print("update_el_variable_outputs: speed_voltage: ");
+ debug_print_int(speed_voltage);
+ #endif // DEBUG_VARIABLE_OUTPUTS
- if (((el_state == SLOW_START_UP) || (el_state == NORMAL_UP) || (el_state == SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_UP)) && (rotate_up_pwm)){
+ if (((el_state == SLOW_START_UP) || (el_state == NORMAL_UP) || (el_state == SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_UP)) && (rotate_up_pwm)) {
#ifdef DEBUG_VARIABLE_OUTPUTS
- if (debug_mode) {Serial.print(F("\trotate_up_pwm"));}
- #endif //DEBUG_VARIABLE_OUTPUTS
- analogWrite(rotate_up_pwm,speed_voltage);
+ debug_print("\trotate_up_pwm");
+ #endif // DEBUG_VARIABLE_OUTPUTS
+ analogWriteEnhanced(rotate_up_pwm, speed_voltage);
}
-
- if (((el_state == SLOW_START_DOWN) || (el_state == NORMAL_DOWN) || (el_state == SLOW_DOWN_DOWN) || (el_state == TIMED_SLOW_DOWN_DOWN)) && (rotate_down_pwm)){
+
+ if (((el_state == SLOW_START_DOWN) || (el_state == NORMAL_DOWN) || (el_state == SLOW_DOWN_DOWN) || (el_state == TIMED_SLOW_DOWN_DOWN)) && (rotate_down_pwm)) {
#ifdef DEBUG_VARIABLE_OUTPUTS
- if (debug_mode) {Serial.print(F("\trotate_down_pwm"));}
- #endif //DEBUG_VARIABLE_OUTPUTS
- analogWrite(rotate_down_pwm,speed_voltage);
+ debug_print("\trotate_down_pwm");
+ #endif // DEBUG_VARIABLE_OUTPUTS
+ analogWriteEnhanced(rotate_down_pwm, speed_voltage);
}
if (((el_state == SLOW_START_DOWN) || (el_state == NORMAL_DOWN) || (el_state == SLOW_DOWN_DOWN) || (el_state == TIMED_SLOW_DOWN_DOWN) ||
- (el_state == SLOW_START_UP) || (el_state == NORMAL_UP) || (el_state == SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_UP)) && (rotate_up_down_pwm)){
+ (el_state == SLOW_START_UP) || (el_state == NORMAL_UP) || (el_state == SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_UP)) && (rotate_up_down_pwm)) {
#ifdef DEBUG_VARIABLE_OUTPUTS
- if (debug_mode) {Serial.print(F("\trotate_up_down_pwm"));}
- #endif //DEBUG_VARIABLE_OUTPUTS
- analogWrite(rotate_up_down_pwm,speed_voltage);
+ debug_print("\trotate_up_down_pwm");
+ #endif // DEBUG_VARIABLE_OUTPUTS
+ analogWriteEnhanced(rotate_up_down_pwm, speed_voltage);
}
-
- if (((el_state == SLOW_START_UP) || (el_state == NORMAL_UP) || (el_state == SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_UP)) && (rotate_up_freq)){
+
+ if (((el_state == SLOW_START_UP) || (el_state == NORMAL_UP) || (el_state == SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_UP)) && (rotate_up_freq)) {
#ifdef DEBUG_VARIABLE_OUTPUTS
- if (debug_mode) {Serial.print(F("\trotate_up_freq"));}
- #endif //DEBUG_VARIABLE_OUTPUTS
- tone(rotate_up_freq,map(speed_voltage,0,255,EL_VARIABLE_FREQ_OUTPUT_LOW,EL_VARIABLE_FREQ_OUTPUT_HIGH));
+ debug_print("\trotate_up_freq");
+ #endif // DEBUG_VARIABLE_OUTPUTS
+ tone(rotate_up_freq, map(speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH));
}
-
- if (((el_state == SLOW_START_DOWN) || (el_state == NORMAL_DOWN) || (el_state == SLOW_DOWN_DOWN) || (el_state == TIMED_SLOW_DOWN_DOWN)) && (rotate_down_freq)){
+
+ if (((el_state == SLOW_START_DOWN) || (el_state == NORMAL_DOWN) || (el_state == SLOW_DOWN_DOWN) || (el_state == TIMED_SLOW_DOWN_DOWN)) && (rotate_down_freq)) {
#ifdef DEBUG_VARIABLE_OUTPUTS
- if (debug_mode) {Serial.print(F("\trotate_down_freq"));}
- #endif //DEBUG_VARIABLE_OUTPUTS
- tone(rotate_down_freq,map(speed_voltage,0,255,EL_VARIABLE_FREQ_OUTPUT_LOW,EL_VARIABLE_FREQ_OUTPUT_HIGH));
- }
-
- if (elevation_speed_voltage){
- analogWrite(elevation_speed_voltage,speed_voltage);
+ debug_print("\trotate_down_freq");
+ #endif // DEBUG_VARIABLE_OUTPUTS
+ tone(rotate_down_freq, map(speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH));
}
-
- if (debug_mode) {Serial.println();}
-
+
+ #ifdef FEATURE_STEPPER_MOTOR
+
+ unsigned int el_tone = 0;
+
+ if (((el_state == SLOW_START_UP) || (el_state == NORMAL_UP) || (el_state == SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_UP) || (el_state == SLOW_START_DOWN) || (el_state == NORMAL_DOWN) || (el_state == SLOW_DOWN_DOWN) || (el_state == TIMED_SLOW_DOWN_DOWN)) && (el_stepper_motor_pulse)) {
+ #ifdef DEBUG_VARIABLE_OUTPUTS
+ debug_print("\tel_stepper_motor_pulse: ");
+ #endif // DEBUG_VARIABLE_OUTPUTS
+ el_tone = map(speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH);
+
+ if ((el_tone < 31) && (el_tone != 0)) {el_tone = 31;}
+ if (el_tone > 20000) {el_tone = 20000;}
+ if (el_tone > 0) {
+ tone(el_stepper_motor_pulse,el_tone);
+ } else {
+ noTone(el_stepper_motor_pulse);
+ }
+ #ifdef DEBUG_VARIABLE_OUTPUTS
+ debug_print_int(el_tone);
+ #endif // DEBUG_VARIABLE_OUTPUTS
+ //tone(el_stepper_motor_pulse, map(speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH));
+ }
+ #endif //FEATURE_STEPPER_MOTOR
+
+ if (elevation_speed_voltage) {
+ analogWriteEnhanced(elevation_speed_voltage, speed_voltage);
+ }
+
+ #ifdef DEBUG_VARIABLE_OUTPUTS
+ debug_println("");
+ #endif // DEBUG_VARIABLE_OUTPUTS
+
current_el_speed_voltage = speed_voltage;
-
-}
-#endif //FEATURE_ELEVATION_CONTROL
-//--------------------------------------------------------------
+} /* update_el_variable_outputs */
+#endif // FEATURE_ELEVATION_CONTROL
+
+// --------------------------------------------------------------
void update_az_variable_outputs(byte speed_voltage){
#ifdef DEBUG_VARIABLE_OUTPUTS
- if (debug_mode) {
- Serial.print(F("update_az_variable_outputs: speed_voltage: "));
- Serial.print(speed_voltage);
- }
- #endif //DEBUG_VARIABLE_OUTPUTS
+ int temp_int = 0;
- if (((az_state == SLOW_START_CW) || (az_state == NORMAL_CW) || (az_state == SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CW)) && (rotate_cw_pwm)){
- #ifdef DEBUG_VARIABLE_OUTPUTS
- if (debug_mode) {Serial.print(F("\trotate_cw_pwm"));}
- #endif //DEBUG_VARIABLE_OUTPUTS
- analogWrite(rotate_cw_pwm,speed_voltage);
+ debug_print("update_az_variable_outputs: az_state: ");
+ switch (az_state) {
+ case IDLE: debug_print("IDLE"); break;
+ case SLOW_START_CW: debug_print("SLOW_START_CW"); break;
+ case SLOW_START_CCW: debug_print("SLOW_START_CCW"); break;
+ case NORMAL_CW: debug_print("NORMAL_CW"); break;
+ case NORMAL_CCW: debug_print("NORMAL_CCW"); break;
+ case SLOW_DOWN_CW: debug_print("SLOW_DOWN_CW"); break;
+ case SLOW_DOWN_CCW: debug_print("SLOW_DOWN_CCW"); break;
+ case INITIALIZE_SLOW_START_CW: debug_print("INITIALIZE_SLOW_START_CW"); break;
+ case INITIALIZE_SLOW_START_CCW: debug_print("INITIALIZE_SLOW_START_CCW"); break;
+ case INITIALIZE_TIMED_SLOW_DOWN_CW: debug_print("INITIALIZE_TIMED_SLOW_DOWN_CW"); break;
+ case INITIALIZE_TIMED_SLOW_DOWN_CCW: debug_print("INITIALIZE_TIMED_SLOW_DOWN_CCW"); break;
+ case TIMED_SLOW_DOWN_CW: debug_print("TIMED_SLOW_DOWN_CW"); break;
+ case TIMED_SLOW_DOWN_CCW: debug_print("TIMED_SLOW_DOWN_CCW"); break;
+ case INITIALIZE_DIR_CHANGE_TO_CW: debug_print("INITIALIZE_DIR_CHANGE_TO_CW"); break;
+ case INITIALIZE_DIR_CHANGE_TO_CCW: debug_print("INITIALIZE_DIR_CHANGE_TO_CCW"); break;
+ case INITIALIZE_NORMAL_CW: debug_print("INITIALIZE_NORMAL_CW"); break;
+ case INITIALIZE_NORMAL_CCW: debug_print("INITIALIZE_NORMAL_CCW"); break;
+ default: debug_print("UNDEF"); break;
}
-
- if (((az_state == SLOW_START_CCW) || (az_state == NORMAL_CCW) || (az_state == SLOW_DOWN_CCW) || (az_state == TIMED_SLOW_DOWN_CCW)) && (rotate_ccw_pwm)){
+ debug_print(" speed_voltage: ");
+ debug_print_int(speed_voltage);
+ #endif // DEBUG_VARIABLE_OUTPUTS
+
+ if (((az_state == SLOW_START_CW) || (az_state == NORMAL_CW) || (az_state == SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CW)) && (rotate_cw_pwm)) {
#ifdef DEBUG_VARIABLE_OUTPUTS
- if (debug_mode) {Serial.print(F("\trotate_ccw_pwm"));}
- #endif //DEBUG_VARIABLE_OUTPUTS
- analogWrite(rotate_ccw_pwm,speed_voltage);
+ debug_print("\trotate_cw_pwm");
+ #endif // DEBUG_VARIABLE_OUTPUTS
+ analogWriteEnhanced(rotate_cw_pwm, speed_voltage);
}
-
- if (((az_state == SLOW_START_CW) || (az_state == NORMAL_CW) || (az_state == SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CW) || (az_state == SLOW_START_CCW) || (az_state == NORMAL_CCW) || (az_state == SLOW_DOWN_CCW) || (az_state == TIMED_SLOW_DOWN_CCW)) && (rotate_cw_ccw_pwm)){
+
+ if (((az_state == SLOW_START_CCW) || (az_state == NORMAL_CCW) || (az_state == SLOW_DOWN_CCW) || (az_state == TIMED_SLOW_DOWN_CCW)) && (rotate_ccw_pwm)) {
#ifdef DEBUG_VARIABLE_OUTPUTS
- if (debug_mode) {Serial.print(F("\trotate_cw_ccw_pwm"));}
- #endif //DEBUG_VARIABLE_OUTPUTS
- analogWrite(rotate_cw_ccw_pwm,speed_voltage);
- }
-
-
- if (((az_state == SLOW_START_CW) || (az_state == NORMAL_CW) || (az_state == SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CW)) && (rotate_cw_freq)){
- #ifdef DEBUG_VARIABLE_OUTPUTS
- if (debug_mode) {Serial.print(F("\trotate_cw_freq"));}
- #endif //DEBUG_VARIABLE_OUTPUTS
- tone(rotate_cw_freq,map(speed_voltage,0,255,AZ_VARIABLE_FREQ_OUTPUT_LOW,AZ_VARIABLE_FREQ_OUTPUT_HIGH));
+ debug_print("\trotate_ccw_pwm");
+ #endif // DEBUG_VARIABLE_OUTPUTS
+ analogWriteEnhanced(rotate_ccw_pwm, speed_voltage);
}
-
- if (((az_state == SLOW_START_CCW) || (az_state == NORMAL_CCW) || (az_state == SLOW_DOWN_CCW) || (az_state == TIMED_SLOW_DOWN_CCW)) && (rotate_ccw_freq)){
+
+ if (((az_state == SLOW_START_CW) || (az_state == NORMAL_CW) || (az_state == SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CW) || (az_state == SLOW_START_CCW) || (az_state == NORMAL_CCW) || (az_state == SLOW_DOWN_CCW) || (az_state == TIMED_SLOW_DOWN_CCW)) && (rotate_cw_ccw_pwm)) {
#ifdef DEBUG_VARIABLE_OUTPUTS
- if (debug_mode) {Serial.print(F("\trotate_ccw_freq"));}
- #endif //DEBUG_VARIABLE_OUTPUTS
- tone(rotate_ccw_freq,map(speed_voltage,0,255,AZ_VARIABLE_FREQ_OUTPUT_LOW,AZ_VARIABLE_FREQ_OUTPUT_HIGH));
- }
-
+ debug_print("\trotate_cw_ccw_pwm");
+ #endif // DEBUG_VARIABLE_OUTPUTS
+ analogWriteEnhanced(rotate_cw_ccw_pwm, speed_voltage);
+ }
+
+
+ if (((az_state == SLOW_START_CW) || (az_state == NORMAL_CW) || (az_state == SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CW)) && (rotate_cw_freq)) {
+ #ifdef DEBUG_VARIABLE_OUTPUTS
+ debug_print("\trotate_cw_freq: ");
+ temp_int = map(speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH);
+ tone(rotate_cw_freq, temp_int);
+ debug_print_int(temp_int);
+ #else // DEBUG_VARIABLE_OUTPUTS
+ tone(rotate_cw_freq, map(speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH));
+ #endif // DEBUG_VARIABLE_OUTPUTS
+ }
+
+ if (((az_state == SLOW_START_CCW) || (az_state == NORMAL_CCW) || (az_state == SLOW_DOWN_CCW) || (az_state == TIMED_SLOW_DOWN_CCW)) && (rotate_ccw_freq)) {
+ #ifdef DEBUG_VARIABLE_OUTPUTS
+ debug_print("\trotate_ccw_freq: ");
+ temp_int = map(speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH);
+ tone(rotate_ccw_freq, temp_int);
+ debug_print_int(temp_int);
+ #else // DEBUG_VARIABLE_OUTPUTS
+ tone(rotate_ccw_freq, map(speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH));
+ #endif // DEBUG_VARIABLE_OUTPUTS
+ }
+
+ #ifdef FEATURE_STEPPER_MOTOR
+
+ unsigned int az_tone = 0;
+
+ if (((az_state == SLOW_START_CW) || (az_state == NORMAL_CW) || (az_state == SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CW) || (az_state == SLOW_START_CCW) || (az_state == NORMAL_CCW) || (az_state == SLOW_DOWN_CCW) || (az_state == TIMED_SLOW_DOWN_CCW)) && (az_stepper_motor_pulse)) {
+ #ifdef DEBUG_VARIABLE_OUTPUTS
+ debug_print("\taz_stepper_motor_pulse: ");
+ #endif // DEBUG_VARIABLE_OUTPUTS
+ az_tone = map(speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH);
+ if ((az_tone < 31) && (az_tone != 0)) {az_tone = 31;}
+ if (az_tone > 20000) {az_tone = 20000;}
+ if (az_tone > 0) {
+ tone(az_stepper_motor_pulse,az_tone);
+ } else {
+ noTone(az_stepper_motor_pulse);
+ }
+ #ifdef DEBUG_VARIABLE_OUTPUTS
+ debug_print_int(az_tone);
+ #endif // DEBUG_VARIABLE_OUTPUTS
+ }
+ #endif //FEATURE_STEPPER_MOTOR
+
if (azimuth_speed_voltage) {
- analogWrite(azimuth_speed_voltage,speed_voltage);
+ analogWriteEnhanced(azimuth_speed_voltage, speed_voltage);
}
-
- #ifdef DEBUG_VARIABLE_OUTPUTS
- if (debug_mode) {Serial.println();}
- #endif //DEBUG_VARIABLE_OUTPUTS
-
- current_az_speed_voltage = speed_voltage;
-
-}
-//--------------------------------------------------------------
+ #ifdef DEBUG_VARIABLE_OUTPUTS
+ debug_println("");
+ #endif // DEBUG_VARIABLE_OUTPUTS
+
+ current_az_speed_voltage = speed_voltage;
+
+} /* update_az_variable_outputs */
+
+// --------------------------------------------------------------
void rotator(byte rotation_action, byte rotation_type) {
-
+
#ifdef DEBUG_ROTATOR
if (debug_mode) {
- Serial.flush();
- Serial.print(F("rotator: rotation_action:"));
- Serial.print(rotation_action);
- Serial.print(F(" rotation_type:"));
- Serial.flush();
- Serial.print(rotation_type);
- Serial.print(F("->"));
- Serial.flush();
- //delay(1000);
- }
- #endif //DEBUG_ROTATOR
-
- switch(rotation_type) {
+ control_port->flush();
+ control_port->print(F("rotator: rotation_action:"));
+ control_port->print(rotation_action);
+ control_port->print(F(" rotation_type:"));
+ control_port->flush();
+ control_port->print(rotation_type);
+ control_port->print(F("->"));
+ control_port->flush();
+ // delay(1000);
+ }
+ #endif // DEBUG_ROTATOR
+
+ switch (rotation_type) {
case CW:
+ #ifdef DEBUG_ROTATOR
+ if (debug_mode) {
+ control_port->print(F("CW ")); control_port->flush();
+ }
+ #endif // DEBUG_ROTATOR
+ if (rotation_action == ACTIVATE) {
#ifdef DEBUG_ROTATOR
- if (debug_mode) { Serial.print(F("CW ")); Serial.flush();}
- #endif //DEBUG_ROTATOR
- if (rotation_action == ACTIVATE) {
- #ifdef DEBUG_ROTATOR
- if (debug_mode) { Serial.println(F("ACTIVATE")); Serial.flush();}
- #endif //DEBUG_ROTATOR
- brake_release(AZ, BRAKE_RELEASE_ON);
- if (az_slowstart_active) {
- if (rotate_cw_pwm) {analogWrite(rotate_cw_pwm,0);}
- if (rotate_ccw_pwm) {analogWrite(rotate_ccw_pwm,0);digitalWrite(rotate_ccw_pwm,LOW);}
- if (rotate_cw_ccw_pwm) {analogWrite(rotate_cw_ccw_pwm,0);}
- if (rotate_cw_freq) {noTone(rotate_cw_freq);}
- if (rotate_ccw_freq) {noTone(rotate_ccw_freq);}
- } else {
- if (rotate_cw_pwm) {analogWrite(rotate_cw_pwm,normal_az_speed_voltage);}
- if (rotate_ccw_pwm) {analogWrite(rotate_ccw_pwm,0);digitalWrite(rotate_ccw_pwm,LOW);}
- if (rotate_cw_ccw_pwm) {analogWrite(rotate_cw_ccw_pwm,normal_az_speed_voltage);}
- if (rotate_cw_freq) {tone(rotate_cw_freq,map(normal_az_speed_voltage,0,255,AZ_VARIABLE_FREQ_OUTPUT_LOW,AZ_VARIABLE_FREQ_OUTPUT_HIGH));}
- if (rotate_ccw_freq) {noTone(rotate_ccw_freq);}
+ if (debug_mode) {
+ control_port->println(F("ACTIVATE")); control_port->flush();
+ }
+ #endif // DEBUG_ROTATOR
+ brake_release(AZ, BRAKE_RELEASE_ON);
+ if (az_slowstart_active) {
+ if (rotate_cw_pwm) {
+ analogWriteEnhanced(rotate_cw_pwm, 0);
}
- if (rotate_cw) {digitalWrite(rotate_cw,ROTATE_PIN_ACTIVE_VALUE);}
- if (rotate_ccw) {digitalWrite(rotate_ccw,ROTATE_PIN_INACTIVE_VALUE);}
- #ifdef DEBUG_ROTATOR
- if (debug_mode) {
- Serial.print(F("rotator: normal_az_speed_voltage:"));
- Serial.println(normal_az_speed_voltage);
- Serial.flush();
+ if (rotate_ccw_pwm) {
+ analogWriteEnhanced(rotate_ccw_pwm, 0); digitalWriteEnhanced(rotate_ccw_pwm, LOW);
}
- #endif //DEBUG_ROTATOR
- } else {
+ if (rotate_cw_ccw_pwm) {
+ analogWriteEnhanced(rotate_cw_ccw_pwm, 0);
+ }
+ if (rotate_cw_freq) {
+ noTone(rotate_cw_freq);
+ }
+ if (rotate_ccw_freq) {
+ noTone(rotate_ccw_freq);
+ }
+ if (az_stepper_motor_pulse) {
+ noTone(az_stepper_motor_pulse);
+ digitalWriteEnhanced(az_stepper_motor_pulse, LOW);
+ }
+ } else {
+ if (rotate_cw_pwm) {
+ analogWriteEnhanced(rotate_cw_pwm, normal_az_speed_voltage);
+ }
+ if (rotate_ccw_pwm) {
+ analogWriteEnhanced(rotate_ccw_pwm, 0); digitalWriteEnhanced(rotate_ccw_pwm, LOW);
+ }
+ if (rotate_cw_ccw_pwm) {
+ analogWriteEnhanced(rotate_cw_ccw_pwm, normal_az_speed_voltage);
+ }
+ if (rotate_cw_freq) {
+ tone(rotate_cw_freq, map(normal_az_speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH));
+ }
+ if (rotate_ccw_freq) {
+ noTone(rotate_ccw_freq);
+ }
+ if (az_stepper_motor_pulse) {
+ tone(az_stepper_motor_pulse, map(normal_az_speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH));
+ }
+ }
+ if (rotate_cw) {
+ digitalWriteEnhanced(rotate_cw, ROTATE_PIN_ACTIVE_VALUE);
+ }
+ if (rotate_ccw) {
+ digitalWriteEnhanced(rotate_ccw, ROTATE_PIN_INACTIVE_VALUE);
+ }
+ if (rotate_cw_ccw){
+ digitalWriteEnhanced(rotate_cw_ccw, ROTATE_PIN_ACTIVE_VALUE);
+ }
+ #ifdef FEATURE_STEPPER_MOTOR
+ if (az_stepper_motor_direction){
+ if (az_stepper_motor_last_direction != STEPPER_CW){
+ if (az_stepper_motor_last_pin_state == LOW){
+ digitalWriteEnhanced(az_stepper_motor_direction,HIGH);
+ az_stepper_motor_last_pin_state = HIGH;
+ } else {
+ digitalWriteEnhanced(az_stepper_motor_direction,LOW);
+ az_stepper_motor_last_pin_state = LOW;
+ }
+ az_stepper_motor_last_direction = STEPPER_CW;
+ }
+ }
+ #endif //FEATURE_STEPPER_MOTOR
#ifdef DEBUG_ROTATOR
- if (debug_mode) {Serial.println(F("DEACTIVATE"));Serial.flush();}
- #endif //DEBUG_ROTATOR
- if (rotate_cw_pwm) {analogWrite(rotate_cw_pwm,0);digitalWrite(rotate_cw_pwm,LOW);}
- if (rotate_cw_ccw_pwm) {analogWrite(rotate_cw_ccw_pwm,0);}
- if (rotate_cw) {digitalWrite(rotate_cw,ROTATE_PIN_INACTIVE_VALUE);}
- if (rotate_cw_freq) {noTone(rotate_cw_freq);}
- }
+ if (debug_mode) {
+ control_port->print(F("rotator: normal_az_speed_voltage:"));
+ control_port->println(normal_az_speed_voltage);
+ //control_port->flush();
+ }
+ #endif // DEBUG_ROTATOR
+ } else {
+ #ifdef DEBUG_ROTATOR
+ if (debug_mode) {
+ control_port->println(F("DEACTIVATE")); //control_port->flush();
+ }
+ #endif // DEBUG_ROTATOR
+ if (rotate_cw_pwm) {
+ analogWriteEnhanced(rotate_cw_pwm, 0); digitalWriteEnhanced(rotate_cw_pwm, LOW);
+ }
+ if (rotate_cw_ccw_pwm) {
+ analogWriteEnhanced(rotate_cw_ccw_pwm, 0);
+ }
+ if (rotate_cw) {
+ digitalWriteEnhanced(rotate_cw, ROTATE_PIN_INACTIVE_VALUE);
+ }
+ if (rotate_cw_ccw){
+ digitalWriteEnhanced(rotate_cw_ccw, ROTATE_PIN_INACTIVE_VALUE);
+ }
+ if (rotate_cw_freq) {
+ noTone(rotate_cw_freq);
+ }
+ #ifdef FEATURE_STEPPER_MOTOR
+ if (az_stepper_motor_pulse) {
+ noTone(az_stepper_motor_pulse);
+ digitalWriteEnhanced(az_stepper_motor_pulse, HIGH);
+ }
+ #endif //FEATURE_STEPPER_MOTOR
+ }
break;
case CCW:
#ifdef DEBUG_ROTATOR
- if (debug_mode) {Serial.print(F("CCW "));Serial.flush();}
- #endif //DEBUG_ROTATOR
+ if (debug_mode) {
+ control_port->print(F("CCW ")); control_port->flush();
+ }
+ #endif // DEBUG_ROTATOR
if (rotation_action == ACTIVATE) {
#ifdef DEBUG_ROTATOR
- if (debug_mode) {Serial.println(F("ACTIVATE"));Serial.flush();}
- #endif //DEBUG_ROTATOR
- brake_release(AZ, BRAKE_RELEASE_ON);
- if (az_slowstart_active) {
- if (rotate_cw_pwm) {analogWrite(rotate_cw_pwm,0);digitalWrite(rotate_cw_pwm,LOW);}
- if (rotate_ccw_pwm) {analogWrite(rotate_ccw_pwm,0);}
- if (rotate_cw_ccw_pwm) {analogWrite(rotate_cw_ccw_pwm,0);}
- if (rotate_cw_freq) {noTone(rotate_cw_freq);}
- if (rotate_ccw_freq) {noTone(rotate_ccw_freq);}
- } else {
- if (rotate_cw_pwm) {analogWrite(rotate_cw_pwm,0);digitalWrite(rotate_cw_pwm,LOW);}
- if (rotate_ccw_pwm) {analogWrite(rotate_ccw_pwm,normal_az_speed_voltage);}
- if (rotate_cw_ccw_pwm) {analogWrite(rotate_cw_ccw_pwm,normal_az_speed_voltage);}
- if (rotate_cw_freq) {noTone(rotate_cw_freq);}
- if (rotate_ccw_freq) {tone(rotate_ccw_freq,map(normal_az_speed_voltage,0,255,AZ_VARIABLE_FREQ_OUTPUT_LOW,AZ_VARIABLE_FREQ_OUTPUT_HIGH));}
+ if (debug_mode) {
+ control_port->println(F("ACTIVATE")); control_port->flush();
+ }
+ #endif // DEBUG_ROTATOR
+ brake_release(AZ, BRAKE_RELEASE_ON);
+ if (az_slowstart_active) {
+ if (rotate_cw_pwm) {
+ analogWriteEnhanced(rotate_cw_pwm, 0); digitalWriteEnhanced(rotate_cw_pwm, LOW);
+ }
+ if (rotate_ccw_pwm) {
+ analogWriteEnhanced(rotate_ccw_pwm, 0);
+ }
+ if (rotate_cw_ccw_pwm) {
+ analogWriteEnhanced(rotate_cw_ccw_pwm, 0);
+ }
+ if (rotate_cw_freq) {
+ noTone(rotate_cw_freq);
+ }
+ if (rotate_ccw_freq) {
+ noTone(rotate_ccw_freq);
+ }
+ #ifdef FEATURE_STEPPER_MOTOR
+ if (az_stepper_motor_pulse) {
+ noTone(az_stepper_motor_pulse);
+ digitalWriteEnhanced(az_stepper_motor_pulse, LOW);
}
- if (rotate_cw) {digitalWrite(rotate_cw,ROTATE_PIN_INACTIVE_VALUE);}
- if (rotate_ccw) {digitalWrite(rotate_ccw,ROTATE_PIN_ACTIVE_VALUE);}
- #ifdef DEBUG_ROTATOR
- if (debug_mode) {
- Serial.print(F("rotator: normal_az_speed_voltage:"));
- Serial.println(normal_az_speed_voltage);
- Serial.flush();
+ #endif //FEATURE_STEPPER_MOTOR
+ } else {
+ if (rotate_cw_pwm) {
+ analogWriteEnhanced(rotate_cw_pwm, 0); digitalWriteEnhanced(rotate_cw_pwm, LOW);
+ }
+ if (rotate_ccw_pwm) {
+ analogWriteEnhanced(rotate_ccw_pwm, normal_az_speed_voltage);
+ }
+ if (rotate_cw_ccw_pwm) {
+ analogWriteEnhanced(rotate_cw_ccw_pwm, normal_az_speed_voltage);
+ }
+ if (rotate_cw_freq) {
+ noTone(rotate_cw_freq);
+ }
+ if (rotate_ccw_freq) {
+ tone(rotate_ccw_freq, map(normal_az_speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH));
+ }
+ #ifdef FEATURE_STEPPER_MOTOR
+ if (az_stepper_motor_pulse) {
+ tone(az_stepper_motor_pulse, map(normal_az_speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH));
}
- #endif //DEBUG_ROTATOR
+ #endif //FEATURE_STEPPER_MOTOR
+ }
+ if (rotate_cw) {
+ digitalWriteEnhanced(rotate_cw, ROTATE_PIN_INACTIVE_VALUE);
+ }
+ if (rotate_ccw) {
+ digitalWriteEnhanced(rotate_ccw, ROTATE_PIN_ACTIVE_VALUE);
+ }
+ if (rotate_cw_ccw){
+ digitalWriteEnhanced(rotate_cw_ccw, ROTATE_PIN_ACTIVE_VALUE);
+ }
+ #ifdef FEATURE_STEPPER_MOTOR
+ if (az_stepper_motor_direction){
+ if (az_stepper_motor_last_direction != STEPPER_CCW){
+ if (az_stepper_motor_last_pin_state == LOW){
+ digitalWriteEnhanced(az_stepper_motor_direction,HIGH);
+ az_stepper_motor_last_pin_state = HIGH;
+ } else {
+ digitalWriteEnhanced(az_stepper_motor_direction,LOW);
+ az_stepper_motor_last_pin_state = LOW;
+ }
+ az_stepper_motor_last_direction = STEPPER_CCW;
+ }
+ }
+ #endif //FEATURE_STEPPER_MOTOR
+
+ #ifdef DEBUG_ROTATOR
+ if (debug_mode) {
+ control_port->print(F("rotator: normal_az_speed_voltage:"));
+ control_port->println(normal_az_speed_voltage);
+ control_port->flush();
+ }
+ #endif // DEBUG_ROTATOR
} else {
#ifdef DEBUG_ROTATOR
- if (debug_mode) {Serial.println(F("DEACTIVATE"));Serial.flush();}
- #endif //DEBUG_ROTATOR
- if (rotate_ccw_pwm) {analogWrite(rotate_ccw_pwm,0);digitalWrite(rotate_ccw_pwm,LOW);}
- if (rotate_ccw) {digitalWrite(rotate_ccw,ROTATE_PIN_INACTIVE_VALUE);}
- if (rotate_ccw_freq) {noTone(rotate_ccw_freq);}
- }
- break;
-
- #ifdef FEATURE_ELEVATION_CONTROL
-
- //TODO: add pwm and freq pins
-
- case UP:
- #ifdef DEBUG_ROTATOR
- if (debug_mode) { Serial.print(F("ROTATION_UP "));Serial.flush(); }
- #endif //DEBUG_ROTATOR
- if (rotation_action == ACTIVATE) {
- #ifdef DEBUG_ROTATOR
- if (debug_mode) { Serial.println(F("ACTIVATE"));Serial.flush(); }
- #endif //DEBUG_ROTATOR
- brake_release(EL, BRAKE_RELEASE_ON);
- if (el_slowstart_active) {
- if (rotate_up_pwm) {analogWrite(rotate_up_pwm,0);}
- if (rotate_down_pwm) {analogWrite(rotate_down_pwm,0);digitalWrite(rotate_down_pwm,LOW);}
- if (rotate_up_down_pwm) {analogWrite(rotate_up_down_pwm,0);}
- if (rotate_up_freq) {noTone(rotate_up_freq);}
- if (rotate_down_freq) {noTone(rotate_down_freq);}
- } else {
- if (rotate_up_pwm) {analogWrite(rotate_up_pwm,normal_el_speed_voltage);}
- if (rotate_down_pwm) {analogWrite(rotate_down_pwm,0);digitalWrite(rotate_down_pwm,LOW);}
- if (rotate_up_down_pwm) {analogWrite(rotate_up_down_pwm,normal_el_speed_voltage);}
- if (rotate_up_freq) {tone(rotate_up_freq,map(normal_el_speed_voltage,0,255,EL_VARIABLE_FREQ_OUTPUT_LOW,EL_VARIABLE_FREQ_OUTPUT_HIGH));}
- if (rotate_down_freq) {noTone(rotate_down_freq);}
- }
- if (rotate_up) {digitalWrite(rotate_up,ROTATE_PIN_ACTIVE_VALUE);}
- if (rotate_down) {digitalWrite(rotate_down,ROTATE_PIN_INACTIVE_VALUE);}
- if (rotate_up_or_down) {digitalWrite(rotate_up_or_down,ROTATE_PIN_ACTIVE_VALUE);}
- } else {
- #ifdef DEBUG_ROTATOR
- if (debug_mode) { Serial.println(F("DEACTIVATE"));Serial.flush(); }
- #endif //DEBUG_ROTATOR
- if (rotate_up) {digitalWrite(rotate_up,ROTATE_PIN_INACTIVE_VALUE);}
- if (rotate_up_pwm) {analogWrite(rotate_up_pwm,0);digitalWrite(rotate_up_pwm,LOW);}
- if (rotate_up_down_pwm) {analogWrite(rotate_up_down_pwm,0);}
- if (rotate_up_freq) {noTone(rotate_up_freq);}
- if (rotate_up_or_down) {digitalWrite(rotate_up_or_down,ROTATE_PIN_INACTIVE_VALUE);}
- }
+ if (debug_mode) {
+ control_port->println(F("DEACTIVATE")); control_port->flush();
+ }
+ #endif // DEBUG_ROTATOR
+ if (rotate_ccw_pwm) {
+ analogWriteEnhanced(rotate_ccw_pwm, 0); digitalWriteEnhanced(rotate_ccw_pwm, LOW);
+ }
+ if (rotate_ccw) {
+ digitalWriteEnhanced(rotate_ccw, ROTATE_PIN_INACTIVE_VALUE);
+ }
+ if (rotate_ccw_freq) {
+ noTone(rotate_ccw_freq);
+ }
+ }
break;
-
- case DOWN:
- #ifdef DEBUG_ROTATOR
- if (debug_mode) { Serial.print(F("ROTATION_DOWN ")); Serial.flush();}
- #endif //DEBUG_ROTATOR
- if (rotation_action == ACTIVATE) {
- #ifdef DEBUG_ROTATOR
- if (debug_mode) { Serial.println(F("ACTIVATE"));Serial.flush(); }
- #endif //DEBUG_ROTATOR
- brake_release(EL, BRAKE_RELEASE_ON);
- if (el_slowstart_active) {
- if (rotate_down_pwm) {analogWrite(rotate_down_pwm,0);}
- if (rotate_up_pwm) {analogWrite(rotate_up_pwm,0);digitalWrite(rotate_up_pwm,LOW);}
- if (rotate_up_down_pwm) {analogWrite(rotate_up_down_pwm,0);}
- if (rotate_up_freq) {noTone(rotate_up_freq);}
- if (rotate_down_freq) {noTone(rotate_down_freq);}
- } else {
- if (rotate_down_pwm) {analogWrite(rotate_down_pwm,normal_el_speed_voltage);}
- if (rotate_up_pwm) {analogWrite(rotate_up_pwm,0);digitalWrite(rotate_up_pwm,LOW);}
- if (rotate_up_down_pwm) {analogWrite(rotate_up_down_pwm,normal_el_speed_voltage);}
- if (rotate_down_freq) {tone(rotate_down_freq,map(normal_el_speed_voltage,0,255,EL_VARIABLE_FREQ_OUTPUT_LOW,EL_VARIABLE_FREQ_OUTPUT_HIGH));}
- if (rotate_up_freq) {noTone(rotate_up_freq);}
- }
- if (rotate_up) {digitalWrite(rotate_up,ROTATE_PIN_INACTIVE_VALUE);}
- if (rotate_down) {digitalWrite(rotate_down,ROTATE_PIN_ACTIVE_VALUE);}
- if (rotate_up_or_down) {digitalWrite(rotate_up_or_down,ROTATE_PIN_ACTIVE_VALUE);}
+
+ #ifdef FEATURE_ELEVATION_CONTROL
+
+
+ case UP:
+ #ifdef DEBUG_ROTATOR
+ if (debug_mode) {
+ control_port->print(F("ROTATION_UP ")); control_port->flush();
+ }
+ #endif // DEBUG_ROTATOR
+ if (rotation_action == ACTIVATE) {
+ #ifdef DEBUG_ROTATOR
+ if (debug_mode) {
+ control_port->println(F("ACTIVATE")); control_port->flush();
+ }
+ #endif // DEBUG_ROTATOR
+ brake_release(EL, BRAKE_RELEASE_ON);
+ if (el_slowstart_active) {
+ if (rotate_up_pwm) {
+ analogWriteEnhanced(rotate_up_pwm, 0);
+ }
+ if (rotate_down_pwm) {
+ analogWriteEnhanced(rotate_down_pwm, 0); digitalWriteEnhanced(rotate_down_pwm, LOW);
+ }
+ if (rotate_up_down_pwm) {
+ analogWriteEnhanced(rotate_up_down_pwm, 0);
+ }
+ if (rotate_up_freq) {
+ noTone(rotate_up_freq);
+ }
+ if (rotate_down_freq) {
+ noTone(rotate_down_freq);
+ }
+ #ifdef FEATURE_STEPPER_MOTOR
+ if (el_stepper_motor_pulse) {
+ noTone(el_stepper_motor_pulse);
+ digitalWriteEnhanced(el_stepper_motor_pulse,LOW);
+ }
+ #endif //FEATURE_STEPPER_MOTOR
+ } else {
+ if (rotate_up_pwm) {
+ analogWriteEnhanced(rotate_up_pwm, normal_el_speed_voltage);
+ }
+ if (rotate_down_pwm) {
+ analogWriteEnhanced(rotate_down_pwm, 0); digitalWriteEnhanced(rotate_down_pwm, LOW);
+ }
+ if (rotate_up_down_pwm) {
+ analogWriteEnhanced(rotate_up_down_pwm, normal_el_speed_voltage);
+ }
+ if (rotate_up_freq) {
+ tone(rotate_up_freq, map(normal_el_speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH));
+ }
+ #ifdef FEATURE_STEPPER_MOTOR
+ if (el_stepper_motor_pulse) {
+ tone(el_stepper_motor_pulse, map(normal_el_speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH));
+ }
+ #endif //FEATURE_STEPPER_MOTOR
+ if (rotate_down_freq) {
+ noTone(rotate_down_freq);
+ }
+ }
+ if (rotate_up) {
+ digitalWriteEnhanced(rotate_up, ROTATE_PIN_ACTIVE_VALUE);
+ }
+ if (rotate_down) {
+ digitalWriteEnhanced(rotate_down, ROTATE_PIN_INACTIVE_VALUE);
+ }
+ if (rotate_up_or_down) {
+ digitalWriteEnhanced(rotate_up_or_down, ROTATE_PIN_ACTIVE_VALUE);
+ }
+ #ifdef FEATURE_STEPPER_MOTOR
+ if (el_stepper_motor_direction){
+ if (el_stepper_motor_last_direction != STEPPER_UP){
+ if (el_stepper_motor_last_pin_state == LOW){
+ digitalWriteEnhanced(el_stepper_motor_direction,HIGH);
+ el_stepper_motor_last_pin_state = HIGH;
+ } else {
+ digitalWriteEnhanced(el_stepper_motor_direction,LOW);
+ el_stepper_motor_last_pin_state = LOW;
+ }
+ el_stepper_motor_last_direction = STEPPER_UP;
+ }
+ }
+ #endif //FEATURE_STEPPER_MOTOR
} else {
+ #ifdef DEBUG_ROTATOR
+ if (debug_mode) {
+ control_port->println(F("DEACTIVATE")); control_port->flush();
+ }
+ #endif // DEBUG_ROTATOR
+ if (rotate_up) {
+ digitalWriteEnhanced(rotate_up, ROTATE_PIN_INACTIVE_VALUE);
+ }
+ if (rotate_up_pwm) {
+ analogWriteEnhanced(rotate_up_pwm, 0); digitalWriteEnhanced(rotate_up_pwm, LOW);
+ }
+ if (rotate_up_down_pwm) {
+ analogWriteEnhanced(rotate_up_down_pwm, 0);
+ }
+ if (rotate_up_freq) {
+ noTone(rotate_up_freq);
+ }
+ if (rotate_up_or_down) {
+ digitalWriteEnhanced(rotate_up_or_down, ROTATE_PIN_INACTIVE_VALUE);
+ }
+ #ifdef FEATURE_STEPPER_MOTOR
+ if (el_stepper_motor_pulse) {
+ noTone(el_stepper_motor_pulse);
+ digitalWriteEnhanced(el_stepper_motor_pulse,HIGH);
+ }
+ #endif //FEATURE_STEPPER_MOTOR
+ }
+ break;
+
+ case DOWN:
+ #ifdef DEBUG_ROTATOR
+ if (debug_mode) {
+ control_port->print(F("ROTATION_DOWN ")); control_port->flush();
+ }
+ #endif // DEBUG_ROTATOR
+ if (rotation_action == ACTIVATE) {
#ifdef DEBUG_ROTATOR
- if (debug_mode) { Serial.println(F("DEACTIVATE"));Serial.flush(); }
- #endif //DEBUG_ROTATOR
- if (rotate_down) {digitalWrite(rotate_down,ROTATE_PIN_INACTIVE_VALUE);}
- if (rotate_down_pwm) {analogWrite(rotate_down_pwm,0);digitalWrite(rotate_down_pwm,LOW);}
- if (rotate_up_down_pwm) {analogWrite(rotate_up_down_pwm,0);}
- if (rotate_down_freq) {noTone(rotate_down_freq);}
- if (rotate_up_or_down) {digitalWrite(rotate_up_or_down,ROTATE_PIN_INACTIVE_VALUE);}
- }
- break;
- #endif //FEATURE_ELEVATION_CONTROL
- }
-
+ if (debug_mode) {
+ control_port->println(F("ACTIVATE")); control_port->flush();
+ }
+ #endif // DEBUG_ROTATOR
+ brake_release(EL, BRAKE_RELEASE_ON);
+ if (el_slowstart_active) {
+ if (rotate_down_pwm) {
+ analogWriteEnhanced(rotate_down_pwm, 0);
+ }
+ if (rotate_up_pwm) {
+ analogWriteEnhanced(rotate_up_pwm, 0); digitalWriteEnhanced(rotate_up_pwm, LOW);
+ }
+ if (rotate_up_down_pwm) {
+ analogWriteEnhanced(rotate_up_down_pwm, 0);
+ }
+ if (rotate_up_freq) {
+ noTone(rotate_up_freq);
+ }
+ if (rotate_down_freq) {
+ noTone(rotate_down_freq);
+ }
+ #ifdef FEATURE_STEPPER_MOTOR
+ if (el_stepper_motor_pulse) {
+ noTone(el_stepper_motor_pulse);
+ digitalWriteEnhanced(el_stepper_motor_pulse,LOW);
+ }
+ #endif //FEATURE_STEPPER_MOTOR
+ } else {
+ if (rotate_down_pwm) {
+ analogWriteEnhanced(rotate_down_pwm, normal_el_speed_voltage);
+ }
+ if (rotate_up_pwm) {
+ analogWriteEnhanced(rotate_up_pwm, 0); digitalWriteEnhanced(rotate_up_pwm, LOW);
+ }
+ if (rotate_up_down_pwm) {
+ analogWriteEnhanced(rotate_up_down_pwm, normal_el_speed_voltage);
+ }
+ if (rotate_down_freq) {
+ tone(rotate_down_freq, map(normal_el_speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH));
+ }
+ if (rotate_up_freq) {
+ noTone(rotate_up_freq);
+ }
+ #ifdef FEATURE_STEPPER_MOTOR
+ if (el_stepper_motor_pulse) {
+ tone(el_stepper_motor_pulse, map(normal_el_speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH));
+ digitalWriteEnhanced(el_stepper_motor_pulse,LOW);
+ }
+ #endif //FEATURE_STEPPER_MOTOR
+ }
+ if (rotate_up) {
+ digitalWriteEnhanced(rotate_up, ROTATE_PIN_INACTIVE_VALUE);
+ }
+ if (rotate_down) {
+ digitalWriteEnhanced(rotate_down, ROTATE_PIN_ACTIVE_VALUE);
+ }
+ if (rotate_up_or_down) {
+ digitalWriteEnhanced(rotate_up_or_down, ROTATE_PIN_ACTIVE_VALUE);
+ }
+ #ifdef FEATURE_STEPPER_MOTOR
+ if (el_stepper_motor_direction){
+ if (el_stepper_motor_last_direction != STEPPER_DOWN){
+ if (el_stepper_motor_last_pin_state == LOW){
+ digitalWriteEnhanced(el_stepper_motor_direction,HIGH);
+ el_stepper_motor_last_pin_state = HIGH;
+ } else {
+ digitalWriteEnhanced(el_stepper_motor_direction,LOW);
+ el_stepper_motor_last_pin_state = LOW;
+ }
+ el_stepper_motor_last_direction = STEPPER_DOWN;
+ }
+ }
+ #endif //FEATURE_STEPPER_MOTOR
+ } else {
+ #ifdef DEBUG_ROTATOR
+ if (debug_mode) {
+ control_port->println(F("DEACTIVATE")); control_port->flush();
+ }
+ #endif // DEBUG_ROTATOR
+ if (rotate_down) {
+ digitalWriteEnhanced(rotate_down, ROTATE_PIN_INACTIVE_VALUE);
+ }
+ if (rotate_down_pwm) {
+ analogWriteEnhanced(rotate_down_pwm, 0); digitalWriteEnhanced(rotate_down_pwm, LOW);
+ }
+ if (rotate_up_down_pwm) {
+ analogWriteEnhanced(rotate_up_down_pwm, 0);
+ }
+ if (rotate_down_freq) {
+ noTone(rotate_down_freq);
+ }
+ if (rotate_up_or_down) {
+ digitalWriteEnhanced(rotate_up_or_down, ROTATE_PIN_INACTIVE_VALUE);
+ }
+ #ifdef FEATURE_STEPPER_MOTOR
+ if (el_stepper_motor_pulse) {
+ noTone(el_stepper_motor_pulse);
+ digitalWriteEnhanced(el_stepper_motor_pulse,HIGH);
+ }
+ #endif //FEATURE_STEPPER_MOTOR
+ }
+ break;
+ #endif // FEATURE_ELEVATION_CONTROL
+ } /* switch */
+
#ifdef DEBUG_ROTATOR
if (debug_mode) {
- Serial.println(F("rotator: exiting"));
- Serial.flush();
- }
- #endif //DEBUG_ROTATOR
-}
+ control_port->println(F("rotator: exiting"));
+ control_port->flush();
+ }
+ #endif // DEBUG_ROTATOR
+} /* rotator */
-//--------------------------------------------------------------
+// --------------------------------------------------------------
void initialize_interrupts(){
-
+
#ifdef FEATURE_AZ_POSITION_PULSE_INPUT
attachInterrupt(AZ_POSITION_PULSE_PIN_INTERRUPT, az_position_pulse_interrupt_handler, FALLING);
- #endif //FEATURE_AZ_POSITION_PULSE_INPUT
-
+ #endif // FEATURE_AZ_POSITION_PULSE_INPUT
+
#ifdef FEATURE_EL_POSITION_PULSE_INPUT
attachInterrupt(EL_POSITION_PULSE_PIN_INTERRUPT, el_position_pulse_interrupt_handler, FALLING);
- #endif //FEATURE_EL_POSITION_PULSE_INPUT
-
-
+ #endif // FEATURE_EL_POSITION_PULSE_INPUT
+
+
}
-//--------------------------------------------------------------
+// --------------------------------------------------------------
void initialize_pins(){
-
+
if (serial_led) {
- pinMode(serial_led, OUTPUT);
+ pinModeEnhanced(serial_led, OUTPUT);
}
-
+
if (overlap_led) {
- pinMode(overlap_led, OUTPUT);
+ pinModeEnhanced(overlap_led, OUTPUT);
}
if (brake_az) {
- pinMode(brake_az, OUTPUT);
- digitalWrite(brake_az, LOW);
+ pinModeEnhanced(brake_az, OUTPUT);
+ digitalWriteEnhanced(brake_az, LOW);
}
-
+
if (az_speed_pot) {
- pinMode(az_speed_pot, INPUT);
- digitalWrite(az_speed_pot, LOW);
+ pinModeEnhanced(az_speed_pot, INPUT);
+ digitalWriteEnhanced(az_speed_pot, LOW);
}
-
+
if (az_preset_pot) {
- pinMode(az_preset_pot, INPUT);
- digitalWrite(az_preset_pot, LOW);
+ pinModeEnhanced(az_preset_pot, INPUT);
+ digitalWriteEnhanced(az_preset_pot, LOW);
}
-
+
if (preset_start_button) {
- pinMode(preset_start_button, INPUT);
- digitalWrite(preset_start_button, HIGH);
- }
+ pinModeEnhanced(preset_start_button, INPUT);
+ digitalWriteEnhanced(preset_start_button, HIGH);
+ }
if (button_stop) {
- pinMode(button_stop, INPUT);
- digitalWrite(button_stop, HIGH);
- }
+ pinModeEnhanced(button_stop, INPUT);
+ digitalWriteEnhanced(button_stop, HIGH);
+ }
#ifdef FEATURE_ELEVATION_CONTROL
if (brake_el) {
- pinMode(brake_el, OUTPUT);
- digitalWrite(brake_el, LOW);
- }
- #endif //FEATURE_ELEVATION_CONTROL
-
- if (rotate_cw) {pinMode(rotate_cw, OUTPUT);}
- if (rotate_ccw) {pinMode(rotate_ccw, OUTPUT);}
- if (rotate_cw_pwm) {pinMode(rotate_cw_pwm, OUTPUT);}
- if (rotate_ccw_pwm) {pinMode(rotate_ccw_pwm, OUTPUT);}
- if (rotate_cw_ccw_pwm) {pinMode(rotate_cw_ccw_pwm, OUTPUT);}
- if (rotate_cw_freq) {pinMode(rotate_cw_freq, OUTPUT);}
- if (rotate_ccw_freq) {pinMode(rotate_ccw_freq, OUTPUT);}
-
- rotator(DEACTIVATE,CW);
- rotator(DEACTIVATE,CCW);
+ pinModeEnhanced(brake_el, OUTPUT);
+ digitalWriteEnhanced(brake_el, LOW);
+ }
+ #endif // FEATURE_ELEVATION_CONTROL
+
+ if (rotate_cw) {
+ pinModeEnhanced(rotate_cw, OUTPUT);
+ }
+ if (rotate_ccw) {
+ pinModeEnhanced(rotate_ccw, OUTPUT);
+ }
+ if (rotate_cw_pwm) {
+ pinModeEnhanced(rotate_cw_pwm, OUTPUT);
+ }
+ if (rotate_ccw_pwm) {
+ pinModeEnhanced(rotate_ccw_pwm, OUTPUT);
+ }
+ if (rotate_cw_ccw_pwm) {
+ pinModeEnhanced(rotate_cw_ccw_pwm, OUTPUT);
+ }
+ if (rotate_cw_freq) {
+ pinModeEnhanced(rotate_cw_freq, OUTPUT);
+ }
+ if (rotate_ccw_freq) {
+ pinModeEnhanced(rotate_ccw_freq, OUTPUT);
+ }
+
+ rotator(DEACTIVATE, CW);
+ rotator(DEACTIVATE, CCW);
#ifndef FEATURE_AZ_POSITION_HMC5883L
- pinMode(rotator_analog_az, INPUT);
+ pinModeEnhanced(rotator_analog_az, INPUT);
#endif
-
+
if (button_cw) {
- pinMode(button_cw, INPUT);
- digitalWrite(button_cw, HIGH);
+ pinModeEnhanced(button_cw, INPUT);
+ digitalWriteEnhanced(button_cw, HIGH);
}
if (button_ccw) {
- pinMode(button_ccw, INPUT);
- digitalWrite(button_ccw, HIGH);
+ pinModeEnhanced(button_ccw, INPUT);
+ digitalWriteEnhanced(button_ccw, HIGH);
}
-
+
normal_az_speed_voltage = PWM_SPEED_VOLTAGE_X4;
current_az_speed_voltage = PWM_SPEED_VOLTAGE_X4;
-
+
+ #ifdef FEATURE_ELEVATION_CONTROL
+ normal_el_speed_voltage = PWM_SPEED_VOLTAGE_X4;
+ current_el_speed_voltage = PWM_SPEED_VOLTAGE_X4;
+ #endif // FEATURE_ELEVATION_CONTROL
+
if (azimuth_speed_voltage) { // if azimuth_speed_voltage pin is configured, set it up for PWM output
- analogWrite(azimuth_speed_voltage, PWM_SPEED_VOLTAGE_X4);
+ analogWriteEnhanced(azimuth_speed_voltage, PWM_SPEED_VOLTAGE_X4);
}
-
+
#ifdef FEATURE_ELEVATION_CONTROL
- pinMode(rotate_up, OUTPUT);
- pinMode(rotate_down, OUTPUT);
- if (rotate_up_or_down) {pinMode(rotate_up_or_down, OUTPUT);}
- if (rotate_up_pwm) {pinMode(rotate_up_pwm, OUTPUT);}
- if (rotate_down_pwm) {pinMode(rotate_down_pwm, OUTPUT);}
- if (rotate_up_down_pwm) {pinMode(rotate_up_down_pwm, OUTPUT);}
- if (rotate_up_freq) {pinMode(rotate_up_freq, OUTPUT);}
- if (rotate_down_freq) {pinMode(rotate_down_freq, OUTPUT);}
- rotator(DEACTIVATE,UP);
- rotator(DEACTIVATE,DOWN);
+ pinModeEnhanced(rotate_up, OUTPUT);
+ pinModeEnhanced(rotate_down, OUTPUT);
+ if (rotate_up_or_down) {
+ pinModeEnhanced(rotate_up_or_down, OUTPUT);
+ }
+ if (rotate_up_pwm) {
+ pinModeEnhanced(rotate_up_pwm, OUTPUT);
+ }
+ if (rotate_down_pwm) {
+ pinModeEnhanced(rotate_down_pwm, OUTPUT);
+ }
+ if (rotate_up_down_pwm) {
+ pinModeEnhanced(rotate_up_down_pwm, OUTPUT);
+ }
+ if (rotate_up_freq) {
+ pinModeEnhanced(rotate_up_freq, OUTPUT);
+ }
+ if (rotate_down_freq) {
+ pinModeEnhanced(rotate_down_freq, OUTPUT);
+ }
+ rotator(DEACTIVATE, UP);
+ rotator(DEACTIVATE, DOWN);
#ifdef FEATURE_EL_POSITION_POTENTIOMETER
- pinMode(rotator_analog_el, INPUT);
- #endif //FEATURE_EL_POSITION_POTENTIOMETER
+ pinModeEnhanced(rotator_analog_el, INPUT);
+ #endif // FEATURE_EL_POSITION_POTENTIOMETER
if (button_up) {
- pinMode(button_up, INPUT);
- digitalWrite(button_up, HIGH);
+ pinModeEnhanced(button_up, INPUT);
+ digitalWriteEnhanced(button_up, HIGH);
}
if (button_down) {
- pinMode(button_down, INPUT);
- digitalWrite(button_down, HIGH);
+ pinModeEnhanced(button_down, INPUT);
+ digitalWriteEnhanced(button_down, HIGH);
}
-
+
if (elevation_speed_voltage) { // if elevation_speed_voltage pin is configured, set it up for PWM output
- analogWrite(elevation_speed_voltage, PWM_SPEED_VOLTAGE_X4);
+ analogWriteEnhanced(elevation_speed_voltage, PWM_SPEED_VOLTAGE_X4);
normal_el_speed_voltage = PWM_SPEED_VOLTAGE_X4;
current_el_speed_voltage = PWM_SPEED_VOLTAGE_X4;
- }
-
- read_elevation();
- #endif //FEATURE_ELEVATION_CONTROL
-
+ }
+
+ read_elevation(0);
+ #endif // FEATURE_ELEVATION_CONTROL
+
#ifdef FEATURE_AZ_POSITION_PULSE_INPUT
if (az_position_pulse_pin) {
- pinMode(az_position_pulse_pin, INPUT);
+ pinModeEnhanced(az_position_pulse_pin, INPUT);
#ifdef OPTION_POSITION_PULSE_INPUT_PULLUPS
- digitalWrite(az_position_pulse_pin, HIGH);
- #endif //OPTION_POSITION_PULSE_INPUT_PULLUPS
+ digitalWriteEnhanced(az_position_pulse_pin, HIGH);
+ #endif // OPTION_POSITION_PULSE_INPUT_PULLUPS
}
- #endif //FEATURE_AZ_POSITION_PULSE_INPUT
-
-
+ #endif // FEATURE_AZ_POSITION_PULSE_INPUT
+
+
#ifdef FEATURE_EL_POSITION_PULSE_INPUT
if (el_position_pulse_pin) {
- pinMode(el_position_pulse_pin, INPUT);
+ pinModeEnhanced(el_position_pulse_pin, INPUT);
#ifdef OPTION_POSITION_PULSE_INPUT_PULLUPS
- digitalWrite(el_position_pulse_pin, HIGH);
- #endif //OPTION_POSITION_PULSE_INPUT_PULLUPS
+ digitalWriteEnhanced(el_position_pulse_pin, HIGH);
+ #endif // OPTION_POSITION_PULSE_INPUT_PULLUPS
}
- #endif //FEATURE_EL_POSITION_PULSE_INPUT
-
- #ifdef FEATURE_PARK
- if (button_park){
- pinMode(button_park, INPUT);
- digitalWrite(button_park, HIGH);
- }
- #endif //FEATURE_PARK
-
- #ifdef FEATURE_ROTATION_INDICATOR_PIN
- if (rotation_indication_pin){
- pinMode(rotation_indication_pin, OUTPUT);
- digitalWrite(rotation_indication_pin,ROTATION_INDICATOR_PIN_INACTIVE_STATE);
- }
- #endif //FEATURE_ROTATION_INDICATOR_PIN
-
- if (blink_led) {pinMode(blink_led,OUTPUT);}
-}
+ #endif // FEATURE_EL_POSITION_PULSE_INPUT
-//--------------------------------------------------------------
+ #ifdef FEATURE_PARK
+ if (button_park) {
+ pinModeEnhanced(button_park, INPUT);
+ digitalWriteEnhanced(button_park, HIGH);
+ }
+ #endif // FEATURE_PARK
+
+ #ifdef FEATURE_ROTATION_INDICATOR_PIN
+ if (rotation_indication_pin) {
+ pinModeEnhanced(rotation_indication_pin, OUTPUT);
+ digitalWriteEnhanced(rotation_indication_pin, ROTATION_INDICATOR_PIN_INACTIVE_STATE);
+ }
+ #endif // FEATURE_ROTATION_INDICATOR_PIN
+
+ #ifdef FEATURE_PARK
+ if (park_in_progress_pin) {
+ pinModeEnhanced(park_in_progress_pin, OUTPUT);
+ digitalWriteEnhanced(park_in_progress_pin, LOW);
+ }
+ if (parked_pin) {
+ pinModeEnhanced(parked_pin, OUTPUT);
+ digitalWriteEnhanced(parked_pin, LOW);
+ }
+ #endif // FEATURE_PARK
+
+ if (blink_led) {
+ pinModeEnhanced(blink_led, OUTPUT);
+ }
+
+ if (heading_reading_inhibit_pin) {
+ pinModeEnhanced(heading_reading_inhibit_pin, INPUT);
+ }
+
+ #ifdef FEATURE_LIMIT_SENSE
+ if (az_limit_sense_pin) {
+ pinModeEnhanced(az_limit_sense_pin, INPUT);
+ digitalWriteEnhanced(az_limit_sense_pin, HIGH);
+ }
+ #ifdef FEATURE_ELEVATION_CONTROL
+ if (el_limit_sense_pin) {
+ pinModeEnhanced(el_limit_sense_pin, INPUT);
+ digitalWriteEnhanced(el_limit_sense_pin, HIGH);
+ }
+ #endif // FEATURE_ELEVATION_CONTROL
+ #endif // FEATURE_LIMIT_SENSE
+
+ #ifdef FEATURE_MOON_TRACKING
+ if (moon_tracking_active_pin) {
+ pinModeEnhanced(moon_tracking_active_pin, OUTPUT);
+ digitalWriteEnhanced(moon_tracking_active_pin, LOW);
+ }
+ if (moon_tracking_activate_line) {
+ pinModeEnhanced(moon_tracking_activate_line, INPUT);
+ digitalWriteEnhanced(moon_tracking_activate_line, HIGH);
+ }
+ if (moon_tracking_button) {
+ pinModeEnhanced(moon_tracking_button, INPUT);
+ digitalWriteEnhanced(moon_tracking_button, HIGH);
+ }
+ #endif // FEATURE_MOON_TRACKING
+
+
+ #ifdef FEATURE_SUN_TRACKING
+ if (sun_tracking_active_pin) {
+ pinModeEnhanced(sun_tracking_active_pin, OUTPUT);
+ digitalWriteEnhanced(sun_tracking_active_pin, LOW);
+ }
+ if (sun_tracking_activate_line) {
+ pinModeEnhanced(sun_tracking_activate_line, INPUT);
+ digitalWriteEnhanced(sun_tracking_activate_line, HIGH);
+ }
+ if (sun_tracking_button) {
+ pinModeEnhanced(sun_tracking_button, INPUT);
+ digitalWriteEnhanced(sun_tracking_button, HIGH);
+ }
+ #endif // FEATURE_SUN_TRACKING
+
+
+ #ifdef FEATURE_GPS
+ if (gps_sync) {
+ pinModeEnhanced(gps_sync, OUTPUT);
+ digitalWriteEnhanced(gps_sync, LOW);
+ }
+ #endif //FEATURE_GPS
+
+ #ifdef FEATURE_POWER_SWITCH
+ pinModeEnhanced(power_switch, OUTPUT);
+ digitalWriteEnhanced(power_switch, HIGH);
+ #endif //FEATURE_POWER_SWITCH
+
+ #ifdef FEATURE_STEPPER_MOTOR
+ if (az_stepper_motor_pulse){
+ pinModeEnhanced(az_stepper_motor_pulse, OUTPUT);
+ digitalWriteEnhanced(az_stepper_motor_pulse, HIGH);
+ }
+
+ if (az_stepper_motor_direction){
+ pinModeEnhanced(az_stepper_motor_direction, OUTPUT);
+ digitalWriteEnhanced(az_stepper_motor_direction, LOW);
+ }
+
+
+ #ifdef FEATURE_ELEVATION_CONTROL
+ if (el_stepper_motor_pulse){
+ pinModeEnhanced(el_stepper_motor_pulse, OUTPUT);
+ digitalWriteEnhanced(el_stepper_motor_pulse, HIGH);
+ }
+
+ if (el_stepper_motor_direction){
+ pinModeEnhanced(el_stepper_motor_direction, OUTPUT);
+ digitalWriteEnhanced(el_stepper_motor_direction, LOW);
+ }
+ #endif //FEATURE_ELEVATION_CONTROL
+ #endif //FEATURE_STEPPER_MOTOR
+
+ #ifdef FEATURE_EL_POSITION_MEMSIC_2125
+ pinModeEnhanced(pin_memsic_2125_x, INPUT);
+ pinModeEnhanced(pin_memsic_2125_y, INPUT);
+ #endif //FEATURE_EL_POSITION_MEMSIC_2125
+
+
+} /* initialize_pins */
+
+// --------------------------------------------------------------
void initialize_serial(){
-
- Serial.begin(SERIAL_BAUD_RATE);
-
- #ifdef FEATURE_REMOTE_UNIT_SLAVE
- Serial.print(F("CS"));
- Serial.println(CODE_VERSION);
- #endif //FEATURE_REMOTE_UNIT_SLAVE
-
- #ifdef OPTION_SERIAL1_SUPPORT
- Serial1.begin(SERIAL1_BAUD_RATE);
- #endif //OPTION_SERIAL1_SUPPORT
-
- #ifdef OPTION_SERIAL2_SUPPORT
- Serial1.begin(SERIAL2_BAUD_RATE);
- #endif //OPTION_SERIAL2_SUPPORT
-
- #ifdef OPTION_SERIAL2_SUPPORT
- Serial1.begin(SERIAL2_BAUD_RATE);
- #endif //OPTION_SERIAL2_SUPPORT
-
-}
-//--------------------------------------------------------------
+ #if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION) || defined(FEATURE_CLOCK)
+ control_port = CONTROL_PORT_MAPPED_TO;
+ control_port->begin(CONTROL_PORT_BAUD_RATE);
+ #endif
+
+ #ifdef FEATURE_REMOTE_UNIT_SLAVE
+ control_port->print(F("CS"));
+ control_port->println(CODE_VERSION);
+ #endif // FEATURE_REMOTE_UNIT_SLAVE
+
+ #if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE)
+ remote_unit_port = REMOTE_PORT_MAPPED_TO;
+ remote_unit_port->begin(REMOTE_UNIT_PORT_BAUD_RATE);
+ #endif
+
+ #ifdef FEATURE_GPS
+ gps_port = GPS_PORT_MAPPED_TO;
+ gps_port->begin(GPS_PORT_BAUD_RATE);
+ #ifdef GPS_MIRROR_PORT
+ gps_mirror_port = GPS_MIRROR_PORT;
+ gps_mirror_port->begin(GPS_MIRROR_PORT_BAUD_RATE);
+ #endif //GPS_MIRROR_PORT
+ #endif //FEATURE_GPS
+
+} /* initialize_serial */
+
+// --------------------------------------------------------------
#ifdef FEATURE_LCD_DISPLAY
void initialize_display(){
-
-
- #ifndef OPTION_INITIALIZE_YOURDUINO_I2C
- lcd.begin(LCD_COLUMNS, 2);
- #endif
-
- #ifdef OPTION_INITIALIZE_YOURDUINO_I2C
- lcd.begin (16,2);
- lcd.setBacklightPin(BACKLIGHT_PIN,POSITIVE);
- lcd.setBacklight(LED_ON);
- #endif //OPTION_INITIALIZE_YOURDUINO_I2C
-
- #ifdef FEATURE_I2C_LCD
- lcd.setBacklight(lcdcolor);
- #endif //FEATURE_I2C_LCD
-
- lcd.setCursor(((LCD_COLUMNS-4)/2),0);
- lcd.print("K3NG");
- if (LCD_COLUMNS < 20) {
- lcd.setCursor(((LCD_COLUMNS-15)/2),1); // W3SA
- } else {
- lcd.setCursor(((LCD_COLUMNS-18)/2),1);
- }
- lcd.print("Rotor Controller");
- last_lcd_update = millis();
-
-}
-#endif
-//--------------------------------------------------------------
+ byte start_row = 0;
+
+
+ lcd.begin(LCD_COLUMNS, LCD_ROWS);
+
+ #ifdef FEATURE_YOURDUINO_I2C_LCD
+ lcd.setBacklightPin(BACKLIGHT_PIN, POSITIVE);
+ lcd.setBacklight(I2C_LCD_COLOR);
+ #endif // FEATURE_YOURDUINO_I2C_LCD
+
+ #ifdef FEATURE_ADAFRUIT_I2C_LCD
+ lcd.setBacklight(I2C_LCD_COLOR);
+ #endif // FEATURE_ADAFRUIT_I2C_LCD
+
+ if (LCD_ROWS == 4){start_row = 1;}
+
+ lcd.setCursor(((LCD_COLUMNS - 4) / 2), start_row);
+ lcd.print("\x4B\x33\x4E\x47");
+ lcd.setCursor(((LCD_COLUMNS - 16) / 2), start_row + 1);
+ lcd.print("\x52\x6F\x74\x6F\x72\x20\x43\x6F\x6E\x74\x72\x6F\x6C\x6C\x65\x72");
+ last_lcd_update = millis();
+
+} /* initialize_display */
+#endif /* ifdef FEATURE_LCD_DISPLAY */
+
+// --------------------------------------------------------------
void initialize_peripherals(){
-
- #ifdef FEATURE_WIRE_SUPPORT
+
+ #ifdef FEATURE_WIRE_SUPPORT
Wire.begin();
#endif
-
+
#ifdef FEATURE_AZ_POSITION_HMC5883L
compass = HMC5883L();
- int error;
- error = compass.SetScale(1.3); //Set the scale of the compass.
+ int error;
+ error = compass.SetScale(1.3); // Set the scale of the compass.
+ #ifndef OPTION_DISABLE_HMC5883L_ERROR_CHECKING
if (error != 0) {
- Serial.print(F("setup: compass error:"));
- Serial.println(compass.GetErrorText(error)); //check if there is an error, and print if so
+ #if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
+ control_port->print(F("setup: compass error:"));
+ control_port->println(compass.GetErrorText(error)); // check if there is an error, and print if so
+ #endif
}
+ #endif //OPTION_DISABLE_HMC5883L_ERROR_CHECKING
error = compass.SetMeasurementMode(Measurement_Continuous); // Set the measurement mode to Continuous
+ #ifndef OPTION_DISABLE_HMC5883L_ERROR_CHECKING
if (error != 0) {
- Serial.print(F("setup: compass error:"));
- Serial.println(compass.GetErrorText(error)); //check if there is an error, and print if so
+ #if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
+ control_port->print(F("setup: compass error:"));
+ control_port->println(compass.GetErrorText(error)); // check if there is an error, and print if so
+ #endif
}
- #endif //FEATURE_AZ_POSITION_HMC5883L
-
+ #endif //OPTION_DISABLE_HMC5883L_ERROR_CHECKING
+ #endif // FEATURE_AZ_POSITION_HMC5883L
+
#ifdef FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB
accel = ADXL345();
accel.SetRange(2, true);
accel.EnableMeasurements();
- #endif //FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB
-
+ #endif // FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB
+
#ifdef FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB
accel.begin();
- #endif //FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB
-
+ #endif // FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB
+
#ifdef FEATURE_JOYSTICK_CONTROL
- pinMode(pin_joystick_x,INPUT);
- pinMode(pin_joystick_y,INPUT);
- #endif //FEATURE_JOYSTICK_CONTROL
-
+ pinModeEnhanced(pin_joystick_x, INPUT);
+ pinModeEnhanced(pin_joystick_y, INPUT);
+ #endif // FEATURE_JOYSTICK_CONTROL
+
#if defined(FEATURE_EL_POSITION_LSM303) || defined(FEATURE_AZ_POSITION_LSM303)
- if (!lsm.begin()){
- Serial.println(F("setup: LSM303 error"));
- }
- #endif //FEATURE_EL_POSITION_LSM303 || FEATURE_AZ_POSITION_LSM303
-
-}
+ if (!lsm.begin()) {
+ #if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
+ control_port->println(F("setup: LSM303 error"));
+ #endif
+ }
+ #endif // FEATURE_EL_POSITION_LSM303 || FEATURE_AZ_POSITION_LSM303
+
+ #ifdef FEATURE_AZ_POSITION_HH12_AS5045_SSI
+ azimuth_hh12.initialize(az_hh12_clock_pin, az_hh12_cs_pin, az_hh12_data_pin);
+ #endif // FEATURE_AZ_POSITION_HH12_AS5045_SSI
+
+ #ifdef FEATURE_EL_POSITION_HH12_AS5045_SSI
+ elevation_hh12.initialize(el_hh12_clock_pin, el_hh12_cs_pin, el_hh12_data_pin);
+ #endif // FEATURE_EL_POSITION_HH12_AS5045_SSI
+
+ #ifdef FEATURE_RTC_DS1307
+ rtc.begin();
+ #endif // FEATURE_RTC_DS1307
+
+ #ifdef FEATURE_ETHERNET
+ Ethernet.begin(mac, ip, gateway, subnet);
+ ethernetserver0.begin();
+ #endif //FEATURE_ETHERNET
+
+} /* initialize_peripherals */
-//--------------------------------------------------------------
-void submit_request(byte axis, byte request, int parm){
-
- #ifdef DEBUG_SUBMIT_REQUEST
- if (debug_mode) {Serial.print(F("submit_request: "));}
- #endif //DEBUG_SUBMIT_REQUEST
-
+// --------------------------------------------------------------
+void submit_request(byte axis, byte request, int parm, byte called_by){
+
+ #ifdef DEBUG_SUBMIT_REQUEST
+ debug_print("submit_request: ");
+ debug_print_int(called_by);
+ debug_print(" ");
+ #endif // DEBUG_SUBMIT_REQUEST
+
+ #ifdef FEATURE_PARK
+ park_status = NOT_PARKED;
+ #endif // FEATURE_PARK
+
if (axis == AZ) {
#ifdef DEBUG_SUBMIT_REQUEST
- if (debug_mode) {Serial.print(F("AZ "));Serial.print(request);Serial.print(F(" "));Serial.println(parm);}
- #endif //DEBUG_SUBMIT_REQUEST
+ debug_print("AZ ");
+ #endif // DEBUG_SUBMIT_REQUEST
az_request = request;
az_request_parm = parm;
az_request_queue_state = IN_QUEUE;
- }
+ }
#ifdef FEATURE_ELEVATION_CONTROL
if (axis == EL) {
#ifdef DEBUG_SUBMIT_REQUEST
- if (debug_mode) {Serial.print(F("EL "));Serial.print(request);Serial.print(F(" "));Serial.println(parm);}
- #endif //DEBUG_SUBMIT_REQUEST
+ debug_print("EL ");
+ #endif // DEBUG_SUBMIT_REQUEST
el_request = request;
el_request_parm = parm;
el_request_queue_state = IN_QUEUE;
- }
- #endif //FEATURE_ELEVATION_CONTROL
-
-}
-//--------------------------------------------------------------
-void service_rotation(){
-
+ }
+ #endif // FEATURE_ELEVATION_CONTROL
+
+ #ifdef DEBUG_SUBMIT_REQUEST
+ switch(request){
+ case 0: debug_print("REQUEST_STOP");break;
+ case 1: debug_print("REQUEST_AZIMUTH");break;
+ case 2: debug_print("REQUEST_AZIMUTH_RAW");break;
+ case 3: debug_print("REQUEST_CW");break;
+ case 4: debug_print("REQUEST_CCW");break;
+ case 5: debug_print("REQUEST_UP");break;
+ case 6: debug_print("REQUEST_DOWN");break;
+ case 7: debug_print("REQUEST_ELEVATION");break;
+ case 8: debug_print("REQUEST_KILL");break;
+ }
+ debug_print(" ");
+ debug_print_int(parm);
+ debug_println("");
+ #endif // DEBUG_SUBMIT_REQUEST
+
+} /* submit_request */
+// --------------------------------------------------------------
+void service_rotation(){
+
static byte az_direction_change_flag = 0;
static byte az_initial_slow_down_voltage = 0;
-
+
#ifdef FEATURE_ELEVATION_CONTROL
static byte el_direction_change_flag = 0;
- static byte el_initial_slow_down_voltage = 0;
- #endif //FEATURE_ELEVATION_CONTROL
+ static byte el_initial_slow_down_voltage = 0;
+ #endif // FEATURE_ELEVATION_CONTROL
if (az_state == INITIALIZE_NORMAL_CW) {
update_az_variable_outputs(normal_az_speed_voltage);
- rotator(ACTIVATE,CW);
+ rotator(ACTIVATE, CW);
az_state = NORMAL_CW;
}
if (az_state == INITIALIZE_NORMAL_CCW) {
update_az_variable_outputs(normal_az_speed_voltage);
- rotator(ACTIVATE,CCW);
+ rotator(ACTIVATE, CCW);
az_state = NORMAL_CCW;
}
-
- if (az_state == INITIALIZE_SLOW_START_CW){
+
+ if (az_state == INITIALIZE_SLOW_START_CW) {
update_az_variable_outputs(AZ_SLOW_START_STARTING_PWM);
- rotator(ACTIVATE,CW);
+ rotator(ACTIVATE, CW);
az_slowstart_start_time = millis();
az_last_step_time = 0;
az_slow_start_step = 0;
az_state = SLOW_START_CW;
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.println(F("service_rotation: INITIALIZE_SLOW_START_CW -> SLOW_START_CW"));}
- #endif //DEBUG_SERVICE_ROTATION
+ debug_print("service_rotation: INITIALIZE_SLOW_START_CW -> SLOW_START_CW");
+ #endif // DEBUG_SERVICE_ROTATION
}
-
- if (az_state == INITIALIZE_SLOW_START_CCW){
+
+ if (az_state == INITIALIZE_SLOW_START_CCW) {
update_az_variable_outputs(AZ_SLOW_START_STARTING_PWM);
- rotator(ACTIVATE,CCW);
+ rotator(ACTIVATE, CCW);
az_slowstart_start_time = millis();
az_last_step_time = 0;
az_slow_start_step = 0;
az_state = SLOW_START_CCW;
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.println(F("service_rotation: INITIALIZE_SLOW_START_CCW -> SLOW_START_CCW"));}
- #endif //DEBUG_SERVICE_ROTATION
- }
-
+ debug_print("service_rotation: INITIALIZE_SLOW_START_CCW -> SLOW_START_CCW");
+ #endif // DEBUG_SERVICE_ROTATION
+ }
+
if (az_state == INITIALIZE_TIMED_SLOW_DOWN_CW) {
az_direction_change_flag = 0;
az_timed_slow_down_start_time = millis();
az_last_step_time = millis();
- az_slow_down_step = AZ_SLOW_DOWN_STEPS-1;
+ az_slow_down_step = AZ_SLOW_DOWN_STEPS - 1;
az_state = TIMED_SLOW_DOWN_CW;
}
-
+
if (az_state == INITIALIZE_TIMED_SLOW_DOWN_CCW) {
az_direction_change_flag = 0;
az_timed_slow_down_start_time = millis();
az_last_step_time = millis();
- az_slow_down_step = AZ_SLOW_DOWN_STEPS-1;
+ az_slow_down_step = AZ_SLOW_DOWN_STEPS - 1;
az_state = TIMED_SLOW_DOWN_CCW;
- }
-
+ }
+
if (az_state == INITIALIZE_DIR_CHANGE_TO_CW) {
az_direction_change_flag = 1;
az_timed_slow_down_start_time = millis();
az_last_step_time = millis();
- az_slow_down_step = AZ_SLOW_DOWN_STEPS-1;
- az_state = TIMED_SLOW_DOWN_CCW;
+ az_slow_down_step = AZ_SLOW_DOWN_STEPS - 1;
+ az_state = TIMED_SLOW_DOWN_CCW;
}
-
- if (az_state == INITIALIZE_DIR_CHANGE_TO_CCW) {
+
+ if (az_state == INITIALIZE_DIR_CHANGE_TO_CCW) {
az_direction_change_flag = 1;
az_timed_slow_down_start_time = millis();
az_last_step_time = millis();
- az_slow_down_step = AZ_SLOW_DOWN_STEPS-1;
- az_state = TIMED_SLOW_DOWN_CW;
+ az_slow_down_step = AZ_SLOW_DOWN_STEPS - 1;
+ az_state = TIMED_SLOW_DOWN_CW;
}
-
+
// slow start-------------------------------------------------------------------------------------------------
- if ((az_state == SLOW_START_CW) || (az_state == SLOW_START_CCW)) {
- if ((millis() - az_slowstart_start_time) >= AZ_SLOW_START_UP_TIME) { // is it time to end slow start?
+ if ((az_state == SLOW_START_CW) || (az_state == SLOW_START_CCW)) {
+ if ((millis() - az_slowstart_start_time) >= AZ_SLOW_START_UP_TIME) { // is it time to end slow start?
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.print(F("service_rotation: NORMAL_C"));}
- #endif //DEBUG_SERVICE_ROTATION
+ debug_print("service_rotation: NORMAL_C");
+ #endif // DEBUG_SERVICE_ROTATION
if (az_state == SLOW_START_CW) {
az_state = NORMAL_CW;
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.println(F("W"));}
- #endif //DEBUG_SERVICE_ROTATION
+ debug_print("W");
+ #endif // DEBUG_SERVICE_ROTATION
} else {
az_state = NORMAL_CCW;
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.println(F("CW"));}
- #endif //DEBUG_SERVICE_ROTATION
- }
- update_az_variable_outputs(normal_az_speed_voltage);
+ debug_print("CW");
+ #endif // DEBUG_SERVICE_ROTATION
+ }
+ update_az_variable_outputs(normal_az_speed_voltage);
} else { // it's not time to end slow start yet, but let's check if it's time to step up the speed voltage
- if (((millis() - az_last_step_time) > (AZ_SLOW_START_UP_TIME/AZ_SLOW_START_STEPS)) && (normal_az_speed_voltage > AZ_SLOW_START_STARTING_PWM)){
+ if (((millis() - az_last_step_time) > (AZ_SLOW_START_UP_TIME / AZ_SLOW_START_STEPS)) && (normal_az_speed_voltage > AZ_SLOW_START_STARTING_PWM)) {
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {
- Serial.print(F("service_rotation: step up: "));
- Serial.print(az_slow_start_step);
- Serial.print(F(" pwm: "));
- Serial.println((int)(AZ_SLOW_START_STARTING_PWM+((normal_az_speed_voltage-AZ_SLOW_START_STARTING_PWM)*((float)az_slow_start_step/(float)(AZ_SLOW_START_STEPS-1)))));
- }
- #endif //DEBUG_SERVICE_ROTATION
- update_az_variable_outputs((AZ_SLOW_START_STARTING_PWM+((normal_az_speed_voltage-AZ_SLOW_START_STARTING_PWM)*((float)az_slow_start_step/(float)(AZ_SLOW_START_STEPS-1)))));
- az_last_step_time = millis();
+ debug_print("service_rotation: step up: ");
+ debug_print_int(az_slow_start_step);
+ debug_print(" pwm: ");
+ debug_print_int((int)(AZ_SLOW_START_STARTING_PWM + ((normal_az_speed_voltage - AZ_SLOW_START_STARTING_PWM) * ((float)az_slow_start_step / (float)(AZ_SLOW_START_STEPS - 1)))));
+ debug_println("");
+ #endif // DEBUG_SERVICE_ROTATION
+ update_az_variable_outputs((AZ_SLOW_START_STARTING_PWM + ((normal_az_speed_voltage - AZ_SLOW_START_STARTING_PWM) * ((float)az_slow_start_step / (float)(AZ_SLOW_START_STEPS - 1)))));
+ az_last_step_time = millis();
az_slow_start_step++;
- }
- }
- } //((az_state == SLOW_START_CW) || (az_state == SLOW_START_CCW))
+ }
+ }
+ } // ((az_state == SLOW_START_CW) || (az_state == SLOW_START_CCW))
// timed slow down ------------------------------------------------------------------------------------------------------
- if (((az_state == TIMED_SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CCW)) && ((millis() - az_last_step_time) >= (TIMED_SLOW_DOWN_TIME/AZ_SLOW_DOWN_STEPS))) {
+ if (((az_state == TIMED_SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CCW)) && ((millis() - az_last_step_time) >= (TIMED_SLOW_DOWN_TIME / AZ_SLOW_DOWN_STEPS))) {
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {
- Serial.print(F("service_rotation: TIMED_SLOW_DOWN step down: "));
- Serial.print(az_slow_down_step);
- Serial.print(F(" pwm: "));
- Serial.println((int)(normal_az_speed_voltage*((float)az_slow_down_step/(float)AZ_SLOW_DOWN_STEPS)));
- }
- #endif //DEBUG_SERVICE_ROTATION
- update_az_variable_outputs((int)(normal_az_speed_voltage*((float)az_slow_down_step/(float)AZ_SLOW_DOWN_STEPS)));
- az_last_step_time = millis();
- az_slow_down_step--;
-
+ debug_print("service_rotation: TIMED_SLOW_DOWN step down: ");
+ debug_print_int(az_slow_down_step);
+ debug_print(" pwm: ");
+ debug_print_int((int)(normal_az_speed_voltage * ((float)az_slow_down_step / (float)AZ_SLOW_DOWN_STEPS)));
+ debug_println("");
+ #endif // DEBUG_SERVICE_ROTATION
+ update_az_variable_outputs((int)(normal_az_speed_voltage * ((float)az_slow_down_step / (float)AZ_SLOW_DOWN_STEPS)));
+ az_last_step_time = millis();
+ if (az_slow_down_step > 0) {az_slow_down_step--;}
+
if (az_slow_down_step == 0) { // is it time to exit timed slow down?
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.println(F("service_rotation: TIMED_SLOW_DOWN->IDLE"));}
- #endif //DEBUG_SERVICE_ROTATION
- rotator(DEACTIVATE,CW);
- rotator(DEACTIVATE,CCW);
+ debug_print("service_rotation: TIMED_SLOW_DOWN->IDLE");
+ #endif // DEBUG_SERVICE_ROTATION
+ rotator(DEACTIVATE, CW);
+ rotator(DEACTIVATE, CCW);
if (az_direction_change_flag) {
if (az_state == TIMED_SLOW_DOWN_CW) {
- rotator(ACTIVATE,CCW);
- if (az_slowstart_active) {az_state = INITIALIZE_SLOW_START_CCW;} else {az_state = NORMAL_CCW;};
+ //rotator(ACTIVATE, CCW);
+ if (az_slowstart_active) {
+ az_state = INITIALIZE_SLOW_START_CCW;
+ } else { az_state = NORMAL_CCW; };
az_direction_change_flag = 0;
}
if (az_state == TIMED_SLOW_DOWN_CCW) {
- rotator(ACTIVATE,CW);
- if (az_slowstart_active) {az_state = INITIALIZE_SLOW_START_CW;} else {az_state = NORMAL_CW;};
+ //rotator(ACTIVATE, CW);
+ if (az_slowstart_active) {
+ az_state = INITIALIZE_SLOW_START_CW;
+ } else { az_state = NORMAL_CW; };
az_direction_change_flag = 0;
}
} else {
az_state = IDLE;
- az_request_queue_state = NONE;
- }
+ az_request_queue_state = NONE;
+ }
}
-
- } //((az_state == TIMED_SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CCW))
-
+
+ } // ((az_state == TIMED_SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CCW))
+
// slow down ---------------------------------------------------------------------------------------------------------------
- if ((az_state == SLOW_DOWN_CW) || (az_state == SLOW_DOWN_CCW)) {
+ if ((az_state == SLOW_DOWN_CW) || (az_state == SLOW_DOWN_CCW)) {
+
// is it time to do another step down?
- if (abs((target_raw_azimuth - raw_azimuth)/HEADING_MULTIPLIER) <= (((float)SLOW_DOWN_BEFORE_TARGET_AZ*((float)az_slow_down_step/(float)AZ_SLOW_DOWN_STEPS)))){
+ if (abs((target_raw_azimuth - raw_azimuth) / HEADING_MULTIPLIER) <= (((float)SLOW_DOWN_BEFORE_TARGET_AZ * ((float)az_slow_down_step / (float)AZ_SLOW_DOWN_STEPS)))) {
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {
- Serial.print(F("service_rotation: step down: "));
- Serial.print(az_slow_down_step);
- Serial.print(F(" pwm: "));
- Serial.println((int)(AZ_SLOW_DOWN_PWM_STOP+((az_initial_slow_down_voltage-AZ_SLOW_DOWN_PWM_STOP)*((float)az_slow_down_step/(float)AZ_SLOW_DOWN_STEPS))));
- }
- #endif //DEBUG_SERVICE_ROTATION
- update_az_variable_outputs((AZ_SLOW_DOWN_PWM_STOP+((az_initial_slow_down_voltage-AZ_SLOW_DOWN_PWM_STOP)*((float)az_slow_down_step/(float)AZ_SLOW_DOWN_STEPS))));
- az_slow_down_step--;
- }
- } //((az_state == SLOW_DOWN_CW) || (az_state == SLOW_DOWN_CCW))
-
+ debug_print("service_rotation: step down: ");
+ debug_print_int(az_slow_down_step);
+ debug_print(" pwm: ");
+ debug_print_int((int)(AZ_SLOW_DOWN_PWM_STOP + ((az_initial_slow_down_voltage - AZ_SLOW_DOWN_PWM_STOP) * ((float)az_slow_down_step / (float)AZ_SLOW_DOWN_STEPS))));
+ debug_println("");
+ #endif // DEBUG_SERVICE_ROTATION
+ update_az_variable_outputs((AZ_SLOW_DOWN_PWM_STOP + ((az_initial_slow_down_voltage - AZ_SLOW_DOWN_PWM_STOP) * ((float)az_slow_down_step / (float)AZ_SLOW_DOWN_STEPS))));
+ if (az_slow_down_step > 0) {az_slow_down_step--;}
+ }
+ } // ((az_state == SLOW_DOWN_CW) || (az_state == SLOW_DOWN_CCW))
+
// normal -------------------------------------------------------------------------------------------------------------------
// if slow down is enabled, see if we're ready to go into slowdown
- if (((az_state == NORMAL_CW) || (az_state == SLOW_START_CW) || (az_state == NORMAL_CCW) || (az_state == SLOW_START_CCW)) &&
- (az_request_queue_state == IN_PROGRESS_TO_TARGET) && az_slowdown_active && (abs((target_raw_azimuth - raw_azimuth)/HEADING_MULTIPLIER) <= SLOW_DOWN_BEFORE_TARGET_AZ)) {
+ if (((az_state == NORMAL_CW) || (az_state == SLOW_START_CW) || (az_state == NORMAL_CCW) || (az_state == SLOW_START_CCW)) &&
+ (az_request_queue_state == IN_PROGRESS_TO_TARGET) && az_slowdown_active && (abs((target_raw_azimuth - raw_azimuth) / HEADING_MULTIPLIER) <= SLOW_DOWN_BEFORE_TARGET_AZ)) {
+
+ byte az_state_was = az_state;
+
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.print(F("service_rotation: SLOW_DOWN_C"));}
- #endif //DEBUG_SERVICE_ROTATION
- az_slow_down_step = AZ_SLOW_DOWN_STEPS-1;
- if ((az_state == NORMAL_CW) || (az_state == SLOW_START_CW)){
+ debug_print("service_rotation: SLOW_DOWN_C");
+ #endif // DEBUG_SERVICE_ROTATION
+ az_slow_down_step = AZ_SLOW_DOWN_STEPS - 1;
+ if ((az_state == NORMAL_CW) || (az_state == SLOW_START_CW)) {
az_state = SLOW_DOWN_CW;
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.println(F("W"));}
- #endif //DEBUG_SERVICE_ROTATION
+ debug_print("W");
+ #endif // DEBUG_SERVICE_ROTATION
} else {
az_state = SLOW_DOWN_CCW;
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.println(F("CW"));}
- #endif //DEBUG_SERVICE_ROTATION
+ debug_print("CW");
+ #endif // DEBUG_SERVICE_ROTATION
}
- if (AZ_SLOW_DOWN_PWM_START < current_az_speed_voltage) {
- update_az_variable_outputs(AZ_SLOW_DOWN_PWM_START);
- az_initial_slow_down_voltage = AZ_SLOW_DOWN_PWM_START;
+ //aaaaaa
+ if ((az_state_was == SLOW_START_CW) || (az_state_was == SLOW_START_CCW)){
+ az_initial_slow_down_voltage = (AZ_INITIALLY_IN_SLOW_DOWN_PWM);
+ update_az_variable_outputs(az_initial_slow_down_voltage);
+ #ifdef DEBUG_SERVICE_ROTATION
+ debug_print(" SLOW_START -> SLOW_DOWN az_initial_slow_down_voltage:");
+ debug_print_int(az_initial_slow_down_voltage);
+ debug_print(" ");
+ #endif // DEBUG_SERVICE_ROTATION
} else {
- az_initial_slow_down_voltage = current_az_speed_voltage;
+ if (AZ_SLOW_DOWN_PWM_START < current_az_speed_voltage) {
+ update_az_variable_outputs(AZ_SLOW_DOWN_PWM_START);
+ az_initial_slow_down_voltage = AZ_SLOW_DOWN_PWM_START;
+ } else {
+ az_initial_slow_down_voltage = current_az_speed_voltage;
+ }
}
-
+
}
-
+
// check rotation target --------------------------------------------------------------------------------------------------------
- if ((az_state != IDLE) && (az_request_queue_state == IN_PROGRESS_TO_TARGET) ) {
- if ((az_state == NORMAL_CW) || (az_state == SLOW_START_CW) || (az_state == SLOW_DOWN_CW)){
- if ((abs(raw_azimuth - target_raw_azimuth) < (AZIMUTH_TOLERANCE*HEADING_MULTIPLIER)) || ((raw_azimuth > target_raw_azimuth) && ((raw_azimuth - target_raw_azimuth) < ((AZIMUTH_TOLERANCE+5)*HEADING_MULTIPLIER)))) {
+ if ((az_state != IDLE) && (az_request_queue_state == IN_PROGRESS_TO_TARGET) ) {
+ if ((az_state == NORMAL_CW) || (az_state == SLOW_START_CW) || (az_state == SLOW_DOWN_CW)) {
+ if ((abs(raw_azimuth - target_raw_azimuth) < (AZIMUTH_TOLERANCE * HEADING_MULTIPLIER)) || ((raw_azimuth > target_raw_azimuth) && ((raw_azimuth - target_raw_azimuth) < ((AZIMUTH_TOLERANCE + 5) * HEADING_MULTIPLIER)))) {
delay(50);
- read_azimuth();
- if ((abs(raw_azimuth - target_raw_azimuth) < (AZIMUTH_TOLERANCE*HEADING_MULTIPLIER)) || ((raw_azimuth > target_raw_azimuth) && ((raw_azimuth - target_raw_azimuth) < ((AZIMUTH_TOLERANCE+5)*HEADING_MULTIPLIER)))) {
- rotator(DEACTIVATE,CW);
- rotator(DEACTIVATE,CCW);
+ read_azimuth(0);
+ if ((abs(raw_azimuth - target_raw_azimuth) < (AZIMUTH_TOLERANCE * HEADING_MULTIPLIER)) || ((raw_azimuth > target_raw_azimuth) && ((raw_azimuth - target_raw_azimuth) < ((AZIMUTH_TOLERANCE + 5) * HEADING_MULTIPLIER)))) {
+ rotator(DEACTIVATE, CW);
+ rotator(DEACTIVATE, CCW);
az_state = IDLE;
az_request_queue_state = NONE;
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.println(F("service_rotation: IDLE"));}
- #endif //DEBUG_SERVICE_ROTATION
+ debug_print("service_rotation: IDLE");
+ #endif // DEBUG_SERVICE_ROTATION
+
+ #if defined(FEATURE_PARK) && !defined(FEATURE_ELEVATION_CONTROL)
+ if (park_status == PARK_INITIATED) {
+ park_status = PARKED;
+ }
+ #endif // defined(FEATURE_PARK) && !defined(FEATURE_ELEVATION_CONTROL)
+
+ #if defined(FEATURE_PARK) && defined(FEATURE_ELEVATION_CONTROL)
+ if ((park_status == PARK_INITIATED) && (el_state == IDLE)) {
+ park_status = PARKED;
+ }
+ #endif // defined(FEATURE_PARK) && !defined(FEATURE_ELEVATION_CONTROL)
+
}
- }
+ }
} else {
- if ((abs(raw_azimuth - target_raw_azimuth) < (AZIMUTH_TOLERANCE*HEADING_MULTIPLIER)) || ((raw_azimuth < target_raw_azimuth) && ((target_raw_azimuth - raw_azimuth) < ((AZIMUTH_TOLERANCE+5)*HEADING_MULTIPLIER)))) {
+ if ((abs(raw_azimuth - target_raw_azimuth) < (AZIMUTH_TOLERANCE * HEADING_MULTIPLIER)) || ((raw_azimuth < target_raw_azimuth) && ((target_raw_azimuth - raw_azimuth) < ((AZIMUTH_TOLERANCE + 5) * HEADING_MULTIPLIER)))) {
delay(50);
- read_azimuth();
- if ((abs(raw_azimuth - target_raw_azimuth) < (AZIMUTH_TOLERANCE*HEADING_MULTIPLIER)) || ((raw_azimuth < target_raw_azimuth) && ((target_raw_azimuth - raw_azimuth) < ((AZIMUTH_TOLERANCE+5)*HEADING_MULTIPLIER)))) {
- rotator(DEACTIVATE,CW);
- rotator(DEACTIVATE,CCW);
+ read_azimuth(0);
+ if ((abs(raw_azimuth - target_raw_azimuth) < (AZIMUTH_TOLERANCE * HEADING_MULTIPLIER)) || ((raw_azimuth < target_raw_azimuth) && ((target_raw_azimuth - raw_azimuth) < ((AZIMUTH_TOLERANCE + 5) * HEADING_MULTIPLIER)))) {
+ rotator(DEACTIVATE, CW);
+ rotator(DEACTIVATE, CCW);
az_state = IDLE;
az_request_queue_state = NONE;
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.println(F("service_rotation: IDLE"));}
- #endif //DEBUG_SERVICE_ROTATION
+ debug_print("service_rotation: IDLE");
+ #endif // DEBUG_SERVICE_ROTATION
+
+ #if defined(FEATURE_PARK) && !defined(FEATURE_ELEVATION_CONTROL)
+ if (park_status == PARK_INITIATED) {
+ park_status = PARKED;
+ }
+ #endif // defined(FEATURE_PARK) && !defined(FEATURE_ELEVATION_CONTROL)
+
+ #if defined(FEATURE_PARK) && defined(FEATURE_ELEVATION_CONTROL)
+ if ((park_status == PARK_INITIATED) && (el_state == IDLE)) {
+ park_status = PARKED;
+ }
+ #endif // defined(FEATURE_PARK) && !defined(FEATURE_ELEVATION_CONTROL)
+
}
- }
+ }
}
}
- #ifdef FEATURE_ELEVATION_CONTROL
+ #ifdef FEATURE_ELEVATION_CONTROL
if (el_state == INITIALIZE_NORMAL_UP) {
update_el_variable_outputs(normal_el_speed_voltage);
- rotator(ACTIVATE,UP);
+ rotator(ACTIVATE, UP);
el_state = NORMAL_UP;
}
if (el_state == INITIALIZE_NORMAL_DOWN) {
update_el_variable_outputs(normal_el_speed_voltage);
- rotator(ACTIVATE,DOWN);
+ rotator(ACTIVATE, DOWN);
el_state = NORMAL_DOWN;
}
-
- if (el_state == INITIALIZE_SLOW_START_UP){
+
+ if (el_state == INITIALIZE_SLOW_START_UP) {
update_el_variable_outputs(EL_SLOW_START_STARTING_PWM);
- rotator(ACTIVATE,UP);
+ rotator(ACTIVATE, UP);
el_slowstart_start_time = millis();
el_last_step_time = 0;
el_slow_start_step = 0;
el_state = SLOW_START_UP;
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.println(F("service_rotation: INITIALIZE_SLOW_START_UP -> SLOW_START_UP"));}
- #endif //DEBUG_SERVICE_ROTATION
+ debug_print("service_rotation: INITIALIZE_SLOW_START_UP -> SLOW_START_UP");
+ #endif // DEBUG_SERVICE_ROTATION
}
-
- if (el_state == INITIALIZE_SLOW_START_DOWN){
+
+ if (el_state == INITIALIZE_SLOW_START_DOWN) {
update_el_variable_outputs(EL_SLOW_START_STARTING_PWM);
- rotator(ACTIVATE,DOWN);
+ rotator(ACTIVATE, DOWN);
el_slowstart_start_time = millis();
el_last_step_time = 0;
el_slow_start_step = 0;
el_state = SLOW_START_DOWN;
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.println(F("service_rotation: INITIALIZE_SLOW_START_DOWN -> SLOW_START_DOWN"));}
- #endif //DEBUG_SERVICE_ROTATION
- }
-
+ debug_print("service_rotation: INITIALIZE_SLOW_START_DOWN -> SLOW_START_DOWN");
+ #endif // DEBUG_SERVICE_ROTATION
+ }
+
if (el_state == INITIALIZE_TIMED_SLOW_DOWN_UP) {
el_direction_change_flag = 0;
el_timed_slow_down_start_time = millis();
el_last_step_time = millis();
- el_slow_down_step = EL_SLOW_DOWN_STEPS-1;
+ el_slow_down_step = EL_SLOW_DOWN_STEPS - 1;
el_state = TIMED_SLOW_DOWN_UP;
}
-
+
if (el_state == INITIALIZE_TIMED_SLOW_DOWN_DOWN) {
el_direction_change_flag = 0;
el_timed_slow_down_start_time = millis();
el_last_step_time = millis();
- el_slow_down_step = EL_SLOW_DOWN_STEPS-1;
+ el_slow_down_step = EL_SLOW_DOWN_STEPS - 1;
el_state = TIMED_SLOW_DOWN_DOWN;
- }
-
+ }
+
if (el_state == INITIALIZE_DIR_CHANGE_TO_UP) {
el_direction_change_flag = 1;
el_timed_slow_down_start_time = millis();
el_last_step_time = millis();
- el_slow_down_step = EL_SLOW_DOWN_STEPS-1;
- el_state = TIMED_SLOW_DOWN_DOWN;
+ el_slow_down_step = EL_SLOW_DOWN_STEPS - 1;
+ el_state = TIMED_SLOW_DOWN_DOWN;
}
-
- if (el_state == INITIALIZE_DIR_CHANGE_TO_DOWN) {
+
+ if (el_state == INITIALIZE_DIR_CHANGE_TO_DOWN) {
el_direction_change_flag = 1;
el_timed_slow_down_start_time = millis();
el_last_step_time = millis();
- el_slow_down_step = EL_SLOW_DOWN_STEPS-1;
- el_state = TIMED_SLOW_DOWN_UP;
+ el_slow_down_step = EL_SLOW_DOWN_STEPS - 1;
+ el_state = TIMED_SLOW_DOWN_UP;
}
// slow start-------------------------------------------------------------------------------------------------
- if ((el_state == SLOW_START_UP) || (el_state == SLOW_START_DOWN)) {
- if ((millis() - el_slowstart_start_time) >= EL_SLOW_START_UP_TIME) { // is it time to end slow start?
+ if ((el_state == SLOW_START_UP) || (el_state == SLOW_START_DOWN)) {
+ if ((millis() - el_slowstart_start_time) >= EL_SLOW_START_UP_TIME) { // is it time to end slow start?
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.print(F("service_rotation: NORMAL_"));}
- #endif //DEBUG_SERVICE_ROTATION
+ debug_print("service_rotation: NORMAL_");
+ #endif // DEBUG_SERVICE_ROTATION
if (el_state == SLOW_START_UP) {
el_state = NORMAL_UP;
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.println(F("UP"));}
- #endif //DEBUG_SERVICE_ROTATION
+ debug_print("UP");
+ #endif // DEBUG_SERVICE_ROTATION
} else {
el_state = NORMAL_DOWN;
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.println(F("DOWN"));}
- #endif //DEBUG_SERVICE_ROTATION
- }
- update_el_variable_outputs(normal_el_speed_voltage);
+ debug_print("DOWN");
+ #endif // DEBUG_SERVICE_ROTATION
+ }
+ update_el_variable_outputs(normal_el_speed_voltage);
} else { // it's not time to end slow start yet, but let's check if it's time to step up the speed voltage
- if (((millis() - el_last_step_time) > (EL_SLOW_START_UP_TIME/EL_SLOW_START_STEPS)) && (normal_el_speed_voltage > EL_SLOW_START_STARTING_PWM)){
+ if (((millis() - el_last_step_time) > (EL_SLOW_START_UP_TIME / EL_SLOW_START_STEPS)) && (normal_el_speed_voltage > EL_SLOW_START_STARTING_PWM)) {
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {
- Serial.print(F("service_rotation: step up: "));
- Serial.print(el_slow_start_step);
- Serial.print(F(" pwm: "));
- Serial.println((int)(EL_SLOW_START_STARTING_PWM+((normal_el_speed_voltage-EL_SLOW_START_STARTING_PWM)*((float)el_slow_start_step/(float)(EL_SLOW_START_STEPS-1)))));
- }
- #endif //DEBUG_SERVICE_ROTATION
- update_el_variable_outputs((EL_SLOW_START_STARTING_PWM+((normal_el_speed_voltage-EL_SLOW_START_STARTING_PWM)*((float)el_slow_start_step/(float)(EL_SLOW_START_STEPS-1)))));
- el_last_step_time = millis();
+ debug_print("service_rotation: step up: ");
+ debug_print_int(el_slow_start_step);
+ debug_print(" pwm: ");
+ debug_print_int((int)(EL_SLOW_START_STARTING_PWM + ((normal_el_speed_voltage - EL_SLOW_START_STARTING_PWM) * ((float)el_slow_start_step / (float)(EL_SLOW_START_STEPS - 1)))));
+ debug_println("");
+ #endif // DEBUG_SERVICE_ROTATION
+ update_el_variable_outputs((EL_SLOW_START_STARTING_PWM + ((normal_el_speed_voltage - EL_SLOW_START_STARTING_PWM) * ((float)el_slow_start_step / (float)(EL_SLOW_START_STEPS - 1)))));
+ el_last_step_time = millis();
el_slow_start_step++;
- }
- }
- } //((el_state == SLOW_START_UP) || (el_state == SLOW_START_DOWN))
+ }
+ }
+ } // ((el_state == SLOW_START_UP) || (el_state == SLOW_START_DOWN))
// timed slow down ------------------------------------------------------------------------------------------------------
- if (((el_state == TIMED_SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_DOWN)) && ((millis() - el_last_step_time) >= (TIMED_SLOW_DOWN_TIME/EL_SLOW_DOWN_STEPS))) {
+ if (((el_state == TIMED_SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_DOWN)) && ((millis() - el_last_step_time) >= (TIMED_SLOW_DOWN_TIME / EL_SLOW_DOWN_STEPS))) {
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {
- Serial.print(F("service_rotation: TIMED_SLOW_DOWN step down: "));
- Serial.print(el_slow_down_step);
- Serial.print(F(" pwm: "));
- Serial.println((int)(normal_el_speed_voltage*((float)el_slow_down_step/(float)EL_SLOW_DOWN_STEPS)));
- }
- #endif //DEBUG_SERVICE_ROTATION
- update_el_variable_outputs((int)(normal_el_speed_voltage*((float)el_slow_down_step/(float)EL_SLOW_DOWN_STEPS)));
- el_last_step_time = millis();
- el_slow_down_step--;
-
+ debug_print("service_rotation: TIMED_SLOW_DOWN step down: ");
+ debug_print_int(el_slow_down_step);
+ debug_print(" pwm: ");
+ debug_print_int((int)(normal_el_speed_voltage * ((float)el_slow_down_step / (float)EL_SLOW_DOWN_STEPS)));
+ debug_println("");
+ #endif // DEBUG_SERVICE_ROTATION
+ update_el_variable_outputs((int)(normal_el_speed_voltage * ((float)el_slow_down_step / (float)EL_SLOW_DOWN_STEPS)));
+ el_last_step_time = millis();
+ if (el_slow_down_step > 0) {el_slow_down_step--;}
+
if (el_slow_down_step == 0) { // is it time to exit timed slow down?
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.println(F("service_rotation: TIMED_SLOW_DOWN->IDLE"));}
- #endif //DEBUG_SERVICE_ROTATION
- rotator(DEACTIVATE,UP);
- rotator(DEACTIVATE,DOWN);
+ debug_print("service_rotation: TIMED_SLOW_DOWN->IDLE");
+ #endif // DEBUG_SERVICE_ROTATION
+ rotator(DEACTIVATE, UP);
+ rotator(DEACTIVATE, DOWN);
if (el_direction_change_flag) {
if (el_state == TIMED_SLOW_DOWN_UP) {
- rotator(ACTIVATE,DOWN);
- if (el_slowstart_active) {el_state = INITIALIZE_SLOW_START_DOWN;} else {el_state = NORMAL_DOWN;};
+ if (el_slowstart_active) {
+ el_state = INITIALIZE_SLOW_START_DOWN;
+ } else { el_state = NORMAL_DOWN; };
el_direction_change_flag = 0;
}
if (el_state == TIMED_SLOW_DOWN_DOWN) {
- rotator(ACTIVATE,UP);
- if (el_slowstart_active) {el_state = INITIALIZE_SLOW_START_UP;} else {el_state = NORMAL_UP;};
+ if (el_slowstart_active) {
+ el_state = INITIALIZE_SLOW_START_UP;
+ } else { el_state = NORMAL_UP; };
el_direction_change_flag = 0;
}
} else {
el_state = IDLE;
- el_request_queue_state = NONE;
- }
+ el_request_queue_state = NONE;
+ }
}
-
- } //((el_state == TIMED_SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_DOWN))
-
+
+ } // ((el_state == TIMED_SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_DOWN))
+
// slow down ---------------------------------------------------------------------------------------------------------------
- if ((el_state == SLOW_DOWN_UP) || (el_state == SLOW_DOWN_DOWN)) {
+ if ((el_state == SLOW_DOWN_UP) || (el_state == SLOW_DOWN_DOWN)) {
// is it time to do another step down?
- if (abs((target_elevation - elevation)/HEADING_MULTIPLIER) <= (((float)SLOW_DOWN_BEFORE_TARGET_EL*((float)el_slow_down_step/(float)EL_SLOW_DOWN_STEPS)))){
+ if (abs((target_elevation - elevation) / HEADING_MULTIPLIER) <= (((float)SLOW_DOWN_BEFORE_TARGET_EL * ((float)el_slow_down_step / (float)EL_SLOW_DOWN_STEPS)))) {
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {
- Serial.print(F("service_rotation: step down: "));
- Serial.print(el_slow_down_step);
- Serial.print(F(" pwm: "));
- Serial.println((int)(EL_SLOW_DOWN_PWM_STOP+((el_initial_slow_down_voltage-EL_SLOW_DOWN_PWM_STOP)*((float)el_slow_down_step/(float)EL_SLOW_DOWN_STEPS))));
- }
- #endif //DEBUG_SERVICE_ROTATION
- update_el_variable_outputs((EL_SLOW_DOWN_PWM_STOP+((el_initial_slow_down_voltage-EL_SLOW_DOWN_PWM_STOP)*((float)el_slow_down_step/(float)EL_SLOW_DOWN_STEPS))));
- el_slow_down_step--;
- }
- } //((el_state == SLOW_DOWN_UP) || (el_state == SLOW_DOWN_DOWN))
-
+ debug_print("service_rotation: step down: ");
+ debug_print_int(el_slow_down_step);
+ debug_print(" pwm: ");
+ debug_print_int((int)(EL_SLOW_DOWN_PWM_STOP + ((el_initial_slow_down_voltage - EL_SLOW_DOWN_PWM_STOP) * ((float)el_slow_down_step / (float)EL_SLOW_DOWN_STEPS))));
+ debug_println("");
+ #endif // DEBUG_SERVICE_ROTATION
+ update_el_variable_outputs((EL_SLOW_DOWN_PWM_STOP + ((el_initial_slow_down_voltage - EL_SLOW_DOWN_PWM_STOP) * ((float)el_slow_down_step / (float)EL_SLOW_DOWN_STEPS))));
+ if (el_slow_down_step > 0) {el_slow_down_step--;}
+ }
+ } // ((el_state == SLOW_DOWN_UP) || (el_state == SLOW_DOWN_DOWN))
+
// normal -------------------------------------------------------------------------------------------------------------------
// if slow down is enabled, see if we're ready to go into slowdown
- if (((el_state == NORMAL_UP) || (el_state == SLOW_START_UP) || (el_state == NORMAL_DOWN) || (el_state == SLOW_START_DOWN)) &&
- (el_request_queue_state == IN_PROGRESS_TO_TARGET) && el_slowdown_active && (abs((target_elevation - elevation)/HEADING_MULTIPLIER) <= SLOW_DOWN_BEFORE_TARGET_EL)) {
+ if (((el_state == NORMAL_UP) || (el_state == SLOW_START_UP) || (el_state == NORMAL_DOWN) || (el_state == SLOW_START_DOWN)) &&
+ (el_request_queue_state == IN_PROGRESS_TO_TARGET) && el_slowdown_active && (abs((target_elevation - elevation) / HEADING_MULTIPLIER) <= SLOW_DOWN_BEFORE_TARGET_EL)) {
+
+ byte el_state_was = el_state;
+
+
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.print(F("service_rotation: SLOW_DOWN_"));}
- #endif //DEBUG_SERVICE_ROTATION
- el_slow_down_step = EL_SLOW_DOWN_STEPS-1;
- if ((el_state == NORMAL_UP) || (el_state == SLOW_START_UP)){
+ debug_print("service_rotation: SLOW_DOWN_");
+ #endif // DEBUG_SERVICE_ROTATION
+ el_slow_down_step = EL_SLOW_DOWN_STEPS - 1;
+ if ((el_state == NORMAL_UP) || (el_state == SLOW_START_UP)) {
el_state = SLOW_DOWN_UP;
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.println(F("UP"));}
- #endif //DEBUG_SERVICE_ROTATION
+ debug_print("UP");
+ #endif // DEBUG_SERVICE_ROTATION
} else {
el_state = SLOW_DOWN_DOWN;
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.println(F("DOWN"));}
- #endif //DEBUG_SERVICE_ROTATION
+ debug_print("DOWN");
+ #endif // DEBUG_SERVICE_ROTATION
}
- if (EL_SLOW_DOWN_PWM_START < current_el_speed_voltage) {
- update_el_variable_outputs(EL_SLOW_DOWN_PWM_START);
- el_initial_slow_down_voltage = EL_SLOW_DOWN_PWM_START;
+
+ if ((el_state_was == SLOW_START_UP) || (el_state_was == SLOW_START_DOWN)){
+ el_initial_slow_down_voltage = EL_INITIALLY_IN_SLOW_DOWN_PWM;
+ update_el_variable_outputs(el_initial_slow_down_voltage);
+ #ifdef DEBUG_SERVICE_ROTATION
+ debug_print(" SLOW_START -> SLOW_DOWN el_initial_slow_down_voltage:");
+ debug_print_int(el_initial_slow_down_voltage);
+ debug_print(" ");
+ #endif // DEBUG_SERVICE_ROTATION
+
} else {
- el_initial_slow_down_voltage = current_el_speed_voltage;
+ if (EL_SLOW_DOWN_PWM_START < current_el_speed_voltage) {
+ update_el_variable_outputs(EL_SLOW_DOWN_PWM_START);
+ el_initial_slow_down_voltage = EL_SLOW_DOWN_PWM_START;
+ } else {
+ el_initial_slow_down_voltage = current_el_speed_voltage;
+ }
}
-
}
-
+
// check rotation target --------------------------------------------------------------------------------------------------------
- if ((el_state != IDLE) && (el_request_queue_state == IN_PROGRESS_TO_TARGET) ) {
- if ((el_state == NORMAL_UP) || (el_state == SLOW_START_UP) || (el_state == SLOW_DOWN_UP)){
- if ((abs(elevation - target_elevation) < (ELEVATION_TOLERANCE*HEADING_MULTIPLIER)) || ((elevation > target_elevation) && ((elevation - target_elevation) < ((ELEVATION_TOLERANCE+5)*HEADING_MULTIPLIER)))) {
+ if ((el_state != IDLE) && (el_request_queue_state == IN_PROGRESS_TO_TARGET) ) {
+ if ((el_state == NORMAL_UP) || (el_state == SLOW_START_UP) || (el_state == SLOW_DOWN_UP)) {
+ if ((abs(elevation - target_elevation) < (ELEVATION_TOLERANCE * HEADING_MULTIPLIER)) || ((elevation > target_elevation) && ((elevation - target_elevation) < ((ELEVATION_TOLERANCE + 5) * HEADING_MULTIPLIER)))) {
delay(50);
- read_elevation();
- if ((abs(elevation - target_elevation) < (ELEVATION_TOLERANCE*HEADING_MULTIPLIER)) || ((elevation > target_elevation) && ((elevation - target_elevation) < ((ELEVATION_TOLERANCE+5)*HEADING_MULTIPLIER)))) {
- rotator(DEACTIVATE,UP);
- rotator(DEACTIVATE,DOWN);
+ read_elevation(0);
+ if ((abs(elevation - target_elevation) < (ELEVATION_TOLERANCE * HEADING_MULTIPLIER)) || ((elevation > target_elevation) && ((elevation - target_elevation) < ((ELEVATION_TOLERANCE + 5) * HEADING_MULTIPLIER)))) {
+ rotator(DEACTIVATE, UP);
+ rotator(DEACTIVATE, DOWN);
el_state = IDLE;
el_request_queue_state = NONE;
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.println(F("service_rotation: IDLE"));}
- #endif //DEBUG_SERVICE_ROTATION
+ debug_print("service_rotation: IDLE");
+ #endif // DEBUG_SERVICE_ROTATION
+
+ #if defined(FEATURE_PARK)
+ if ((park_status == PARK_INITIATED) && (az_state == IDLE)) {
+ park_status = PARKED;
+ }
+ #endif // defined(FEATURE_PARK)
+
}
- }
+ }
} else {
- if ((abs(elevation - target_elevation) < (ELEVATION_TOLERANCE*HEADING_MULTIPLIER)) || ((elevation < target_elevation) && ((target_elevation - elevation) < ((ELEVATION_TOLERANCE+5)*HEADING_MULTIPLIER)))) {
+ if ((abs(elevation - target_elevation) < (ELEVATION_TOLERANCE * HEADING_MULTIPLIER)) || ((elevation < target_elevation) && ((target_elevation - elevation) < ((ELEVATION_TOLERANCE + 5) * HEADING_MULTIPLIER)))) {
delay(50);
- read_elevation();
- if ((abs(elevation - target_elevation) < (ELEVATION_TOLERANCE*HEADING_MULTIPLIER)) || ((elevation < target_elevation) && ((target_elevation - elevation) < ((ELEVATION_TOLERANCE+5)*HEADING_MULTIPLIER)))) {
- rotator(DEACTIVATE,UP);
- rotator(DEACTIVATE,DOWN);
+ read_elevation(0);
+ if ((abs(elevation - target_elevation) < (ELEVATION_TOLERANCE * HEADING_MULTIPLIER)) || ((elevation < target_elevation) && ((target_elevation - elevation) < ((ELEVATION_TOLERANCE + 5) * HEADING_MULTIPLIER)))) {
+ rotator(DEACTIVATE, UP);
+ rotator(DEACTIVATE, DOWN);
el_state = IDLE;
el_request_queue_state = NONE;
#ifdef DEBUG_SERVICE_ROTATION
- if (debug_mode) {Serial.println(F("service_rotation: IDLE"));}
- #endif //DEBUG_SERVICE_ROTATION
+ debug_print("service_rotation: IDLE");
+ #endif // DEBUG_SERVICE_ROTATION
+
+ #if defined(FEATURE_PARK)
+ if ((park_status == PARK_INITIATED) && (az_state == IDLE)) {
+ park_status = PARKED;
+ }
+ #endif // defined(FEATURE_PARK)
}
- }
+ }
}
}
-
- #endif //FEATURE_ELEVATION_CONTROL
-
-
+ #endif // FEATURE_ELEVATION_CONTROL
+
+
+
+} /* service_rotation */
+// --------------------------------------------------------------
+void stop_all_tracking(){
+
+
+ #ifdef FEATURE_MOON_TRACKING
+ moon_tracking_active = 0;
+ #endif // FEATURE_MOON_TRACKING
+ #ifdef FEATURE_SUN_TRACKING
+ sun_tracking_active = 0;
+ #endif // FEATURE_SUN_TRACKING
+
}
-//--------------------------------------------------------------
-void service_request_queue(){
+// --------------------------------------------------------------
+void service_request_queue(){
+
+// xxxx
-//xxxx
-
int work_target_raw_azimuth = 0;
byte direction_to_go = 0;
-
+ byte within_tolerance_flag = 0;
+
if (az_request_queue_state == IN_QUEUE) {
-
+
+
+ #ifdef FEATURE_POWER_SWITCH
+ last_activity_time = millis();
+ #endif //FEATURE_POWER_SWITCH
+
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F("service_request_queue: AZ "));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
-
- switch(az_request){
- case(REQUEST_STOP):
+ debug_print("service_request_queue: AZ ");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+
+ switch (az_request) {
+ case (REQUEST_STOP):
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F("REQUEST_STOP"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- if (az_state != IDLE){
+ debug_print("REQUEST_STOP");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ stop_all_tracking();
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+ if (az_state != IDLE) {
if (az_slowdown_active) {
- if ((az_state == TIMED_SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CCW)) { // if we're already in timed slow down and we get another stop, do a hard stop
- rotator(DEACTIVATE,CW);
- rotator(DEACTIVATE,CCW);
+ if ((az_state == TIMED_SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CCW) || (az_state == SLOW_DOWN_CW) || (az_state == SLOW_DOWN_CCW)) { // if we're already in timed slow down and we get another stop, do a hard stop
+ rotator(DEACTIVATE, CW);
+ rotator(DEACTIVATE, CCW);
az_state = IDLE;
- az_request_queue_state = NONE;
+ az_request_queue_state = NONE;
}
if ((az_state == SLOW_START_CW) || (az_state == NORMAL_CW)) {
az_state = INITIALIZE_TIMED_SLOW_DOWN_CW;
- az_request_queue_state = IN_PROGRESS_TIMED;
- az_last_rotate_initiation = millis();
+ az_request_queue_state = IN_PROGRESS_TIMED;
+ az_last_rotate_initiation = millis();
}
if ((az_state == SLOW_START_CCW) || (az_state == NORMAL_CCW)) {
az_state = INITIALIZE_TIMED_SLOW_DOWN_CCW;
- az_request_queue_state = IN_PROGRESS_TIMED;
- az_last_rotate_initiation = millis();
- }
-
+ az_request_queue_state = IN_PROGRESS_TIMED;
+ az_last_rotate_initiation = millis();
+ }
+
} else {
- rotator(DEACTIVATE,CW);
- rotator(DEACTIVATE,CCW);
+ rotator(DEACTIVATE, CW);
+ rotator(DEACTIVATE, CCW);
az_state = IDLE;
- az_request_queue_state = NONE;
+ az_request_queue_state = NONE;
}
} else {
- az_request_queue_state = NONE; // nothing to do - we clear the queue
+ az_request_queue_state = NONE; // nothing to do - we clear the queue
}
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println();}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- break; //REQUEST_STOP
-
- case(REQUEST_AZIMUTH):
+ if (debug_mode) {
+ control_port->println();
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ break; // REQUEST_STOP
+
+ case (REQUEST_AZIMUTH):
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F("REQUEST_AZIMUTH"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- if ((az_request_parm >= 0) && (az_request_parm <= (360*HEADING_MULTIPLIER))) {
+ debug_print("REQUEST_AZIMUTH");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ if ((az_request_parm >= 0) && (az_request_parm <= (360 * HEADING_MULTIPLIER))) {
target_azimuth = az_request_parm;
target_raw_azimuth = az_request_parm;
- if (target_azimuth == (360*HEADING_MULTIPLIER)) {target_azimuth = 0;}
- if ((target_azimuth > (azimuth - (AZIMUTH_TOLERANCE*HEADING_MULTIPLIER))) && (target_azimuth < (azimuth + (AZIMUTH_TOLERANCE*HEADING_MULTIPLIER)))) {
+ if (target_azimuth == (360 * HEADING_MULTIPLIER)) {
+ target_azimuth = 0;
+ }
+ if ((target_azimuth > (azimuth - (AZIMUTH_TOLERANCE * HEADING_MULTIPLIER))) && (target_azimuth < (azimuth + (AZIMUTH_TOLERANCE * HEADING_MULTIPLIER)))) {
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F(" request within tolerance"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
+ debug_print(" request within tolerance");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ within_tolerance_flag = 1;
+ az_request_queue_state = NONE;
} else { // target azimuth is not within tolerance, we need to rotate
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F(" ->A"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- work_target_raw_azimuth = target_azimuth;
+ debug_print(" ->A");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ work_target_raw_azimuth = target_azimuth;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {
- Serial.print(F(" work_target_raw_azimuth:"));
- Serial.print(work_target_raw_azimuth/HEADING_MULTIPLIER);
- Serial.print(F(" configuration.azimuth_starting_point:"));
- Serial.print(configuration.azimuth_starting_point);
- Serial.print(" ");
- }
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
-
- if (work_target_raw_azimuth < (configuration.azimuth_starting_point*HEADING_MULTIPLIER)) {
- work_target_raw_azimuth = work_target_raw_azimuth + (360*HEADING_MULTIPLIER);
+ debug_print(" work_target_raw_azimuth:");
+ debug_print_int(work_target_raw_azimuth / HEADING_MULTIPLIER);
+ debug_print(" azimuth_starting_point:");
+ debug_print_int(azimuth_starting_point);
+ debug_print(" ");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+
+ if (work_target_raw_azimuth < (azimuth_starting_point * HEADING_MULTIPLIER)) {
+ work_target_raw_azimuth = work_target_raw_azimuth + (360 * HEADING_MULTIPLIER);
target_raw_azimuth = work_target_raw_azimuth;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F("->B"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
+ debug_print("->B");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
}
- if ((work_target_raw_azimuth + (360*HEADING_MULTIPLIER)) < ((configuration.azimuth_starting_point + configuration.azimuth_rotation_capability)*HEADING_MULTIPLIER)) { // is there a second possible heading in overlap?
- if (abs(raw_azimuth - work_target_raw_azimuth) < abs((work_target_raw_azimuth+(360*HEADING_MULTIPLIER)) - raw_azimuth)) { // is second possible heading closer?
+ if ((work_target_raw_azimuth + (360 * HEADING_MULTIPLIER)) < ((azimuth_starting_point + azimuth_rotation_capability) * HEADING_MULTIPLIER)) { // is there a second possible heading in overlap?
+ if (abs(raw_azimuth - work_target_raw_azimuth) < abs((work_target_raw_azimuth + (360 * HEADING_MULTIPLIER)) - raw_azimuth)) { // is second possible heading closer?
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F("->C"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
+ debug_print("->C");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
if (work_target_raw_azimuth > raw_azimuth) { // not closer, use position in non-overlap
- direction_to_go = CW;
+ direction_to_go = CW;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println(F("->CW!"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
+ debug_print("->CW!");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
} else {
direction_to_go = CCW;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println(F("->CCW!"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- }
+ debug_print("->CCW!");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ }
} else { // go to position in overlap
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F("->D"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- target_raw_azimuth = work_target_raw_azimuth + (360*HEADING_MULTIPLIER);
- if ((work_target_raw_azimuth + (360*HEADING_MULTIPLIER)) > raw_azimuth) {
- direction_to_go = CW;
+ debug_print("->D");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ target_raw_azimuth = work_target_raw_azimuth + (360 * HEADING_MULTIPLIER);
+ if ((work_target_raw_azimuth + (360 * HEADING_MULTIPLIER)) > raw_azimuth) {
+ direction_to_go = CW;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F("->CW!"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- } else {
- direction_to_go = CCW;
+ debug_print("->CW!");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ } else {
+ direction_to_go = CCW;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F("->CCW!"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- }
+ debug_print("->CCW!");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ }
}
} else { // no possible second heading in overlap
- #ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F("->E"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
+ #ifdef DEBUG_SERVICE_REQUEST_QUEUE
+ debug_print("->E");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
if (work_target_raw_azimuth > raw_azimuth) {
direction_to_go = CW;
} else {
direction_to_go = CCW;
}
- }
+ }
}
} else {
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F("->F"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- if ((az_request_parm > (360*HEADING_MULTIPLIER)) && (az_request_parm <= ((configuration.azimuth_starting_point+configuration.azimuth_rotation_capability)*HEADING_MULTIPLIER))) {
- target_azimuth = az_request_parm - (360*HEADING_MULTIPLIER);
+ debug_print("->F");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ if ((az_request_parm > (360 * HEADING_MULTIPLIER)) && (az_request_parm <= ((azimuth_starting_point + azimuth_rotation_capability) * HEADING_MULTIPLIER))) {
+ target_azimuth = az_request_parm - (360 * HEADING_MULTIPLIER);
target_raw_azimuth = az_request_parm;
if (az_request_parm > raw_azimuth) {
direction_to_go = CW;
} else {
direction_to_go = CCW;
- }
+ }
} else {
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {
- Serial.print(F(" error: bogus azimuth request:"));
- Serial.println(az_request_parm);
- }
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- rotator(DEACTIVATE,CW);
- rotator(DEACTIVATE,CCW);
+ debug_print(" error: bogus azimuth request:");
+ debug_print_int(az_request_parm);
+ debug_println("");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ rotator(DEACTIVATE, CW);
+ rotator(DEACTIVATE, CCW);
az_state = IDLE;
- az_request_queue_state = NONE;
+ az_request_queue_state = NONE;
return;
}
}
- if (direction_to_go == CW){
- if (((az_state == SLOW_START_CCW) || (az_state == NORMAL_CCW) || (az_state == SLOW_DOWN_CCW) || (az_state == TIMED_SLOW_DOWN_CCW)) && (az_slowstart_active)){
+ if (direction_to_go == CW) {
+ if (((az_state == SLOW_START_CCW) || (az_state == NORMAL_CCW) || (az_state == SLOW_DOWN_CCW) || (az_state == TIMED_SLOW_DOWN_CCW)) && (az_slowstart_active)) {
az_state = INITIALIZE_DIR_CHANGE_TO_CW;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F(" INITIALIZE_DIR_CHANGE_TO_CW"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- } else {
+ debug_print(" INITIALIZE_DIR_CHANGE_TO_CW");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ } else {
if ((az_state != INITIALIZE_SLOW_START_CW) && (az_state != SLOW_START_CW) && (az_state != NORMAL_CW)) { // if we're already rotating CW, don't do anything
- //rotator(ACTIVATE,CW);
- if (az_slowstart_active) {az_state = INITIALIZE_SLOW_START_CW;} else {az_state = INITIALIZE_NORMAL_CW;};
- }
+ // rotator(ACTIVATE,CW);
+ if (az_slowstart_active) {
+ az_state = INITIALIZE_SLOW_START_CW;
+ } else { az_state = INITIALIZE_NORMAL_CW; };
+ }
}
}
- if (direction_to_go == CCW){
- if (((az_state == SLOW_START_CW) || (az_state == NORMAL_CW) || (az_state == SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CW)) && (az_slowstart_active)){
+ if (direction_to_go == CCW) {
+ if (((az_state == SLOW_START_CW) || (az_state == NORMAL_CW) || (az_state == SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CW)) && (az_slowstart_active)) {
az_state = INITIALIZE_DIR_CHANGE_TO_CCW;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F(" INITIALIZE_DIR_CHANGE_TO_CCW"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- } else {
+ debug_print(" INITIALIZE_DIR_CHANGE_TO_CCW");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ } else {
if ((az_state != INITIALIZE_SLOW_START_CCW) && (az_state != SLOW_START_CCW) && (az_state != NORMAL_CCW)) { // if we're already rotating CCW, don't do anything
- //rotator(ACTIVATE,CCW);
- if (az_slowstart_active) {az_state = INITIALIZE_SLOW_START_CCW;} else {az_state = INITIALIZE_NORMAL_CCW;};
+ // rotator(ACTIVATE,CCW);
+ if (az_slowstart_active) {
+ az_state = INITIALIZE_SLOW_START_CCW;
+ } else { az_state = INITIALIZE_NORMAL_CCW; };
}
- }
+ }
+ }
+ if (!within_tolerance_flag) {
+ az_request_queue_state = IN_PROGRESS_TO_TARGET;
+ az_last_rotate_initiation = millis();
}
- az_request_queue_state = IN_PROGRESS_TO_TARGET;
- az_last_rotate_initiation = millis();
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println();}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- break; //REQUEST_AZIMUTH
+ if (debug_mode) {
+ control_port->println();
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ break; // REQUEST_AZIMUTH
- case(REQUEST_AZIMUTH_RAW):
+ case (REQUEST_AZIMUTH_RAW):
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F("REQUEST_AZIMUTH_RAW"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
+ debug_print("REQUEST_AZIMUTH_RAW");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
target_raw_azimuth = az_request_parm;
target_azimuth = target_raw_azimuth;
- if (target_azimuth >= (360*HEADING_MULTIPLIER)) {target_azimuth = target_azimuth - (360*HEADING_MULTIPLIER);}
-
- if (((abs(raw_azimuth - target_raw_azimuth) < (AZIMUTH_TOLERANCE*HEADING_MULTIPLIER))) && (az_state == IDLE)) {
+ if (target_azimuth >= (360 * HEADING_MULTIPLIER)) {
+ target_azimuth = target_azimuth - (360 * HEADING_MULTIPLIER);
+ }
+
+ if (((abs(raw_azimuth - target_raw_azimuth) < (AZIMUTH_TOLERANCE * HEADING_MULTIPLIER))) && (az_state == IDLE)) {
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F(" request within tolerance"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
+ debug_print(" request within tolerance");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
az_request_queue_state = NONE;
+ within_tolerance_flag = 1;
} else {
if (target_raw_azimuth > raw_azimuth) {
- if (((az_state == SLOW_START_CCW) || (az_state == NORMAL_CCW) || (az_state == SLOW_DOWN_CCW) || (az_state == TIMED_SLOW_DOWN_CCW)) && (az_slowstart_active)){
+ if (((az_state == SLOW_START_CCW) || (az_state == NORMAL_CCW) || (az_state == SLOW_DOWN_CCW) || (az_state == TIMED_SLOW_DOWN_CCW)) && (az_slowstart_active)) {
az_state = INITIALIZE_DIR_CHANGE_TO_CW;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F(" INITIALIZE_DIR_CHANGE_TO_CW"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- } else {
+ debug_print(" INITIALIZE_DIR_CHANGE_TO_CW");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ } else {
if ((az_state != INITIALIZE_SLOW_START_CW) && (az_state != SLOW_START_CW) && (az_state != NORMAL_CW)) { // if we're already rotating CW, don't do anything
- //rotator(ACTIVATE,CW);
- if (az_slowstart_active) {az_state = INITIALIZE_SLOW_START_CW;} else {az_state = INITIALIZE_NORMAL_CW;};
- }
+ if (az_slowstart_active) {
+ az_state = INITIALIZE_SLOW_START_CW;
+ } else { az_state = INITIALIZE_NORMAL_CW; };
+ }
}
}
if (target_raw_azimuth < raw_azimuth) {
- if (((az_state == SLOW_START_CW) || (az_state == NORMAL_CW) || (az_state == SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CW)) && (az_slowstart_active)){
+ if (((az_state == SLOW_START_CW) || (az_state == NORMAL_CW) || (az_state == SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CW)) && (az_slowstart_active)) {
az_state = INITIALIZE_DIR_CHANGE_TO_CCW;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F(" INITIALIZE_DIR_CHANGE_TO_CCW"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- } else {
+ debug_print(" INITIALIZE_DIR_CHANGE_TO_CCW");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ } else {
if ((az_state != INITIALIZE_SLOW_START_CCW) && (az_state != SLOW_START_CCW) && (az_state != NORMAL_CCW)) { // if we're already rotating CCW, don't do anything
- // rotator(ACTIVATE,CCW);
- if (az_slowstart_active) {az_state = INITIALIZE_SLOW_START_CCW;} else {az_state = INITIALIZE_NORMAL_CCW;};
- }
+ if (az_slowstart_active) {
+ az_state = INITIALIZE_SLOW_START_CCW;
+ } else { az_state = INITIALIZE_NORMAL_CCW; };
+ }
}
- }
- az_request_queue_state = IN_PROGRESS_TO_TARGET;
- az_last_rotate_initiation = millis();
- }
+ }
+ if (!within_tolerance_flag) {
+ az_request_queue_state = IN_PROGRESS_TO_TARGET;
+ az_last_rotate_initiation = millis();
+ }
+ }
+ #ifdef DEBUG_SERVICE_REQUEST_QUEUE
+ if (debug_mode) {
+ control_port->println();
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ break; // REQUEST_AZIMUTH_RAW
+
+ case (REQUEST_CW):
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println();}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- break; //REQUEST_AZIMUTH_RAW
-
- case(REQUEST_CW):
- #ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F("REQUEST_CW"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- if (((az_state == SLOW_START_CCW) || (az_state == NORMAL_CCW) || (az_state == SLOW_DOWN_CCW) || (az_state == TIMED_SLOW_DOWN_CCW)) && (az_slowstart_active)){
+ debug_print("REQUEST_CW");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ stop_all_tracking();
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+ if (((az_state == SLOW_START_CCW) || (az_state == NORMAL_CCW) || (az_state == SLOW_DOWN_CCW) || (az_state == TIMED_SLOW_DOWN_CCW)) && (az_slowstart_active)) {
az_state = INITIALIZE_DIR_CHANGE_TO_CW;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F(" INITIALIZE_DIR_CHANGE_TO_CW"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
+ debug_print(" INITIALIZE_DIR_CHANGE_TO_CW");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
} else {
if ((az_state != SLOW_START_CW) && (az_state != NORMAL_CW)) {
- //rotator(ACTIVATE,CW);
- if (az_slowstart_active) {az_state = INITIALIZE_SLOW_START_CW;} else {az_state = INITIALIZE_NORMAL_CW;};
+ // rotator(ACTIVATE,CW);
+ if (az_slowstart_active) {
+ az_state = INITIALIZE_SLOW_START_CW;
+ } else {
+ az_state = INITIALIZE_NORMAL_CW;
+ };
}
}
az_request_queue_state = NONE;
az_last_rotate_initiation = millis();
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println();}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- break; //REQUEST_CW
-
- case(REQUEST_CCW):
+ if (debug_mode) {
+ control_port->println();
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ break; // REQUEST_CW
+
+ case (REQUEST_CCW):
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println(F("REQUEST_CCW"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- if (((az_state == SLOW_START_CW) || (az_state == NORMAL_CW) || (az_state == SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CW)) && (az_slowstart_active)){
+ debug_print("REQUEST_CCW");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ stop_all_tracking();
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+ if (((az_state == SLOW_START_CW) || (az_state == NORMAL_CW) || (az_state == SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CW)) && (az_slowstart_active)) {
az_state = INITIALIZE_DIR_CHANGE_TO_CCW;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F(" INITIALIZE_DIR_CHANGE_TO_CCW"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- } else {
+ debug_print(" INITIALIZE_DIR_CHANGE_TO_CCW");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ } else {
if ((az_state != SLOW_START_CCW) && (az_state != NORMAL_CCW)) {
- //rotator(ACTIVATE,CCW);
- if (az_slowstart_active) {az_state = INITIALIZE_SLOW_START_CCW;} else {az_state = INITIALIZE_NORMAL_CCW;};
+ // rotator(ACTIVATE,CCW);
+ if (az_slowstart_active) {
+ az_state = INITIALIZE_SLOW_START_CCW;
+ } else { az_state = INITIALIZE_NORMAL_CCW; };
}
}
- az_request_queue_state = NONE;
+ az_request_queue_state = NONE;
az_last_rotate_initiation = millis();
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println();}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- break; //REQUEST_CCW
-
- case(REQUEST_KILL):
+ if (debug_mode) {
+ control_port->println();
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ break; // REQUEST_CCW
+
+ case (REQUEST_KILL):
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F("REQUEST_KILL"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- rotator(DEACTIVATE,CW);
- rotator(DEACTIVATE,CCW);
+ debug_print("REQUEST_KILL");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ stop_all_tracking();
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+ rotator(DEACTIVATE, CW);
+ rotator(DEACTIVATE, CCW);
az_state = IDLE;
- az_request_queue_state = NONE;
+ az_request_queue_state = NONE;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println();}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- break; //REQUEST_KILL
- }
+ debug_println("");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ break; // REQUEST_KILL
+ } /* switch */
+
+ #ifdef FEATURE_LCD_DISPLAY
+ if (az_request_queue_state != IN_QUEUE) {push_lcd_update = 1;}
+ #endif //FEATURE_LCD_DISPLAY
}
-
+
#ifdef FEATURE_ELEVATION_CONTROL
- if (el_request_queue_state == IN_QUEUE){
+ if (el_request_queue_state == IN_QUEUE) {
+
+ #ifdef FEATURE_POWER_SWITCH
+ last_activity_time = millis();
+ #endif //FEATURE_POWER_SWITCH
+
+ within_tolerance_flag = 0;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F("service_request_queue: EL "));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- switch(el_request) {
- case(REQUEST_ELEVATION):
+ debug_print("service_request_queue: EL ");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ switch (el_request) {
+ case (REQUEST_ELEVATION):
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F("REQUEST_ELEVATION "));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
+ debug_print("REQUEST_ELEVATION ");
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
target_elevation = el_request_parm;
- if (target_elevation > (ELEVATION_MAXIMUM_DEGREES*HEADING_MULTIPLIER)){
+ if (target_elevation > (ELEVATION_MAXIMUM_DEGREES * HEADING_MULTIPLIER)) {
target_elevation = ELEVATION_MAXIMUM_DEGREES * HEADING_MULTIPLIER;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F("REQUEST_ELEVATION: target_elevation > ELEVATION_MAXIMUM_DEGREES"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
+ if (debug_mode) {
+ control_port->print(F("REQUEST_ELEVATION: target_elevation > ELEVATION_MAXIMUM_DEGREES"));
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
}
-
+
#ifdef OPTION_EL_MANUAL_ROTATE_LIMITS
- if (target_elevation < (EL_MANUAL_ROTATE_DOWN_LIMIT*HEADING_MULTIPLIER)){
+ if (target_elevation < (EL_MANUAL_ROTATE_DOWN_LIMIT * HEADING_MULTIPLIER)) {
target_elevation = EL_MANUAL_ROTATE_DOWN_LIMIT * HEADING_MULTIPLIER;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F("REQUEST_ELEVATION: target_elevation < EL_MANUAL_ROTATE_DOWN_LIMIT"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
+ if (debug_mode) {
+ control_port->print(F("REQUEST_ELEVATION: target_elevation < EL_MANUAL_ROTATE_DOWN_LIMIT"));
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
}
- if (target_elevation > (EL_MANUAL_ROTATE_UP_LIMIT*HEADING_MULTIPLIER)){
+ if (target_elevation > (EL_MANUAL_ROTATE_UP_LIMIT * HEADING_MULTIPLIER)) {
target_elevation = EL_MANUAL_ROTATE_UP_LIMIT * HEADING_MULTIPLIER;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.print(F("REQUEST_ELEVATION: target_elevation > EL_MANUAL_ROTATE_UP_LIMIT"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- }
- #endif //OPTION_EL_MANUAL_ROTATE_LIMITS
-
- if (abs(target_elevation - elevation) < (ELEVATION_TOLERANCE*HEADING_MULTIPLIER)) {
+ if (debug_mode) {
+ control_port->print(F("REQUEST_ELEVATION: target_elevation > EL_MANUAL_ROTATE_UP_LIMIT"));
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ }
+ #endif // OPTION_EL_MANUAL_ROTATE_LIMITS
+
+ if (abs(target_elevation - elevation) < (ELEVATION_TOLERANCE * HEADING_MULTIPLIER)) {
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println(F("requested elevation within tolerance"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- //el_request_queue_state = NONE;
+ if (debug_mode) {
+ control_port->println(F("requested elevation within tolerance"));
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ within_tolerance_flag = 1;
+ el_request_queue_state = NONE;
} else {
if (target_elevation > elevation) {
- if (((el_state == SLOW_START_DOWN) || (el_state == NORMAL_DOWN) || (el_state == SLOW_DOWN_DOWN) || (el_state == TIMED_SLOW_DOWN_DOWN)) && (el_slowstart_active)){
+ if (((el_state == SLOW_START_DOWN) || (el_state == NORMAL_DOWN) || (el_state == SLOW_DOWN_DOWN) || (el_state == TIMED_SLOW_DOWN_DOWN)) && (el_slowstart_active)) {
el_state = INITIALIZE_DIR_CHANGE_TO_UP;
- #ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println(F(" INITIALIZE_DIR_CHANGE_TO_UP"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- } else {
+ #ifdef DEBUG_SERVICE_REQUEST_QUEUE
+ if (debug_mode) {
+ control_port->println(F(" INITIALIZE_DIR_CHANGE_TO_UP"));
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ } else {
if ((el_state != INITIALIZE_SLOW_START_UP) && (el_state != SLOW_START_UP) && (el_state != NORMAL_UP)) { // if we're already rotating UP, don't do anything
- if (el_slowstart_active) {el_state = INITIALIZE_SLOW_START_UP;} else {el_state = INITIALIZE_NORMAL_UP;};
- }
+ if (el_slowstart_active) {
+ el_state = INITIALIZE_SLOW_START_UP;
+ } else { el_state = INITIALIZE_NORMAL_UP; };
+ }
}
- } //(target_elevation > elevation)
+ } // (target_elevation > elevation)
if (target_elevation < elevation) {
- if (((el_state == SLOW_START_UP) || (el_state == NORMAL_UP) || (el_state == SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_UP)) && (el_slowstart_active)){
+ if (((el_state == SLOW_START_UP) || (el_state == NORMAL_UP) || (el_state == SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_UP)) && (el_slowstart_active)) {
el_state = INITIALIZE_DIR_CHANGE_TO_DOWN;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println(F(" INITIALIZE_DIR_CHANGE_TO_DOWN"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- } else {
+ if (debug_mode) {
+ control_port->println(F(" INITIALIZE_DIR_CHANGE_TO_DOWN"));
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ } else {
if ((el_state != INITIALIZE_SLOW_START_DOWN) && (el_state != SLOW_START_DOWN) && (el_state != NORMAL_DOWN)) { // if we're already rotating DOWN, don't do anything
- if (el_slowstart_active) {el_state = INITIALIZE_SLOW_START_DOWN;} else {el_state = INITIALIZE_NORMAL_DOWN;};
- }
- }
- } //(target_elevation < elevation)
- } //(abs(target_elevation - elevation) < ELEVATION_TOLERANCE)
- el_request_queue_state = IN_PROGRESS_TO_TARGET;
- el_last_rotate_initiation = millis();
+ if (el_slowstart_active) {
+ el_state = INITIALIZE_SLOW_START_DOWN;
+ } else { el_state = INITIALIZE_NORMAL_DOWN; };
+ }
+ }
+ } // (target_elevation < elevation)
+ } // (abs(target_elevation - elevation) < ELEVATION_TOLERANCE)
+ if (!within_tolerance_flag) {
+ el_request_queue_state = IN_PROGRESS_TO_TARGET;
+ el_last_rotate_initiation = millis();
+ }
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println();}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- break; //REQUEST_ELEVATION
-
- case(REQUEST_UP):
+ if (debug_mode) {
+ control_port->println();
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ break; // REQUEST_ELEVATION
+
+ case (REQUEST_UP):
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println(F("REQUEST_UP"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- if (((el_state == SLOW_START_DOWN) || (el_state == NORMAL_DOWN) || (el_state == SLOW_DOWN_DOWN) || (el_state == TIMED_SLOW_DOWN_DOWN)) && (el_slowstart_active)){
+ if (debug_mode) {
+ control_port->println(F("REQUEST_UP"));
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ stop_all_tracking();
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+ if (((el_state == SLOW_START_DOWN) || (el_state == NORMAL_DOWN) || (el_state == SLOW_DOWN_DOWN) || (el_state == TIMED_SLOW_DOWN_DOWN)) && (el_slowstart_active)) {
el_state = INITIALIZE_DIR_CHANGE_TO_UP;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println(F("service_request_queue: INITIALIZE_DIR_CHANGE_TO_UP"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- } else {
+ if (debug_mode) {
+ control_port->println(F("service_request_queue: INITIALIZE_DIR_CHANGE_TO_UP"));
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ } else {
if ((el_state != SLOW_START_UP) && (el_state != NORMAL_UP)) {
- if (el_slowstart_active) {el_state = INITIALIZE_SLOW_START_UP;} else {el_state = INITIALIZE_NORMAL_UP;};
+ if (el_slowstart_active) {
+ el_state = INITIALIZE_SLOW_START_UP;
+ } else { el_state = INITIALIZE_NORMAL_UP; };
}
}
- el_request_queue_state = NONE;
- el_last_rotate_initiation = millis();
+ el_request_queue_state = NONE;
+ el_last_rotate_initiation = millis();
+ #ifdef DEBUG_SERVICE_REQUEST_QUEUE
+ if (debug_mode) {
+ control_port->println();
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ break; // REQUEST_UP
+
+ case (REQUEST_DOWN):
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println();}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- break; //REQUEST_UP
-
- case(REQUEST_DOWN):
- #ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println(F("REQUEST_DOWN"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- if (((el_state == SLOW_START_UP) || (el_state == NORMAL_UP) || (el_state == SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_UP)) && (el_slowstart_active)){
+ if (debug_mode) {
+ control_port->println(F("REQUEST_DOWN"));
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ stop_all_tracking();
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+ if (((el_state == SLOW_START_UP) || (el_state == NORMAL_UP) || (el_state == SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_UP)) && (el_slowstart_active)) {
el_state = INITIALIZE_DIR_CHANGE_TO_DOWN;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println(F("service_request_queue: INITIALIZE_DIR_CHANGE_TO_DOWN"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- } else {
+ if (debug_mode) {
+ control_port->println(F("service_request_queue: INITIALIZE_DIR_CHANGE_TO_DOWN"));
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ } else {
if ((el_state != SLOW_START_DOWN) && (el_state != NORMAL_DOWN)) {
- if (el_slowstart_active) {el_state = INITIALIZE_SLOW_START_DOWN;} else {el_state = INITIALIZE_NORMAL_DOWN;};
+ if (el_slowstart_active) {
+ el_state = INITIALIZE_SLOW_START_DOWN;
+ } else { el_state = INITIALIZE_NORMAL_DOWN; };
}
}
- el_request_queue_state = NONE;
- el_last_rotate_initiation = millis();
+ el_request_queue_state = NONE;
+ el_last_rotate_initiation = millis();
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println();}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- break; //REQUEST_DOWN
+ if (debug_mode) {
+ control_port->println();
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ break; // REQUEST_DOWN
- case(REQUEST_STOP):
+ case (REQUEST_STOP):
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println(F("REQUEST_STOP"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- if (el_state != IDLE){
+ if (debug_mode) {
+ control_port->println(F("REQUEST_STOP"));
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ stop_all_tracking();
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+ if (el_state != IDLE) {
if (el_slowdown_active) {
- if ((el_state == TIMED_SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_DOWN)) { // if we're already in timed slow down and we get another stop, do a hard stop
- rotator(DEACTIVATE,UP);
- rotator(DEACTIVATE,DOWN);
+ if ((el_state == TIMED_SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_DOWN) || (el_state == SLOW_DOWN_UP) || (el_state == SLOW_DOWN_DOWN)) { // if we're already in timed slow down and we get another stop, do a hard stop
+ rotator(DEACTIVATE, UP);
+ rotator(DEACTIVATE, DOWN);
el_state = IDLE;
- el_request_queue_state = NONE;
+ el_request_queue_state = NONE;
}
if ((el_state == SLOW_START_UP) || (el_state == NORMAL_UP)) {
el_state = INITIALIZE_TIMED_SLOW_DOWN_UP;
- el_request_queue_state = IN_PROGRESS_TIMED;
- el_last_rotate_initiation = millis();
+ el_request_queue_state = IN_PROGRESS_TIMED;
+ el_last_rotate_initiation = millis();
}
if ((el_state == SLOW_START_DOWN) || (el_state == NORMAL_DOWN)) {
el_state = INITIALIZE_TIMED_SLOW_DOWN_DOWN;
- el_request_queue_state = IN_PROGRESS_TIMED;
- el_last_rotate_initiation = millis();
- }
+ el_request_queue_state = IN_PROGRESS_TIMED;
+ el_last_rotate_initiation = millis();
+ }
} else {
- rotator(DEACTIVATE,UP);
- rotator(DEACTIVATE,DOWN);
+ rotator(DEACTIVATE, UP);
+ rotator(DEACTIVATE, DOWN);
el_state = IDLE;
- el_request_queue_state = NONE;
+ el_request_queue_state = NONE;
}
- } else {
- el_request_queue_state = NONE; //nothing to do, we're already in IDLE state
+ } else {
+ el_request_queue_state = NONE; // nothing to do, we're already in IDLE state
}
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println();}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- break; //REQUEST_STOP
-
- case(REQUEST_KILL):
+ if (debug_mode) {
+ control_port->println();
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ break; // REQUEST_STOP
+
+ case (REQUEST_KILL):
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println(F("REQUEST_KILL"));}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- rotator(DEACTIVATE,UP);
- rotator(DEACTIVATE,DOWN);
+ if (debug_mode) {
+ control_port->println(F("REQUEST_KILL"));
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ stop_all_tracking();
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+ rotator(DEACTIVATE, UP);
+ rotator(DEACTIVATE, DOWN);
el_state = IDLE;
- el_request_queue_state = NONE;
+ el_request_queue_state = NONE;
#ifdef DEBUG_SERVICE_REQUEST_QUEUE
- if (debug_mode) {Serial.println();}
- #endif //DEBUG_SERVICE_REQUEST_QUEUE
- break; //REQUEST_KILL
- }
- } //(el_request_queue_state == IN_QUEUE)
- #endif //FEATURE_ELEVATION_CONTROL
-
+ if (debug_mode) {
+ control_port->println();
+ }
+ #endif // DEBUG_SERVICE_REQUEST_QUEUE
+ break; // REQUEST_KILL
+ } /* switch */
-}
+ #ifdef FEATURE_LCD_DISPLAY
+ if (el_request_queue_state != IN_QUEUE) {push_lcd_update = 1;}
+ #endif //FEATURE_LCD_DISPLAY
-//--------------------------------------------------------------
+ } // (el_request_queue_state == IN_QUEUE)
+ #endif // FEATURE_ELEVATION_CONTROL
+
+
+} /* service_request_queue */
+
+// --------------------------------------------------------------
void check_for_dirty_configuration(){
-
+
static unsigned long last_config_write_time = 0;
-
- if ((configuration_dirty) && ((millis() - last_config_write_time) > (EEPROM_WRITE_DIRTY_CONFIG_TIME*1000))){
+
+ if ((configuration_dirty) && ((millis() - last_config_write_time) > (EEPROM_WRITE_DIRTY_CONFIG_TIME * 1000))) {
write_settings_to_eeprom();
- last_config_write_time = millis();
+ last_config_write_time = millis();
}
-
+
}
-//--------------------------------------------------------------
+// --------------------------------------------------------------
byte current_az_state(){
-
+
if ((az_state == SLOW_START_CW) || (az_state == NORMAL_CW) || (az_state == SLOW_DOWN_CW) || (az_state == TIMED_SLOW_DOWN_CW)) {
return ROTATING_CW;
}
if ((az_state == SLOW_START_CCW) || (az_state == NORMAL_CCW) || (az_state == SLOW_DOWN_CCW) || (az_state == TIMED_SLOW_DOWN_CCW)) {
return ROTATING_CCW;
- }
+ }
return NOT_DOING_ANYTHING;
-
+
}
-//--------------------------------------------------------------
+// --------------------------------------------------------------
#ifdef FEATURE_ELEVATION_CONTROL
byte current_el_state(){
- if ((el_state == SLOW_START_UP)||(el_state == NORMAL_UP) || (el_state == SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_UP)) {
+ if ((el_state == SLOW_START_UP) || (el_state == NORMAL_UP) || (el_state == SLOW_DOWN_UP) || (el_state == TIMED_SLOW_DOWN_UP)) {
return ROTATING_UP;
}
- if ((el_state == SLOW_START_DOWN)||(el_state == NORMAL_DOWN) || (el_state == SLOW_DOWN_DOWN) || (el_state == TIMED_SLOW_DOWN_DOWN)) {
+ if ((el_state == SLOW_START_DOWN) || (el_state == NORMAL_DOWN) || (el_state == SLOW_DOWN_DOWN) || (el_state == TIMED_SLOW_DOWN_DOWN)) {
return ROTATING_DOWN;
- }
- return NOT_DOING_ANYTHING;
-
+ }
+ return NOT_DOING_ANYTHING;
+
}
-#endif //FEATURE_ELEVATION_CONTROL
-//--------------------------------------------------------------
+#endif // FEATURE_ELEVATION_CONTROL
+// --------------------------------------------------------------
#ifdef FEATURE_AZ_POSITION_PULSE_INPUT
void az_position_pulse_interrupt_handler(){
- //aaaaa
-
- #ifdef DEBUG_POSITION_PULSE_INPUT
- //az_position_pule_interrupt_handler_flag++;
+
+
+ #ifdef DEBUG_POSITION_PULSE_INPUT
+ // az_position_pule_interrupt_handler_flag++;
az_pulse_counter++;
- #endif //DEBUG_POSITION_PULSE_INPUT
-
+ #endif // DEBUG_POSITION_PULSE_INPUT
+
if (current_az_state() == ROTATING_CW) {
az_position_pulse_input_azimuth += AZ_POSITION_PULSE_DEG_PER_PULSE;
last_known_az_state = ROTATING_CW;
@@ -6124,243 +7691,464 @@ void az_position_pulse_interrupt_handler(){
az_position_pulse_input_azimuth -= AZ_POSITION_PULSE_DEG_PER_PULSE;
last_known_az_state = ROTATING_CCW;
} else {
- if (last_known_az_state == ROTATING_CW){
+ #ifndef OPTION_PULSE_IGNORE_AMBIGUOUS_PULSES
+ if (last_known_az_state == ROTATING_CW) {
az_position_pulse_input_azimuth += AZ_POSITION_PULSE_DEG_PER_PULSE;
} else {
- if (last_known_az_state == ROTATING_CCW){
+ if (last_known_az_state == ROTATING_CCW) {
az_position_pulse_input_azimuth -= AZ_POSITION_PULSE_DEG_PER_PULSE;
}
}
- #ifdef DEBUG_POSITION_PULSE_INPUT
+ #endif // OPTION_PULSE_IGNORE_AMBIGUOUS_PULSES
+ #ifdef DEBUG_POSITION_PULSE_INPUT
az_pulse_counter_ambiguous++;
- #endif //DEBUG_POSITION_PULSE_INPUT
+ #endif // DEBUG_POSITION_PULSE_INPUT
}
}
-
+
#ifdef OPTION_AZ_POSITION_PULSE_HARD_LIMIT
- if (az_position_pulse_input_azimuth < configuration.azimuth_starting_point) {
- az_position_pulse_input_azimuth = configuration.azimuth_starting_point;
+ if (az_position_pulse_input_azimuth < azimuth_starting_point) {
+ az_position_pulse_input_azimuth = azimuth_starting_point;
}
- if (az_position_pulse_input_azimuth > (configuration.azimuth_starting_point + configuration.azimuth_rotation_capability)) {
- az_position_pulse_input_azimuth = (configuration.azimuth_starting_point + configuration.azimuth_rotation_capability);
+ if (az_position_pulse_input_azimuth > (azimuth_starting_point + azimuth_rotation_capability)) {
+ az_position_pulse_input_azimuth = (azimuth_starting_point + azimuth_rotation_capability);
}
#else
- if (az_position_pulse_input_azimuth < 0){
+ if (az_position_pulse_input_azimuth < 0) {
az_position_pulse_input_azimuth += 360;
}
- if (az_position_pulse_input_azimuth >= 360){
+ if (az_position_pulse_input_azimuth >= 360) {
az_position_pulse_input_azimuth -= 360;
}
- #endif //OPTION_AZ_POSITION_PULSE_HARD_LIMIT
-
-}
-#endif //FEATURE_AZ_POSITION_PULSE_INPUT
-//--------------------------------------------------------------
+ #endif // OPTION_AZ_POSITION_PULSE_HARD_LIMIT
+
+} /* az_position_pulse_interrupt_handler */
+#endif // FEATURE_AZ_POSITION_PULSE_INPUT
+// --------------------------------------------------------------
#ifdef FEATURE_ELEVATION_CONTROL
#ifdef FEATURE_EL_POSITION_PULSE_INPUT
void el_position_pulse_interrupt_handler(){
#ifdef DEBUG_POSITION_PULSE_INPUT
- //el_position_pule_interrupt_handler_flag++;
+ // el_position_pule_interrupt_handler_flag++;
el_pulse_counter++;
- #endif //DEBUG_POSITION_PULSE_INPUT
-
+ #endif // DEBUG_POSITION_PULSE_INPUT
+
if (current_el_state() == ROTATING_UP) {
el_position_pulse_input_elevation += EL_POSITION_PULSE_DEG_PER_PULSE;
last_known_el_state = ROTATING_UP;
- } else{
+ } else {
if (current_el_state() == ROTATING_DOWN) {
el_position_pulse_input_elevation -= EL_POSITION_PULSE_DEG_PER_PULSE;
last_known_el_state = ROTATING_DOWN;
} else {
- if (last_known_el_state == ROTATING_UP){
+ #ifndef OPTION_PULSE_IGNORE_AMBIGUOUS_PULSES
+ if (last_known_el_state == ROTATING_UP) {
el_position_pulse_input_elevation += EL_POSITION_PULSE_DEG_PER_PULSE;
} else {
- if (last_known_el_state == ROTATING_DOWN){
+ if (last_known_el_state == ROTATING_DOWN) {
el_position_pulse_input_elevation -= EL_POSITION_PULSE_DEG_PER_PULSE;
}
}
- #ifdef DEBUG_POSITION_PULSE_INPUT
+ #endif // OPTION_PULSE_IGNORE_AMBIGUOUS_PULSES
+ #ifdef DEBUG_POSITION_PULSE_INPUT
el_pulse_counter_ambiguous++;
- #endif //DEBUG_POSITION_PULSE_INPUT
+ #endif // DEBUG_POSITION_PULSE_INPUT
}
- }
-
- #ifdef OPTION_EL_POSITION_PULSE_HARD_LIMIT
- if (el_position_pulse_input_elevation < 0){
+ }
+
+ #ifdef OPTION_EL_POSITION_PULSE_HARD_LIMIT
+ if (el_position_pulse_input_elevation < 0) {
el_position_pulse_input_elevation = 0;
}
- if (el_position_pulse_input_elevation > ELEVATION_MAXIMUM_DEGREES){
+ if (el_position_pulse_input_elevation > ELEVATION_MAXIMUM_DEGREES) {
el_position_pulse_input_elevation = ELEVATION_MAXIMUM_DEGREES;
}
- #endif //OPTION_EL_POSITION_PULSE_HARD_LIMIT
-
-
-}
-#endif //FEATURE_EL_POSITION_PULSE_INPUT
-#endif //FEATURE_ELEVATION_CONTROL
-//--------------------------------------------------------------------------
-#ifdef FEATURE_HOST_REMOTE_PROTOCOL
-byte submit_remote_command(byte remote_command_to_send){
+ #endif // OPTION_EL_POSITION_PULSE_HARD_LIMIT
-
- if (remote_unit_command_submitted || suspend_remote_commands) {
+
+} /* el_position_pulse_interrupt_handler */
+#endif // FEATURE_EL_POSITION_PULSE_INPUT
+#endif // FEATURE_ELEVATION_CONTROL
+// --------------------------------------------------------------------------
+#if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+byte submit_remote_command(byte remote_command_to_send, byte parm1, int parm2){
+
+ #ifdef FEATURE_MASTER_WITH_ETHERNET_SLAVE
+ char ethernet_send_string[32];
+ char temp_string[32];
+ #endif //FEATURE_MASTER_WITH_ETHERNET_SLAVE
+
+ #ifdef FEATURE_MASTER_WITH_ETHERNET_SLAVE
+ if (ethernetslavelinkclient0_state != ETHERNET_SLAVE_CONNECTED){return 0;}
+ #endif //FEATURE_MASTER_WITH_ETHERNET_SLAVE
+
+ if ((remote_unit_command_submitted && ((remote_command_to_send == REMOTE_UNIT_AZ_COMMAND) || (remote_command_to_send == REMOTE_UNIT_EL_COMMAND) || (remote_command_to_send == REMOTE_UNIT_CL_COMMAND))) || suspend_remote_commands) {
return 0;
} else {
- switch(remote_command_to_send){
+ switch (remote_command_to_send) {
+ case REMOTE_UNIT_CL_COMMAND:
+ #ifdef FEATURE_MASTER_WITH_SERIAL_SLAVE
+ remote_unit_port->println("CL");
+ #endif //FEATURE_MASTER_WITH_SERIAL_SLAVE
+ #ifdef FEATURE_MASTER_WITH_ETHERNET_SLAVE
+ ethernet_slave_link_send("CL");
+ #endif //FEATURE_MASTER_WITH_ETHERNET_SLAVE
+ #if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
+ if (remote_port_tx_sniff) {control_port->println("CL");}
+ #endif
+ remote_unit_command_submitted = REMOTE_UNIT_CL_COMMAND;
+ break;
+
+
case REMOTE_UNIT_AZ_COMMAND:
- Serial1.println("AZ");
- if (remote_port_tx_sniff) {Serial.println("AZ");}
+ #ifdef FEATURE_MASTER_WITH_SERIAL_SLAVE
+ remote_unit_port->println("AZ");
+ #endif //FEATURE_MASTER_WITH_SERIAL_SLAVE
+ #ifdef FEATURE_MASTER_WITH_ETHERNET_SLAVE
+ ethernet_slave_link_send("AZ");
+ #endif //FEATURE_MASTER_WITH_ETHERNET_SLAVE
+ #if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
+ if (remote_port_tx_sniff) {control_port->println("AZ");}
+ #endif
remote_unit_command_submitted = REMOTE_UNIT_AZ_COMMAND;
break;
+
case REMOTE_UNIT_EL_COMMAND:
- Serial1.println("EL");
- if (remote_port_tx_sniff) {Serial.println("EL");}
+ #ifdef FEATURE_MASTER_WITH_SERIAL_SLAVE
+ remote_unit_port->println("EL");
+ #endif //FEATURE_MASTER_WITH_SERIAL_SLAVE
+ #ifdef FEATURE_MASTER_WITH_ETHERNET_SLAVE
+ ethernet_slave_link_send("EL");
+ #endif //FEATURE_MASTER_WITH_ETHERNET_SLAVE
+ #if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
+ if (remote_port_tx_sniff) {control_port->println("EL");}
+ #endif
remote_unit_command_submitted = REMOTE_UNIT_EL_COMMAND;
- break;
- }
- last_remote_unit_command_time = millis();
+ break;
+
+
+ case REMOTE_UNIT_AW_COMMAND:
+ #ifdef FEATURE_MASTER_WITH_SERIAL_SLAVE
+ take_care_of_pending_remote_command();
+ remote_unit_port->print("AW");
+ parm1 = parm1 - 100; // pin number
+ if (parm1 < 10) {remote_unit_port->print("0");}
+ remote_unit_port->print(parm1);
+ if (parm2 < 10) {remote_unit_port->print("0");}
+ if (parm2 < 100) {remote_unit_port->print("0");}
+ remote_unit_port->println(parm2);
+ #endif //FEATURE_MASTER_WITH_SERIAL_SLAVE
+
+ #ifdef FEATURE_MASTER_WITH_ETHERNET_SLAVE
+ take_care_of_pending_remote_command();
+ strcpy(ethernet_send_string,"AW");
+ parm1 = parm1 - 100; // pin number
+ if (parm1 < 10) {strcat(ethernet_send_string,"0");}
+ dtostrf(parm1,0,0,temp_string);
+ if (parm2 < 10) {strcat(ethernet_send_string,"0");}
+ if (parm2 < 100) {strcat(ethernet_send_string,"0");}
+ dtostrf(parm2,0,0,temp_string);
+ strcat(ethernet_send_string,temp_string);
+ ethernet_slave_link_send(ethernet_send_string);
+ #endif //FEATURE_MASTER_WITH_ETHERNET_SLAVE
+
+ remote_unit_command_submitted = REMOTE_UNIT_OTHER_COMMAND;
+ break;
+
+ case REMOTE_UNIT_DHL_COMMAND:
+ #ifdef FEATURE_MASTER_WITH_SERIAL_SLAVE
+ take_care_of_pending_remote_command();
+ remote_unit_port->print("D");
+ if (parm2 == HIGH) {remote_unit_port->print("H");} else {remote_unit_port->print("L");}
+ parm1 = parm1 - 100;
+ if (parm1 < 10) {remote_unit_port->print("0");}
+ remote_unit_port->println(parm1);
+ #endif //FEATURE_MASTER_WITH_SERIAL_SLAVE
+
+
+ #ifdef FEATURE_MASTER_WITH_ETHERNET_SLAVE
+ take_care_of_pending_remote_command();
+ strcpy(ethernet_send_string,"D");
+ if (parm2 == HIGH) {strcat(ethernet_send_string,"H");} else {strcat(ethernet_send_string,"L");}
+ parm1 = parm1 - 100;
+ if (parm1 < 10) {strcat(ethernet_send_string,"0");}
+ dtostrf(parm1,0,0,temp_string);
+ strcat(ethernet_send_string,temp_string);
+ ethernet_slave_link_send(ethernet_send_string);
+ #endif //FEATURE_MASTER_WITH_ETHERNET_SLAVE
+
+ remote_unit_command_submitted = REMOTE_UNIT_OTHER_COMMAND;
+
+ break;
+
+ case REMOTE_UNIT_DOI_COMMAND:
+ #ifdef FEATURE_MASTER_WITH_SERIAL_SLAVE
+ take_care_of_pending_remote_command();
+ remote_unit_port->print("D");
+ if (parm2 == OUTPUT) {remote_unit_port->print("O");} else {remote_unit_port->print("I");}
+ parm1 = parm1 - 100;
+ if (parm1 < 10) {remote_unit_port->print("0");}
+ remote_unit_port->println(parm1);
+ remote_unit_command_submitted = REMOTE_UNIT_OTHER_COMMAND;
+ // get_remote_port_ok_response();
+ #endif //FEATURE_MASTER_WITH_SERIAL_SLAVE
+
+ #ifdef FEATURE_MASTER_WITH_ETHERNET_SLAVE
+ take_care_of_pending_remote_command();
+ strcpy(ethernet_send_string,"D");
+ if (parm2 == OUTPUT) {strcat(ethernet_send_string,"O");} else {strcat(ethernet_send_string,"I");}
+ parm1 = parm1 - 100;
+ if (parm1 < 10) {strcat(ethernet_send_string,"0");}
+ dtostrf(parm1,0,0,temp_string);
+ strcat(ethernet_send_string,temp_string);
+ ethernet_slave_link_send(ethernet_send_string);
+ remote_unit_command_submitted = REMOTE_UNIT_OTHER_COMMAND;
+ #endif //FEATURE_MASTER_WITH_ETHERNET_SLAVE
+
+ break;
+
+
+ } /* switch */
+ last_remote_unit_command_time = millis();
remote_unit_command_results_available = 0;
return 1;
}
-
-
-}
-#endif //FEATURE_HOST_REMOTE_PROTOCOL
-//--------------------------------------------------------------------------
-#ifdef FEATURE_HOST_REMOTE_PROTOCOL
+
+
+} /* submit_remote_command */
+#endif // defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+
+// --------------------------------------------------------------------------
+
+#if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
byte is_ascii_number(byte char_in){
-
- if ((char_in > 47) && (char_in < 58)) {
- return 1;
- } else {
- return 0;
- }
-
-}
-#endif //FEATURE_HOST_REMOTE_PROTOCOL
-//--------------------------------------------------------------------------
-#ifdef FEATURE_HOST_REMOTE_PROTOCOL
-void service_remote_communications_incoming_serial_buffer(){
-
+ if ((char_in > 47) && (char_in < 58)) {
+ return 1;
+ } else {
+ return 0;
+ }
+
+}\
+
+ #endif // defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+// --------------------------------------------------------------------------
+#if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+void service_remote_communications_incoming_buffer(){
+
+
+ #if defined(FEATURE_CLOCK) && defined(OPTION_SYNC_MASTER_CLOCK_TO_SLAVE)
+ int temp_year = 0;
+ byte temp_month = 0;
+ byte temp_day = 0;
+ byte temp_minute = 0;
+ byte temp_hour = 0;
+ byte temp_sec = 0;
+ #endif // defined(FEATURE_CLOCK) && defined(OPTION_SYNC_MASTER_CLOCK_TO_SLAVE)
+
+
-
byte good_data = 0;
-
- if (serial1_buffer_carriage_return_flag){
-
+
+ if (remote_unit_port_buffer_carriage_return_flag) {
+
#ifdef DEBUG_SVC_REMOTE_COMM_INCOMING_BUFFER
- if (debug_mode){
- Serial.print(F("service_remote_communications_incoming_serial_buffer: serial1_buffer_index: "));
- Serial.print(serial1_buffer_index);
- Serial.print(F(" buffer: "));
- for (int x = 0;x < serial1_buffer_index;x++){
- Serial.write(serial1_buffer[x]);
- }
- Serial.println("$");
+ debug_print("service_remote_communications_incoming_buffer: remote_unit_port_buffer_index: ");
+ debug_print_int(remote_unit_port_buffer_index);
+ debug_print(" buffer: ");
+ for (int x = 0; x < remote_unit_port_buffer_index; x++) {
+ debug_write((char*)remote_unit_port_buffer[x]);
+ debug_println("$");
}
- #endif //DEBUG_SVC_REMOTE_COMM_INCOMING_BUFFER
-
- if (remote_unit_command_submitted) { // this was a solicited response
- switch(remote_unit_command_submitted){
- case REMOTE_UNIT_AZ_COMMAND:
- if ((serial1_buffer_index == 7) && (serial1_buffer[0] == 'A') && (serial1_buffer[1] == 'Z') &&
- (is_ascii_number(serial1_buffer[2])) && (is_ascii_number(serial1_buffer[3])) && (is_ascii_number(serial1_buffer[4])) && (is_ascii_number(serial1_buffer[5]))){
- remote_unit_command_result_float = ((serial1_buffer[2]-48)*100) + ((serial1_buffer[3]-48)*10) + (serial1_buffer[4]-48) + ((serial1_buffer[5]-48)/10.0);
+ #endif // DEBUG_SVC_REMOTE_COMM_INCOMING_BUFFER
+
+ if (remote_unit_command_submitted) { // this was a solicited response
+ switch (remote_unit_command_submitted) {
+
+ case REMOTE_UNIT_CL_COMMAND:
+ if ((remote_unit_port_buffer[0] == 'C') && (remote_unit_port_buffer[1] == 'L') &&
+ (remote_unit_port_buffer[12] == ' ') && (remote_unit_port_buffer[21] == 'Z'))
+ {
+ #if defined(FEATURE_CLOCK) && defined(OPTION_SYNC_MASTER_CLOCK_TO_SLAVE)
+ temp_year = ((remote_unit_port_buffer[2] - 48) * 1000) + ((remote_unit_port_buffer[3] - 48) * 100) + ((remote_unit_port_buffer[4] - 48) * 10) + (remote_unit_port_buffer[5] - 48);
+ temp_month = ((remote_unit_port_buffer[7] - 48) * 10) + (remote_unit_port_buffer[8] - 48);
+ temp_day = ((remote_unit_port_buffer[10] - 48) * 10) + (remote_unit_port_buffer[11] - 48);
+ temp_hour = ((remote_unit_port_buffer[13] - 48) * 10) + (remote_unit_port_buffer[14] - 48);
+ temp_minute = ((remote_unit_port_buffer[16] - 48) * 10) + (remote_unit_port_buffer[17] - 48);
+ temp_sec = ((remote_unit_port_buffer[19] - 48) * 10) + (remote_unit_port_buffer[20] - 48);
+ if ((temp_year > 2013) && (temp_year < 2070) &&
+ (temp_month > 0) && (temp_month < 13) &&
+ (temp_day > 0) && (temp_day < 32) &&
+ (temp_hour >= 0) && (temp_hour < 24) &&
+ (temp_minute >= 0) && (temp_minute < 60) &&
+ (temp_sec >= 0) && (temp_sec < 60) ) {
+
+ clock_year_set = temp_year;
+ clock_month_set = temp_month;
+ clock_day_set = temp_day;
+ clock_hour_set = temp_hour;
+ clock_min_set = temp_minute;
+ clock_sec_set = temp_sec;
+ millis_at_last_calibration = millis();
+ #ifdef DEBUG_SYNC_MASTER_CLOCK_TO_SLAVE
+ debug_println("service_remote_communications_incoming_buffer: clock synced to slave clock");
+ #endif //DEBUG_SYNC_MASTER_CLOCK_TO_SLAVE
+ good_data = 1;
+ if (clock_status == FREE_RUNNING) {clock_status = SLAVE_SYNC;}
+ } else {
+
+ #ifdef DEBUG_SYNC_MASTER_CLOCK_TO_SLAVE
+ debug_println("service_remote_communications_incoming_buffer: slave clock sync error");
+ #endif //DEBUG_SYNC_MASTER_CLOCK_TO_SLAVE
+ if (clock_status == SLAVE_SYNC) {clock_status = FREE_RUNNING;}
+ }
+ #endif // defined(FEATURE_CLOCK) && defined(OPTION_SYNC_MASTER_CLOCK_TO_SLAVE)
+
+ #if !defined(FEATURE_CLOCK) || !defined(OPTION_SYNC_MASTER_CLOCK_TO_SLAVE)
good_data = 1;
- }
- break;
+ #endif //!defined(FEATURE_CLOCK) || !defined(OPTION_SYNC_MASTER_CLOCK_TO_SLAVE)
+ } else {
+ #if defined(FEATURE_CLOCK) && defined(OPTION_SYNC_MASTER_CLOCK_TO_SLAVE)
+ #ifdef DEBUG_SYNC_MASTER_CLOCK_TO_SLAVE
+ debug_print("service_remote_communications_incoming_buffer: REMOTE_UNIT_CL_COMMAND format error. remote_unit_port_buffer_index: ");
+ debug_print_int(remote_unit_port_buffer_index);
+ debug_println("");
+ #endif //DEBUG_SYNC_MASTER_CLOCK_TO_SLAVE
+ if (clock_status == SLAVE_SYNC) {clock_status = FREE_RUNNING;}
+ #endif // defined(FEATURE_CLOCK) && defined(OPTION_SYNC_MASTER_CLOCK_TO_SLAVE)
+ }
+ break;
+ case REMOTE_UNIT_AZ_COMMAND:
+ if ((remote_unit_port_buffer_index == 13) && (remote_unit_port_buffer[0] == 'A') && (remote_unit_port_buffer[1] == 'Z') &&
+ (is_ascii_number(remote_unit_port_buffer[2])) && (is_ascii_number(remote_unit_port_buffer[3])) && (is_ascii_number(remote_unit_port_buffer[4])) && (is_ascii_number(remote_unit_port_buffer[6])) && (is_ascii_number(remote_unit_port_buffer[7])) && (is_ascii_number(remote_unit_port_buffer[8])) && (is_ascii_number(remote_unit_port_buffer[9])) && (is_ascii_number(remote_unit_port_buffer[10])) && (is_ascii_number(remote_unit_port_buffer[11]))) {
+ remote_unit_command_result_float = ((remote_unit_port_buffer[2] - 48) * 100) + ((remote_unit_port_buffer[3] - 48) * 10) + (remote_unit_port_buffer[4] - 48) + ((remote_unit_port_buffer[6] - 48) / 10.0) + ((remote_unit_port_buffer[7] - 48) / 100.0) + ((remote_unit_port_buffer[8] - 48) / 1000.0) + ((remote_unit_port_buffer[9] - 48) / 10000.0) + ((remote_unit_port_buffer[10] - 48) / 100000.0) + ((remote_unit_port_buffer[11] - 48) / 1000000.0);
+ good_data = 1;
+ }
+ break;
case REMOTE_UNIT_EL_COMMAND:
- if ((serial1_buffer_index == 8) && (serial1_buffer[0] == 'E') && (serial1_buffer[1] == 'L') &&
- (is_ascii_number(serial1_buffer[3])) && (is_ascii_number(serial1_buffer[4])) && (is_ascii_number(serial1_buffer[5])) && (is_ascii_number(serial1_buffer[6]))){
- remote_unit_command_result_float = ((serial1_buffer[3]-48)*100) + ((serial1_buffer[4]-48)*10) + (serial1_buffer[5]-48) + ((serial1_buffer[6]-48)/10.0);
- if (serial1_buffer[2] == '+') {
+ if ((remote_unit_port_buffer_index == 14) && (remote_unit_port_buffer[0] == 'E') && (remote_unit_port_buffer[1] == 'L') &&
+ (is_ascii_number(remote_unit_port_buffer[3])) && (is_ascii_number(remote_unit_port_buffer[4])) && (is_ascii_number(remote_unit_port_buffer[5])) && (is_ascii_number(remote_unit_port_buffer[7])) && (is_ascii_number(remote_unit_port_buffer[8])) && (is_ascii_number(remote_unit_port_buffer[9])) && (is_ascii_number(remote_unit_port_buffer[10])) && (is_ascii_number(remote_unit_port_buffer[11])) && (is_ascii_number(remote_unit_port_buffer[12]))) {
+ remote_unit_command_result_float = ((remote_unit_port_buffer[3] - 48) * 100) + ((remote_unit_port_buffer[4] - 48) * 10) + (remote_unit_port_buffer[5] - 48) + ((remote_unit_port_buffer[7] - 48) / 10.0) + ((remote_unit_port_buffer[8] - 48) / 100.0) + ((remote_unit_port_buffer[9] - 48) / 1000.0) + ((remote_unit_port_buffer[10] - 48) / 10000.0) + ((remote_unit_port_buffer[11] - 48) / 100000.0) + ((remote_unit_port_buffer[12] - 48) / 1000000.0);
+ if (remote_unit_port_buffer[2] == '+') {
good_data = 1;
}
- if (serial1_buffer[2] == '-') {
+ if (remote_unit_port_buffer[2] == '-') {
remote_unit_command_result_float = remote_unit_command_result_float * -1.0;
good_data = 1;
- }
- }
- break;
- }
+ }
+ }
+ break;
+ case REMOTE_UNIT_OTHER_COMMAND:
+ if ((remote_unit_port_buffer[0] == 'O') && (remote_unit_port_buffer[1] == 'K')) {
+ good_data = 1;
+ }
+ break;
+ } /* switch */
if (good_data) {
- remote_unit_command_results_available = remote_unit_command_submitted;
- remote_unit_good_results++;
-
- #ifdef DEBUG_SVC_REMOTE_COMM_INCOMING_BUFFER
- if (debug_mode){
- Serial.print(F("service_remote_communications_incoming_serial_buffer: remote_unit_command_results_available: "));
- Serial.print(remote_unit_command_results_available);
- Serial.print(F(" remote_unit_command_result_float: "));
- Serial.println(remote_unit_command_result_float);
+ if (remote_unit_command_submitted != REMOTE_UNIT_OTHER_COMMAND) {
+ remote_unit_command_results_available = remote_unit_command_submitted;
}
- #endif //DEBUG_SVC_REMOTE_COMM_INCOMING_BUFFER
-
-
+ remote_unit_good_results++;
+
+ #ifdef DEBUG_SVC_REMOTE_COMM_INCOMING_BUFFER
+ debug_print("service_remote_communications_incoming_buffer: remote_unit_command_results_available: ");
+ debug_print_int(remote_unit_command_results_available);
+ debug_print(" remote_unit_command_result_float: ");
+ debug_print_float(remote_unit_command_result_float,2);
+ debug_println("");
+ #endif // DEBUG_SVC_REMOTE_COMM_INCOMING_BUFFER
+
+
} else {
+
+ #ifdef DEBUG_SVC_REMOTE_COMM_INCOMING_BUFFER_BAD_DATA
+ debug_print("service_remote_communications_incoming_buffer: bad data: remote_unit_command_submitted: ");
+ switch (remote_unit_command_submitted) {
+ case REMOTE_UNIT_AZ_COMMAND: debug_print("REMOTE_UNIT_AZ_COMMAND"); break;
+ case REMOTE_UNIT_EL_COMMAND: debug_print("REMOTE_UNIT_EL_COMMAND"); break;
+ case REMOTE_UNIT_OTHER_COMMAND: debug_print("REMOTE_UNIT_OTHER_COMMAND"); break;
+ default: debug_print("UNDEFINED"); break;
+ }
+ debug_print(" buffer_index:");
+ debug_print_int(remote_unit_port_buffer_index);
+ debug_print(" buffer: ");
+ for (int x = 0; x < remote_unit_port_buffer_index; x++) {
+ debug_write((char*)remote_unit_port_buffer[x]);
+ }
+ debug_println("$");
+ #endif // DEBUG_SVC_REMOTE_COMM_INCOMING_BUFFER_BAD_DATA
+
+
remote_unit_command_results_available = 0;
remote_unit_bad_results++;
}
- remote_unit_command_submitted = 0;
+ remote_unit_command_submitted = 0;
} else { // this was an unsolicited message
-
+
}
- serial1_buffer_carriage_return_flag = 0;
- serial1_buffer_index = 0;
+ remote_unit_port_buffer_carriage_return_flag = 0;
+ remote_unit_port_buffer_index = 0;
}
-
+
// has a command timed out?
- if ((remote_unit_command_submitted) && ((millis() - last_remote_unit_command_time) > REMOTE_UNIT_COMMAND_TIMEOUT_MS)){
- remote_unit_command_timeouts++;
+ if ((remote_unit_command_submitted) && ((millis() - last_remote_unit_command_time) > REMOTE_UNIT_COMMAND_TIMEOUT_MS)) {
+
+ #if defined(FEATURE_CLOCK) && defined(OPTION_SYNC_MASTER_CLOCK_TO_SLAVE)
+ if ((remote_unit_command_submitted == REMOTE_UNIT_CL_COMMAND) && (clock_status == SLAVE_SYNC)){
+ clock_status = FREE_RUNNING;
+ }
+ #endif //defined(FEATURE_CLOCK) && defined(OPTION_SYNC_MASTER_CLOCK_TO_SLAVE)
+
+ remote_unit_command_timeouts++;
remote_unit_command_submitted = 0;
- serial1_buffer_index = 0;
+ remote_unit_port_buffer_index = 0;
+
}
-
+
// have characters been in the buffer for some time but no carriage return?
- if ((serial1_buffer_index) && (!remote_unit_command_submitted) && ((millis() - serial1_last_receive_time) > REMOTE_UNIT_COMMAND_TIMEOUT_MS)) {
- serial1_buffer_index = 0;
+ if ((remote_unit_port_buffer_index) && (!remote_unit_command_submitted) && ((millis() - serial1_last_receive_time) > REMOTE_UNIT_COMMAND_TIMEOUT_MS)) {
+ remote_unit_port_buffer_index = 0;
remote_unit_incoming_buffer_timeouts++;
}
-
-}
-#endif //FEATURE_HOST_REMOTE_PROTOCOL
-//--------------------------------------------------------------------------
+} /* service_remote_communications_incoming_buffer */
+
+#endif // defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+// --------------------------------------------------------------------------
#ifdef FEATURE_AZIMUTH_CORRECTION
float correct_azimuth(float azimuth_in){
- if (sizeof(azimuth_calibration_from) != sizeof(azimuth_calibration_to)){
+ if (sizeof(azimuth_calibration_from) != sizeof(azimuth_calibration_to)) {
return azimuth_in;
}
- for (unsigned int x = 0;x < (sizeof(azimuth_calibration_from)-2);x++){
- if ((azimuth_in >= azimuth_calibration_from[x]) && (azimuth_in <= azimuth_calibration_from[x+1])){
- return (map(azimuth_in*10,azimuth_calibration_from[x]*10,azimuth_calibration_from[x+1]*10,azimuth_calibration_to[x]*10,azimuth_calibration_to[x+1]*10))/10.0;
+ for (unsigned int x = 0; x < (sizeof(azimuth_calibration_from) - 2); x++) {
+ if ((azimuth_in >= azimuth_calibration_from[x]) && (azimuth_in <= azimuth_calibration_from[x + 1])) {
+ return (map(azimuth_in * 10, azimuth_calibration_from[x] * 10, azimuth_calibration_from[x + 1] * 10, azimuth_calibration_to[x] * 10, azimuth_calibration_to[x + 1] * 10)) / 10.0;
}
}
return(azimuth_in);
}
-#endif //FEATURE_AZIMUTH_CORRECTION
-//--------------------------------------------------------------------------
+#endif // FEATURE_AZIMUTH_CORRECTION
+// --------------------------------------------------------------------------
#ifdef FEATURE_ELEVATION_CORRECTION
float correct_elevation(float elevation_in){
- if (sizeof(elevation_calibration_from) != sizeof(elevation_calibration_to)){
+ if (sizeof(elevation_calibration_from) != sizeof(elevation_calibration_to)) {
return elevation_in;
}
- for (unsigned int x = 0;x < (sizeof(elevation_calibration_from)-2);x++){
- if ((elevation_in >= elevation_calibration_from[x]) && (elevation_in <= elevation_calibration_from[x+1])){
- return (map(elevation_in*10,elevation_calibration_from[x]*10,elevation_calibration_from[x+1]*10,elevation_calibration_to[x]*10,elevation_calibration_to[x+1]*10))/10.0;
+ for (unsigned int x = 0; x < (sizeof(elevation_calibration_from) - 2); x++) {
+ if ((elevation_in >= elevation_calibration_from[x]) && (elevation_in <= elevation_calibration_from[x + 1])) {
+ return (map(elevation_in * 10, elevation_calibration_from[x] * 10, elevation_calibration_from[x + 1] * 10, elevation_calibration_to[x] * 10, elevation_calibration_to[x + 1] * 10)) / 10.0;
}
}
return(elevation_in);
}
-#endif //FEATURE_ELEVATION_CORRECTION
-//--------------------------------------------------------------------------
+#endif // FEATURE_ELEVATION_CORRECTION
+// --------------------------------------------------------------------------
#ifdef FEATURE_JOYSTICK_CONTROL
void check_joystick(){
@@ -6370,180 +8158,3339 @@ void check_joystick(){
static int joystick_resting_x = 0;
static int joystick_resting_y = 0;
-//zzzz
-
-
-
static unsigned long last_joystick_az_action_time = 0;
-
+
static byte joystick_azimuth_rotation = NOT_DOING_ANYTHING;
#ifdef FEATURE_ELEVATION_CONTROL
static byte joystick_elevation_rotation = NOT_DOING_ANYTHING;
- static unsigned long last_joystick_el_action_time = 0;
- #endif //FEATURE_ELEVATION_CONTROL
+ static unsigned long last_joystick_el_action_time = 0;
+ #endif // FEATURE_ELEVATION_CONTROL
if ((joystick_resting_x == 0) || (joystick_resting_y == 0)) { // initialize the resting readings if this is our first time here
-
- joystick_resting_x = analogRead(pin_joystick_x);
- joystick_resting_y = analogRead(pin_joystick_y);
-
- } else {
-
- joystick_x = analogRead(pin_joystick_x);
- joystick_y = analogRead(pin_joystick_y);
- if ((millis() - last_joystick_az_action_time) > JOYSTICK_WAIT_TIME_MS) {
+ joystick_resting_x = analogReadEnhanced(pin_joystick_x);
+ joystick_resting_y = analogReadEnhanced(pin_joystick_y);
+
+ } else {
+
+ joystick_x = analogReadEnhanced(pin_joystick_x);
+ joystick_y = analogReadEnhanced(pin_joystick_y);
+
+ if ((millis() - last_joystick_az_action_time) > JOYSTICK_WAIT_TIME_MS) {
#ifdef DEBUG_JOYSTICK
static unsigned long last_debug_joystick_status = 0;
-
- if ((debug_mode) && ((millis() - last_debug_joystick_status) > 1000)){
- Serial.print("check_joystick: x: ");
- Serial.print(joystick_x);
- Serial.print("\ty: ");
- Serial.println(joystick_y);
+
+ if ((debug_mode) && ((millis() - last_debug_joystick_status) > 1000)) {
+ control_port->print("check_joystick: x: ");
+ control_port->print(joystick_x);
+ control_port->print("\ty: ");
+ control_port->println(joystick_y);
last_debug_joystick_status = millis();
}
- #endif //DEBUG_JOYSTICK
-
+ #endif // DEBUG_JOYSTICK
+
#ifndef OPTION_JOYSTICK_REVERSE_X_AXIS
- if ((joystick_resting_x-joystick_x) < (joystick_resting_x * -0.2)) { // left
+ if ((joystick_resting_x - joystick_x) < (joystick_resting_x * -0.2)) { // left
#else
- if ((joystick_resting_x-joystick_x) > (joystick_resting_x * 0.2)) {
+ if ((joystick_resting_x - joystick_x) > (joystick_resting_x * 0.2)) {
#endif
#ifdef DEBUG_JOYSTICK
- if (debug_mode){Serial.println("check_joystick: L");}
- #endif //DEBUG_JOYSTICK
+ if (debug_mode) {
+ control_port->println("check_joystick: L");
+ }
+ #endif // DEBUG_JOYSTICK
if (current_az_state() != ROTATING_CCW) {
- submit_request(AZ,REQUEST_CCW,0);
- }
- joystick_azimuth_rotation = ROTATING_CCW;
+ submit_request(AZ, REQUEST_CCW, 0, 1);
+ }
+ joystick_azimuth_rotation = ROTATING_CCW;
last_joystick_az_action_time = millis();
-
+
} else {
#ifndef OPTION_JOYSTICK_REVERSE_X_AXIS
- if ((joystick_resting_x-joystick_x) > (joystick_resting_x * 0.2)) { // right
+ if ((joystick_resting_x - joystick_x) > (joystick_resting_x * 0.2)) { // right
#else
- if ((joystick_resting_x-joystick_x) < (joystick_resting_x * -0.2)) {
+ if ((joystick_resting_x - joystick_x) < (joystick_resting_x * -0.2)) {
#endif
#ifdef DEBUG_JOYSTICK
- if (debug_mode){Serial.println("check_joystick: R");}
- #endif //DEBUG_JOYSTICK
+ if (debug_mode) {
+ control_port->println("check_joystick: R");
+ }
+ #endif // DEBUG_JOYSTICK
if (current_az_state() != ROTATING_CW) {
- submit_request(AZ,REQUEST_CW,0);
- }
+ submit_request(AZ, REQUEST_CW, 0, 2);
+ }
joystick_azimuth_rotation = ROTATING_CW;
last_joystick_az_action_time = millis();
-
+
} else { // joystick is in X axis resting position
if (joystick_azimuth_rotation != NOT_DOING_ANYTHING) {
if (current_az_state() != NOT_DOING_ANYTHING) {
- submit_request(AZ,REQUEST_STOP,0);
+ submit_request(AZ, REQUEST_STOP, 0, 3);
last_joystick_az_action_time = millis();
}
joystick_azimuth_rotation = NOT_DOING_ANYTHING;
}
}
-
+
}
-
+
}
-
- if ((millis() - last_joystick_el_action_time) > JOYSTICK_WAIT_TIME_MS) {
- #ifdef FEATURE_ELEVATION_CONTROL
+
+ #ifdef FEATURE_ELEVATION_CONTROL
+ if ((millis() - last_joystick_el_action_time) > JOYSTICK_WAIT_TIME_MS) {
#ifndef OPTION_JOYSTICK_REVERSE_Y_AXIS
- if ((joystick_resting_y-joystick_y) > (joystick_resting_y * 0.2)) { // down
- #else
- if ((joystick_resting_y-joystick_y) < (joystick_resting_y * -0.2)) {
- #endif
- #ifdef DEBUG_JOYSTICK
- if (debug_mode){Serial.println("check_joystick: D");}
- #endif //DEBUG_JOYSTICK
+ if ((joystick_resting_y - joystick_y) > (joystick_resting_y * 0.2)) { // down
+ #else
+ if ((joystick_resting_y - joystick_y) < (joystick_resting_y * -0.2)) {
+ #endif
+ #ifdef DEBUG_JOYSTICK
+ if (debug_mode) {
+ control_port->println("check_joystick: D");
+ }
+ #endif // DEBUG_JOYSTICK
if (current_el_state() != ROTATING_DOWN) {
- submit_request(EL,REQUEST_DOWN,0);
+ submit_request(EL, REQUEST_DOWN, 0, 4);
}
joystick_elevation_rotation = ROTATING_DOWN;
- last_joystick_el_action_time = millis();
+ last_joystick_el_action_time = millis();
} else {
- #ifndef OPTION_JOYSTICK_REVERSE_Y_AXIS
- if ((joystick_resting_y-joystick_y) < (joystick_resting_y * -0.2)) { // up
- #else
- if ((joystick_resting_y-joystick_y) > (joystick_resting_y * 0.2)) {
- #endif
- #ifdef DEBUG_JOYSTICK
- if (debug_mode){Serial.println("check_joystick: U");}
- #endif //DEBUG_JOYSTICK
+ #ifndef OPTION_JOYSTICK_REVERSE_Y_AXIS
+ if ((joystick_resting_y - joystick_y) < (joystick_resting_y * -0.2)) { // up
+ #else
+ if ((joystick_resting_y - joystick_y) > (joystick_resting_y * 0.2)) {
+ #endif
+ #ifdef DEBUG_JOYSTICK
+ if (debug_mode) {
+ control_port->println("check_joystick: U");
+ }
+ #endif // DEBUG_JOYSTICK
if (current_el_state() != ROTATING_UP) {
- submit_request(EL,REQUEST_UP,0);
+ submit_request(EL, REQUEST_UP, 0, 5);
}
joystick_elevation_rotation = ROTATING_UP;
last_joystick_el_action_time = millis();
-
+
} else { // Y axis is in resting position
if (joystick_elevation_rotation != NOT_DOING_ANYTHING) {
if (current_el_state() != NOT_DOING_ANYTHING) {
- submit_request(EL,REQUEST_STOP,0);
+ submit_request(EL, REQUEST_STOP, 0, 6);
last_joystick_el_action_time = millis();
}
joystick_elevation_rotation = NOT_DOING_ANYTHING;
- }
+ }
}
}
- #endif //FEATURE_ELEVATION_CONTROL
-
- }
-
- }
-
+
+
+ }
+ #endif // FEATURE_ELEVATION_CONTROL
+
+ }
+
+
+} /* check_joystick */
+#endif // FEATURE_JOYSTICK_CONTROL
+// --------------------------------------------------------------------------
-}
-#endif //FEATURE_JOYSTICK_CONTROL
-//--------------------------------------------------------------------------
-
#ifdef FEATURE_ROTATION_INDICATOR_PIN
void service_rotation_indicator_pin(){
static byte rotation_indication_pin_state = 0;
static unsigned long time_rotation_went_inactive = 0;
-
+
#ifdef FEATURE_ELEVATION_CONTROL
- if ((!rotation_indication_pin_state) && ((az_state != IDLE) || (el_state != IDLE))){
- #else
- if ((!rotation_indication_pin_state) && ((az_state != IDLE))){
- #endif
- if (rotation_indication_pin){
- digitalWrite(rotation_indication_pin,ROTATION_INDICATOR_PIN_ACTIVE_STATE);
+ if ((!rotation_indication_pin_state) && ((az_state != IDLE) || (el_state != IDLE))) {
+ #else
+ if ((!rotation_indication_pin_state) && ((az_state != IDLE))) {
+ #endif
+ if (rotation_indication_pin) {
+ digitalWriteEnhanced(rotation_indication_pin, ROTATION_INDICATOR_PIN_ACTIVE_STATE);
}
- rotation_indication_pin_state = 1;
- #ifdef DEBUG_ROTATION_INDICATION_PIN
- if (debug_mode){Serial.println(F("service_rotation_indicator_pin: active"));}
- #endif
+ rotation_indication_pin_state = 1;
+ #ifdef DEBUG_ROTATION_INDICATION_PIN
+ if (debug_mode) {
+ control_port->println(F("service_rotation_indicator_pin: active"));
+ }
+ #endif
}
-
- #ifdef FEATURE_ELEVATION_CONTROL
- if ((rotation_indication_pin_state) && (az_state == IDLE) && (el_state == IDLE)){
- #else
- if ((rotation_indication_pin_state) && (az_state == IDLE)){
- #endif
- if (time_rotation_went_inactive == 0){
+
+ #ifdef FEATURE_ELEVATION_CONTROL
+ if ((rotation_indication_pin_state) && (az_state == IDLE) && (el_state == IDLE)) {
+ #else
+ if ((rotation_indication_pin_state) && (az_state == IDLE)) {
+ #endif
+ if (time_rotation_went_inactive == 0) {
time_rotation_went_inactive = millis();
} else {
- if ((millis() - time_rotation_went_inactive) >= ((ROTATION_INDICATOR_PIN_TIME_DELAY_SECONDS * 1000)+(ROTATION_INDICATOR_PIN_TIME_DELAY_MINUTES * 60 * 1000))){
- if (rotation_indication_pin){
- digitalWrite(rotation_indication_pin,ROTATION_INDICATOR_PIN_INACTIVE_STATE);
+ if ((millis() - time_rotation_went_inactive) >= ((ROTATION_INDICATOR_PIN_TIME_DELAY_SECONDS * 1000) + (ROTATION_INDICATOR_PIN_TIME_DELAY_MINUTES * 60 * 1000))) {
+ if (rotation_indication_pin) {
+ digitalWriteEnhanced(rotation_indication_pin, ROTATION_INDICATOR_PIN_INACTIVE_STATE);
}
- rotation_indication_pin_state = 0;
- time_rotation_went_inactive = 0;
- #ifdef DEBUG_ROTATION_INDICATION_PIN
- if (debug_mode){Serial.println(F("service_rotation_indicator_pin: inactive"));}
- #endif
+ rotation_indication_pin_state = 0;
+ time_rotation_went_inactive = 0;
+ #ifdef DEBUG_ROTATION_INDICATION_PIN
+ if (debug_mode) {
+ control_port->println(F("service_rotation_indicator_pin: inactive"));
+ }
+ #endif
}
}
}
-
-
+
+
+} /* service_rotation_indicator_pin */
+ #endif // FEATURE_ROTATION_INDICATOR_PIN
+// --------------------------------------------------------------
+#ifdef FEATURE_PARK
+void deactivate_park(){
+
+ park_status = NOT_PARKED;
+ park_serial_initiated = 0;
}
-#endif //FEATURE_ROTATION_INDICATOR_PIN
+#endif // FEATURE_PARK
+
+// --------------------------------------------------------------
+#ifdef FEATURE_PARK
+void initiate_park(){
+
+ #ifdef DEBUG_PARK
+ control_port->println(F("initiate_park: park initiated"));
+ #endif // DEBUG_PARK
+
+ byte park_initiated = 0;
+
+ stop_all_tracking();
+
+ if (abs(raw_azimuth - PARK_AZIMUTH) > (AZIMUTH_TOLERANCE * HEADING_MULTIPLIER)) {
+ submit_request(AZ, REQUEST_AZIMUTH_RAW, PARK_AZIMUTH, 7);
+ park_initiated = 1;
+ }
+ #ifdef FEATURE_ELEVATION_CONTROL
+ if (abs(elevation - PARK_ELEVATION) > (ELEVATION_TOLERANCE * HEADING_MULTIPLIER)) {
+ submit_request(EL, REQUEST_ELEVATION, PARK_ELEVATION, 8);
+ park_initiated = 1;
+ }
+ #endif // FEATURE_ELEVATION
+
+ if (park_initiated) {
+ park_status = PARK_INITIATED;
+ } else {
+ park_status = PARKED;
+ }
+
+} /* initiate_park */
+ #endif // FEATURE_PARK
+
+// --------------------------------------------------------------
+#ifdef FEATURE_PARK
+void service_park(){
+
+ static byte last_park_status = NOT_PARKED;
+
+ if (park_status == PARKED) {
+ if (abs(raw_azimuth - PARK_AZIMUTH) > (AZIMUTH_TOLERANCE * HEADING_MULTIPLIER)) {
+ park_status = NOT_PARKED;
+ }
+ #ifdef FEATURE_ELEVATION_CONTROL
+ if (abs(elevation - PARK_ELEVATION) > (ELEVATION_TOLERANCE * HEADING_MULTIPLIER)) {
+ park_status = NOT_PARKED;
+ }
+ #endif // FEATURE_ELEVATION_CONTROL
+ }
+ if (park_status != last_park_status) {
+ switch (park_status) {
+ case NOT_PARKED:
+ if (park_in_progress_pin) {
+ digitalWriteEnhanced(park_in_progress_pin, LOW);
+ }
+ if (parked_pin) {
+ digitalWriteEnhanced(parked_pin, LOW);
+ }
+ #ifdef DEBUG_PARK
+ control_port->println(F("service_park: park_in_progress_pin: LOW parked_pin: LOW"));
+ #endif // DEBUG_PARK
+ break;
+ case PARK_INITIATED:
+ if (park_in_progress_pin) {
+ digitalWriteEnhanced(park_in_progress_pin, HIGH);
+ }
+ if (parked_pin) {
+ digitalWriteEnhanced(parked_pin, LOW);
+ }
+ #ifdef DEBUG_PARK
+ control_port->println(F("service_park: park_in_progress_pin: HIGH parked_pin: LOW"));
+ #endif // DEBUG_PARK
+ break;
+ case PARKED:
+ if (park_in_progress_pin) {
+ digitalWriteEnhanced(park_in_progress_pin, LOW);
+ }
+ if (parked_pin) {
+ digitalWriteEnhanced(parked_pin, HIGH);
+ }
+ if (park_serial_initiated) {
+ #if defined(FEATURE_REMOTE_UNIT_SLAVE) || defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION)
+ control_port->println(F("Parked."));
+ #endif
+ park_serial_initiated = 0;
+ }
+ #ifdef DEBUG_PARK
+ control_port->println(F("service_park: park_in_progress_pin: LOW parked_pin: HIGH"));
+ #endif // DEBUG_PARK
+ break;
+ } /* switch */
+ }
+
+ last_park_status = park_status;
+
+} /* service_park */
+#endif // FEATURE_PARK
+
+// --------------------------------------------------------------
+
+#ifdef FEATURE_LIMIT_SENSE
+void check_limit_sense(){
+
+ static byte az_limit_tripped = 0;
+
+ #ifdef FEATURE_ELEVATION_CONTROL
+ static byte el_limit_tripped = 0;
+ #endif // FEATURE_ELEVATION_CONTROL
+
+ if (az_limit_sense_pin) {
+ if (digitalReadEnhanced(az_limit_sense_pin) == 0) {
+ if (!az_limit_tripped) {
+ submit_request(AZ, REQUEST_KILL, 0, 9);
+ az_limit_tripped = 1;
+ #ifdef DEBUG_LIMIT_SENSE
+ control_port->println(F("check_limit_sense: az limit tripped"));
+ #endif // DEBUG_LIMIT_SENSE
+ }
+ } else {
+ az_limit_tripped = 0;
+ }
+ }
+
+ #ifdef FEATURE_ELEVATION_CONTROL
+ if (el_limit_sense_pin) {
+ if (digitalReadEnhanced(el_limit_sense_pin) == 0) {
+ if (!el_limit_tripped) {
+ submit_request(EL, REQUEST_KILL, 0, 10);
+ el_limit_tripped = 1;
+ #ifdef DEBUG_LIMIT_SENSE
+ control_port->println(F("check_limit_sense: el limit tripped"));
+ #endif // DEBUG_LIMIT_SENSE
+ }
+ } else {
+ el_limit_tripped = 0;
+ }
+ }
+ #endif // FEATURE_ELEVATION_CONTROL
+
+
+} /* check_limit_sense */
+ #endif // FEATURE_LIMIT_SENSE
+// --------------------------------------------------------------
+#ifdef FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
+void az_position_incremental_encoder_interrupt_handler(){
+
+ byte rotation_result = 0;
+ byte current_phase_a = digitalReadEnhanced(az_incremental_encoder_pin_phase_a);
+ byte current_phase_b = digitalReadEnhanced(az_incremental_encoder_pin_phase_b);
+ byte current_phase_z = digitalReadEnhanced(az_incremental_encoder_pin_phase_z);
+
+ #ifdef DEBUG_AZ_POSITION_INCREMENTAL_ENCODER
+ az_position_incremental_encoder_interrupt++;
+ #endif // DEBUG_AZ_POSITION_INCREMENTAL_ENCODER
+
+ if ((az_3_phase_encoder_last_phase_a_state != current_phase_a) || (az_3_phase_encoder_last_phase_b_state != current_phase_b)) {
+ if (az_3_phase_encoder_last_phase_a_state == LOW) {
+ rotation_result++;
+ }
+ rotation_result = rotation_result << 1;
+ if (az_3_phase_encoder_last_phase_b_state == LOW) {
+ rotation_result++;
+ }
+ rotation_result = rotation_result << 1;
+ if (current_phase_a == LOW) {
+ rotation_result++;
+ }
+ rotation_result = rotation_result << 1;
+ if (current_phase_b == LOW) {
+ rotation_result++;
+ }
+ switch (rotation_result) {
+ case B0010: //az_incremental_encoder_position++; break;
+ case B1011: //az_incremental_encoder_position++; break;
+ case B1101: //az_incremental_encoder_position++; break;
+ case B0100: az_incremental_encoder_position++; break;
+
+ case B0001: //az_incremental_encoder_position--; break;
+ case B0111: //az_incremental_encoder_position--; break;
+ case B1110: //az_incremental_encoder_position--; break;
+ case B1000: az_incremental_encoder_position--; break;
+ }
+
+ if (az_incremental_encoder_position > ((int(AZ_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.) - 1) * 2)) {
+ az_incremental_encoder_position = 0;
+ }
+ if (az_incremental_encoder_position < 0) {
+ az_incremental_encoder_position = ((int(AZ_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.) - 1) * 2);
+ }
+
+ if ((current_phase_a == LOW) && (current_phase_b == LOW) && (current_phase_z == LOW)) {
+ if ((az_incremental_encoder_position < int((AZ_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.) / 2)) || (az_incremental_encoder_position > int((AZ_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.) * 1.5))) {
+ az_incremental_encoder_position = 0;
+ } else {
+ az_incremental_encoder_position = int(AZ_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.);
+ }
+ }
+
+ az_3_phase_encoder_last_phase_a_state = current_phase_a;
+ az_3_phase_encoder_last_phase_b_state = current_phase_b;
+
+ }
+
+} /* az_position_incremental_encoder_interrupt_handler */
+ #endif // FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
+// --------------------------------------------------------------
+
+#ifdef FEATURE_EL_POSITION_INCREMENTAL_ENCODER
+void el_position_incremental_encoder_interrupt_handler(){
+
+ byte rotation_result = 0;
+ byte current_phase_a = digitalReadEnhanced(el_incremental_encoder_pin_phase_a);
+ byte current_phase_b = digitalReadEnhanced(el_incremental_encoder_pin_phase_b);
+ byte current_phase_z = digitalReadEnhanced(el_incremental_encoder_pin_phase_z);
+
+ #ifdef DEBUG_EL_POSITION_INCREMENTAL_ENCODER
+ el_position_incremental_encoder_interrupt++;
+ #endif // DEBUG_EL_POSITION_INCREMENTAL_ENCODER
+
+ if ((el_3_phase_encoder_last_phase_a_state != current_phase_a) || (el_3_phase_encoder_last_phase_b_state != current_phase_b)) {
+ if (el_3_phase_encoder_last_phase_a_state == LOW) {
+ rotation_result++;
+ }
+ rotation_result = rotation_result << 1;
+ if (el_3_phase_encoder_last_phase_b_state == LOW) {
+ rotation_result++;
+ }
+ rotation_result = rotation_result << 1;
+ if (current_phase_a == LOW) {
+ rotation_result++;
+ }
+ rotation_result = rotation_result << 1;
+ if (current_phase_b == LOW) {
+ rotation_result++;
+ }
+ switch (rotation_result) {
+ case B0010: //el_incremental_encoder_position++; break;
+ case B1011: //el_incremental_encoder_position++; break;
+ case B1101: //el_incremental_encoder_position++; break;
+ case B0100: el_incremental_encoder_position++; break;
+
+ case B0001: //el_incremental_encoder_position--; break;
+ case B0111: //el_incremental_encoder_position--; break;
+ case B1110: //el_incremental_encoder_position--; break;
+ case B1000: el_incremental_encoder_position--; break;
+ }
+
+
+ if ((current_phase_a == LOW) && (current_phase_b == LOW) && (current_phase_z == LOW)) {
+ el_incremental_encoder_position = 0;
+ } else {
+
+ if (el_incremental_encoder_position < 0) {
+ el_incremental_encoder_position = int((EL_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.) - 1);
+ }
+
+ if (el_incremental_encoder_position >= int(EL_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.)) {
+ el_incremental_encoder_position = 0;
+ }
+
+ }
+
+ /*
+
+ if (el_incremental_encoder_position > ((int((EL_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.)) - 1) * 2)) {
+ el_incremental_encoder_position = 0;
+ }
+ if (el_incremental_encoder_position < 0) {
+ el_incremental_encoder_position = ((int(((EL_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.)*4.)) - 1) * 2);
+ }
+
+ if ((current_phase_a == LOW) && (current_phase_b == LOW) && (current_phase_z == LOW)) {
+ if ((el_incremental_encoder_position < int((EL_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.) / 2)) || (el_incremental_encoder_position > int((EL_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.) * 1.5))) {
+ el_incremental_encoder_position = 0;
+ } else {
+ el_incremental_encoder_position = int((EL_POSITION_INCREMENTAL_ENCODER_PULSES_PER_REV*4.));
+ }
+ }
+
+ */
+
+ el_3_phase_encoder_last_phase_a_state = current_phase_a;
+ el_3_phase_encoder_last_phase_b_state = current_phase_b;
+
+ }
+
+} /* el_position_incremental_encoder_interrupt_handler */
+ #endif // FEATURE_EL_POSITION_INCREMENTAL_ENCODER
+
+// --------------------------------------------------------------
+
+void pinModeEnhanced(uint8_t pin, uint8_t mode){
+
+ #if !defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) && !defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+ pinMode(pin, mode);
+ #else
+ if (pin < 100) {
+ pinMode(pin, mode);
+ } else {
+ submit_remote_command(REMOTE_UNIT_DHL_COMMAND, pin, mode);
+ }
+ #endif // !defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) && !defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+
+}
+
+// --------------------------------------------------------------
+
+void digitalWriteEnhanced(uint8_t pin, uint8_t writevalue){
+
+
+
+ #if !defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) && !defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+ digitalWrite(pin, writevalue);
+ #else
+ if (pin < 100) {
+ digitalWrite(pin, writevalue);
+ } else {
+ submit_remote_command(REMOTE_UNIT_DHL_COMMAND, pin, writevalue);
+ }
+ #endif // !defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) && !defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+
+}
+
+// --------------------------------------------------------------
+
+int digitalReadEnhanced(uint8_t pin){
+
+ return digitalRead(pin);
+
+}
+
+// --------------------------------------------------------------
+
+int analogReadEnhanced(uint8_t pin){
+
+ #ifdef OPTION_EXTERNAL_ANALOG_REFERENCE
+ analogReference(EXTERNAL);
+ #endif //OPTION_EXTERNAL_ANALOG_REFERENCE
+ return analogRead(pin);
+
+}
+
+// --------------------------------------------------------------
+
+
+void analogWriteEnhanced(uint8_t pin, int writevalue){
+
+
+ #if !defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) && !defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+ analogWrite(pin, writevalue);
+ #else
+ if (pin < 100) {
+ analogWrite(pin, writevalue);
+ } else {
+ submit_remote_command(REMOTE_UNIT_AW_COMMAND, pin, writevalue);
+ }
+ #endif // !defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) && !defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+
+}
+
+
+// --------------------------------------------------------------
+
+#if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+void take_care_of_pending_remote_command(){
+
+ // if there's a command already sent to the remote and we're awaiting the response, service the serial buffer and the queue
+
+ unsigned long start_time = millis();
+
+ while ((remote_unit_command_submitted) && ((millis() - start_time) < 200)) {
+ #if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE)
+ check_serial();
+ #endif //defined(FEATURE_MASTER_WITH_SERIAL_SLAVE)
+ #if defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+ service_ethernet();
+ #endif //defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+ service_remote_communications_incoming_buffer();
+ }
+
+
+}
+#endif // defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+// --------------------------------------------------------------
+#ifdef FEATURE_MOON_TRACKING
+void service_moon_tracking(){
+
+ static unsigned long last_check = 0;
+ static byte moon_tracking_activated_by_activate_line = 0;
+
+ static byte moon_tracking_pin_state = 0;
+
+ if (moon_tracking_active_pin) {
+ if ((moon_tracking_active) && (!moon_tracking_pin_state)) {
+ digitalWriteEnhanced(moon_tracking_active_pin, HIGH);
+ moon_tracking_pin_state = 1;
+ }
+ if ((!moon_tracking_active) && (moon_tracking_pin_state)) {
+ digitalWriteEnhanced(moon_tracking_active_pin, LOW);
+ moon_tracking_pin_state = 0;
+ }
+ }
+
+ if (moon_tracking_activate_line) {
+ if ((!moon_tracking_active) && (!digitalReadEnhanced(moon_tracking_activate_line))) {
+ moon_tracking_active = 1;
+ moon_tracking_activated_by_activate_line = 1;
+ }
+ if ((moon_tracking_active) && (digitalReadEnhanced(moon_tracking_activate_line)) && (moon_tracking_activated_by_activate_line)) {
+ moon_tracking_active = 0;
+ moon_tracking_activated_by_activate_line = 0;
+ }
+ }
+
+ if ((moon_tracking_active) && ((millis() - last_check) > MOON_TRACKING_CHECK_INTERVAL)) {
+
+ update_time();
+ update_moon_position();
+
+ #ifdef DEBUG_MOON_TRACKING
+ control_port->print(F("service_moon_tracking: AZ: "));
+ control_port->print(moon_azimuth);
+ control_port->print(" EL: ");
+ control_port->print(moon_elevation);
+ control_port->print(" lat: ");
+ control_port->print(latitude);
+ control_port->print(" long: ");
+ control_port->println(longitude);
+ #endif // DEBUG_MOON_TRACKING
+
+ if ((moon_azimuth >= MOON_AOS_AZIMUTH_MIN) && (moon_azimuth <= MOON_AOS_AZIMUTH_MAX) && (moon_elevation >= MOON_AOS_ELEVATION_MIN) && (moon_elevation <= MOON_AOS_ELEVATION_MAX)) {
+ submit_request(AZ, REQUEST_AZIMUTH, moon_azimuth * HEADING_MULTIPLIER, 11);
+ submit_request(EL, REQUEST_ELEVATION, moon_elevation * HEADING_MULTIPLIER, 12);
+ if (!moon_visible) {
+ moon_visible = 1;
+ #ifdef DEBUG_MOON_TRACKING
+ control_port->println(F("service_moon_tracking: moon AOS"));
+ #endif // DEBUG_MOON_TRACKING
+ }
+ } else {
+ if (moon_visible) {
+ moon_visible = 0;
+ #ifdef DEBUG_MOON_TRACKING
+ control_port->println(F("service_moon_tracking: moon loss of AOS"));
+ #endif // DEBUG_MOON_TRACKING
+ } else {
+ #ifdef DEBUG_MOON_TRACKING
+ control_port->println(F("service_moon_tracking: moon out of AOS limits"));
+ #endif // DEBUG_MOON_TRACKING
+ }
+ }
+
+ last_check = millis();
+ }
+
+
+
+} /* service_moon_tracking */
+ #endif // FEATURE_MOON_TRACKING
+
+// --------------------------------------------------------------
+#ifdef FEATURE_SUN_TRACKING
+
+void update_sun_position(){
+
+ update_time();
+ c_time.iYear = clock_years;
+ c_time.iMonth = clock_months;
+ c_time.iDay = clock_days;
+
+ c_time.dHours = clock_hours;
+ c_time.dMinutes = clock_minutes;
+ c_time.dSeconds = clock_seconds;
+
+ c_loc.dLongitude = longitude;
+ c_loc.dLatitude = latitude;
+
+ c_sposn.dZenithAngle = 0;
+ c_sposn.dAzimuth = 0;
+
+ sunpos(c_time, c_loc, &c_sposn);
+
+ // Convert Zenith angle to elevation
+ sun_elevation = 90. - c_sposn.dZenithAngle;
+ sun_azimuth = c_sposn.dAzimuth;
+
+} /* update_sun_position */
+#endif // FEATURE_SUN_TRACKING
+
+// --------------------------------------------------------------
+#ifdef FEATURE_SUN_TRACKING
+void service_sun_tracking(){
+
+ static unsigned long last_check = 0;
+ static byte sun_tracking_pin_state = 0;
+ static byte sun_tracking_activated_by_activate_line = 0;
+
+ if (sun_tracking_active_pin) {
+ if ((sun_tracking_active) && (!sun_tracking_pin_state)) {
+ digitalWriteEnhanced(sun_tracking_active_pin, HIGH);
+ sun_tracking_pin_state = 1;
+ }
+ if ((!sun_tracking_active) && (sun_tracking_pin_state)) {
+ digitalWriteEnhanced(sun_tracking_active_pin, LOW);
+ sun_tracking_pin_state = 0;
+ }
+ }
+
+ if (sun_tracking_activate_line) {
+ if ((!sun_tracking_active) && (!digitalReadEnhanced(sun_tracking_activate_line))) {
+ sun_tracking_active = 1;
+ sun_tracking_activated_by_activate_line = 1;
+ }
+ if ((sun_tracking_active) && (digitalReadEnhanced(sun_tracking_activate_line)) && (sun_tracking_activated_by_activate_line)) {
+ sun_tracking_active = 0;
+ sun_tracking_activated_by_activate_line = 0;
+ }
+ }
+
+ if ((sun_tracking_active) && ((millis() - last_check) > SUN_TRACKING_CHECK_INTERVAL)) {
+
+ update_time();
+ update_sun_position();
+
+
+ #ifdef DEBUG_SUN_TRACKING
+ control_port->print(F("service_sun_tracking: AZ: "));
+ control_port->print(sun_azimuth);
+ control_port->print(" EL: ");
+ control_port->print(sun_elevation);
+ control_port->print(" lat: ");
+ control_port->print(latitude);
+ control_port->print(" long: ");
+ control_port->println(longitude);
+ #endif // DEBUG_SUN_TRACKING
+
+ if ((sun_azimuth >= SUN_AOS_AZIMUTH_MIN) && (sun_azimuth <= SUN_AOS_AZIMUTH_MAX) && (sun_elevation >= SUN_AOS_ELEVATION_MIN) && (sun_elevation <= SUN_AOS_ELEVATION_MAX)) {
+ submit_request(AZ, REQUEST_AZIMUTH, sun_azimuth * HEADING_MULTIPLIER, 13);
+ submit_request(EL, REQUEST_ELEVATION, sun_elevation * HEADING_MULTIPLIER, 14);
+ if (!sun_visible) {
+ sun_visible = 1;
+ #ifdef DEBUG_SUN_TRACKING
+ control_port->println(F("service_sun_tracking: sun AOS"));
+ #endif // DEBUG_SUN_TRACKING
+ }
+ } else {
+ if (sun_visible) {
+ sun_visible = 0;
+ #ifdef DEBUG_SUN_TRACKING
+ control_port->println(F("service_sun_tracking: sun loss of AOS"));
+ #endif // DEBUG_SUN_TRACKING
+ } else {
+ #ifdef DEBUG_SUN_TRACKING
+ control_port->println(F("service_sun_tracking: sun out of AOS limits"));
+ #endif // DEBUG_SUN_TRACKING
+ }
+ }
+
+ last_check = millis();
+ }
+
+
+
+
+} /* service_sun_tracking */
+#endif // FEATURE_SUN_TRACKING
+// --------------------------------------------------------------
+
+#ifdef FEATURE_CLOCK
+void update_time(){
+ unsigned long runtime = millis() - millis_at_last_calibration;
+
+ unsigned long time = (3600L * clock_hour_set) + (60L * clock_min_set) + clock_sec_set + ((runtime + (runtime * INTERNAL_CLOCK_CORRECTION)) / 1000.0);
+
+ clock_years = clock_year_set;
+ clock_months = clock_month_set;
+ clock_days = time / 86400L;
+ time -= clock_days * 86400L;
+ clock_days += clock_day_set;
+ clock_hours = time / 3600L;
+
+ switch (clock_months) {
+
+ case 1:
+ case 3:
+ case 5:
+ case 7:
+ case 8:
+ case 10:
+ case 12:
+ if (clock_days > 31) {
+ clock_days = 1; clock_months++;
+ }
+ break;
+
+ case 2:
+ if ((float(clock_years) / 4.0) == 0.0) { // do we have a leap year?
+ if (clock_days > 29) {
+ clock_days = 1; clock_months++;
+ }
+ } else {
+ if (clock_days > 28) {
+ clock_days = 1; clock_months++;
+ }
+ }
+ break;
+
+ case 4:
+ case 6:
+ case 9:
+ case 11:
+ if (clock_days > 30) {
+ clock_days = 1; clock_months++;
+ }
+ break;
+ } /* switch */
+
+ if (clock_months > 12) {
+ clock_months = 1; clock_years++;
+ }
+
+ time -= clock_hours * 3600L;
+ clock_minutes = time / 60L;
+ time -= clock_minutes * 60L;
+ clock_seconds = time;
+} /* update_time */
+ #endif // FEATURE_CLOCK
+
+
+// --------------------------------------------------------------
+#ifdef FEATURE_GPS
+void service_gps(){
+
+ long gps_lat, gps_lon;
+ unsigned long fix_age;
+ int gps_year;
+ byte gps_month, gps_day, gps_hours, gps_minutes, gps_seconds, gps_hundredths;
+ byte gps_sync_pin_active = 0;
+ #ifdef DEBUG_GPS
+ char tempstring[10] = "";
+ #endif //#ifdef DEBUG_GPS
+
+ static unsigned long last_sync = 0;
+
+ if (gps_data_available) {
+ // retrieves +/- lat/long in 100000ths of a degree
+ gps.get_position(&gps_lat, &gps_lon, &fix_age);
+ gps.crack_datetime(&gps_year, &gps_month, &gps_day, &gps_hours, &gps_minutes, &gps_seconds, &gps_hundredths, &fix_age);
+ #ifdef DEBUG_GPS
+ #ifdef DEBUG_GPS_SERIAL
+ debug_println("");
+ #endif //DEBUG_GPS_SERIAL
+ debug_print("service_gps: fix_age:");
+ debug_print_int(fix_age);
+ debug_print(" lat:");
+ debug_print_float(gps_lat,4);
+ debug_print(" long:");
+ debug_print_float(gps_lon,4);
+ debug_print(" ");
+ debug_print_int(gps_year);
+ debug_print("-");
+ debug_print_int(gps_month);
+ debug_print("-");
+ debug_print_int(gps_day);
+ debug_print(" ");
+ debug_print_int(gps_hours);
+ debug_print(":");
+ debug_print_int(gps_minutes);
+ debug_println("");
+ #endif // DEBUG_GPS
+
+ if (fix_age < GPS_VALID_FIX_AGE_MS) {
+
+ if (SYNC_TIME_WITH_GPS) {
+ clock_year_set = gps_year;
+ clock_month_set = gps_month;
+ clock_day_set = gps_day;
+ clock_hour_set = gps_hours;
+ clock_min_set = gps_minutes;
+ clock_sec_set = gps_seconds;
+ millis_at_last_calibration = millis() - GPS_UPDATE_LATENCY_COMPENSATION_MS;
+ update_time();
+ #ifdef DEBUG_GPS
+ #ifdef DEBUG_GPS_SERIAL
+ debug_println("");
+ #endif //DEBUG_GPS_SERIAL
+ debug_print("service_gps: clock sync:");
+ sprintf(tempstring,"%s",clock_string());
+ debug_print(tempstring);
+ debug_println("");
+ #endif // DEBUG_GPS
+ }
+
+ #if defined(OPTION_SYNC_RTC_TO_GPS) && defined(FEATURE_RTC_DS1307)
+ static unsigned long last_rtc_gps_sync_time;
+ if ((millis() - last_rtc_gps_sync_time) >= (SYNC_RTC_TO_GPS_SECONDS * 1000)) {
+ rtc.adjust(DateTime(gps_year, gps_month, gps_day, gps_hours, gps_minutes, gps_seconds));
+ #ifdef DEBUG_RTC
+ debug_println("service_gps: synced RTC");
+ #endif // DEBUG_RTC
+ last_rtc_gps_sync_time = millis();
+ }
+ #endif // defined(OPTION_SYNC_RTC_TO_GPS) && defined(FEATURE_RTC_DS1307)
+
+ #if defined(OPTION_SYNC_RTC_TO_GPS) && defined(FEATURE_RTC_PCF8583)
+ static unsigned long last_rtc_gps_sync_time;
+ if ((millis() - last_rtc_gps_sync_time) >= (SYNC_RTC_TO_GPS_SECONDS * 1000)) {
+ rtc.year = gps_year;
+ rtc.month = gps_month;
+ rtc.day = gps_day;
+ rtc.hour = gps_hours;
+ rtc.minute = gps_minutes;
+ rtc.second = gps_seconds;
+ rtc.set_time();
+ #ifdef DEBUG_RTC
+ debug_println("service_gps: synced RTC");
+ #endif // DEBUG_RTC
+ last_rtc_gps_sync_time = millis();
+ }
+ #endif // defined(OPTION_SYNC_RTC_TO_GPS) && defined(FEATURE_RTC_PCF8583)
+
+
+ #if defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)
+ if (SYNC_COORDINATES_WITH_GPS) {
+ latitude = float(gps_lat) / 1000000.0;
+ longitude = float(gps_lon) / 1000000.0;
+ #ifdef DEBUG_GPS
+ debug_print("service_gps: coord sync:");
+ debug_print_float(latitude,2);
+ debug_print(" ");
+ debug_print_float(longitude,2);
+ debug_println("");
+ #endif // DEBUG_GPS
+ }
+ #endif // defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)
+
+ last_sync = millis();
+ }
+
+ gps_data_available = 0;
+ }
+
+ if ((millis() > (GPS_SYNC_PERIOD_SECONDS * 1000)) && ((millis() - last_sync) < (GPS_SYNC_PERIOD_SECONDS * 1000)) && (SYNC_TIME_WITH_GPS)) {
+ clock_status = GPS_SYNC;
+ if ((!gps_sync_pin_active) && (gps_sync)){
+ digitalWriteEnhanced(gps_sync,HIGH);
+ gps_sync_pin_active = 1;
+ }
+ } else {
+ if (clock_status == GPS_SYNC) {
+ clock_status = FREE_RUNNING;
+ if (gps_sync_pin_active){
+ digitalWriteEnhanced(gps_sync,LOW);
+ gps_sync_pin_active = 0;
+ }
+ }
+ }
+
+
+} /* service_gps */
+ #endif // FEATURE_GPS
+// --------------------------------------------------------------
+#ifdef FEATURE_MOON_TRACKING
+
+void update_moon_position(){
+
+ update_time();
+
+ double RA, Dec, topRA, topDec, LST, HA, dist;
+ update_time();
+ moon2(clock_years, clock_months, clock_days, (clock_hours + (clock_minutes / 60.0) + (clock_seconds / 3600.0)), longitude, latitude, &RA, &Dec, &topRA, &topDec, &LST, &HA, &moon_azimuth, &moon_elevation, &dist);
+
+
+}
+#endif // FEATURE_SUN_TRACKING
+// --------------------------------------------------------------
+#if defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)
+byte calibrate_az_el(float new_az, float new_el){
+
+ #ifdef DEBUG_OFFSET
+ control_port->print("calibrate_az_el: new_az:");
+ control_port->print(new_az, 2);
+ control_port->print(" new_el:");
+ control_port->println(new_el, 2);
+ #endif // DEBUG_OFFSET
+
+
+
+ if ((new_az >= 0 ) && (new_az <= 360) && (new_el >= 0) && (new_el <= 90)) {
+ configuration.azimuth_offset = 0;
+ configuration.elevation_offset = 0;
+ read_azimuth(1);
+ read_elevation(1);
+
+ #ifdef DEBUG_OFFSET
+ control_port->print("calibrate_az_el: az:");
+ control_port->print(azimuth / LCD_HEADING_MULTIPLIER, 2);
+ control_port->print(" el:");
+ control_port->println(elevation / LCD_HEADING_MULTIPLIER, 2);
+ #endif // DEBUG_OFFSET
+
+
+ configuration.azimuth_offset = new_az - (float(azimuth) / float(HEADING_MULTIPLIER));
+ #if defined(FEATURE_ELEVATION_CONTROL)
+ configuration.elevation_offset = new_el - (float(elevation) / float(HEADING_MULTIPLIER));
+ #endif
+ configuration_dirty = 1;
+ return 1;
+ } else {
+ return 0;
+ }
+
+} /* calibrate_az_el */
+ #endif // defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)
+// --------------------------------------------------------------
+
+#ifdef FEATURE_RTC
+void service_rtc(){
+
+ static unsigned long last_rtc_sync_time = 0;
+
+ if (((millis() - last_rtc_sync_time) >= (SYNC_WITH_RTC_SECONDS * 1000)) || (clock_status == FREE_RUNNING)){
+ last_rtc_sync_time = millis();
+ #ifdef FEATURE_GPS
+ if (clock_status == GPS_SYNC) { // if we're also equipped with GPS and we're synced to it, don't sync to realtime clock
+ #ifdef DEBUG_RTC
+ debug_println("service_rtc: synced to GPS already. Exiting.");
+ #endif // DEBUG_RTC
+ return;
+ }
+ #endif // FEATURE_GPS
+
+
+ #ifdef FEATURE_RTC_DS1307
+ if (rtc.isrunning()) {
+ DateTime now = rtc.now();
+ #ifdef DEBUG_RTC
+ debug_print("service_rtc: syncing: ");
+ debug_print_int(now.year());
+ debug_print("/");
+ debug_print_int(now.month());
+ debug_print("/");
+ debug_print_int(now.day());
+ debug_print(" ");
+ debug_print_int(now.hour());
+ debug_print(":");
+ debug_print_int(now.minute());
+ debug_print(":");
+ debug_print_int(now.second());
+ debug_println("");
+ #endif // DEBUG_RTC
+ clock_year_set = now.year();
+ clock_month_set = now.month();
+ clock_day_set = now.day();
+ clock_hour_set = now.hour();
+ clock_min_set = now.minute();
+ clock_sec_set = now.second();
+ millis_at_last_calibration = millis();
+ update_time();
+ clock_status = RTC_SYNC;
+ } else {
+ clock_status = FREE_RUNNING;
+ #ifdef DEBUG_RTC
+ debug_println("service_rtc: error: RTC not running");
+ #endif // DEBUG_RTC
+ }
+ #endif //#FEATURE_RTC_DS1307
+
+
+
+ #ifdef FEATURE_RTC_PCF8583
+ rtc.get_time();
+ if ((rtc.year > 2000) && (rtc.month > 0) && (rtc.month < 13)){ // do we have a halfway reasonable date?
+ #ifdef DEBUG_RTC
+ control_port->print("service_rtc: syncing: ");
+ control_port->print(rtc.year, DEC);
+ control_port->print('/');
+ control_port->print(rtc.month, DEC);
+ control_port->print('/');
+ control_port->print(rtc.day, DEC);
+ control_port->print(' ');
+ control_port->print(rtc.hour, DEC);
+ control_port->print(':');
+ control_port->print(rtc.minute, DEC);
+ control_port->print(':');
+ control_port->println(rtc.second, DEC);
+ #endif // DEBUG_RTC
+ clock_year_set = rtc.year;
+ clock_month_set = rtc.month;
+ clock_day_set = rtc.day;
+ clock_hour_set = rtc.hour;
+ clock_min_set = rtc.minute;
+ clock_sec_set = rtc.second;
+ millis_at_last_calibration = millis();
+ update_time();
+ clock_status = RTC_SYNC;
+ } else {
+ clock_status = FREE_RUNNING;
+ #ifdef DEBUG_RTC
+ control_port->print("service_rtc: error: RTC not returning valid date or time: ");
+ control_port->print(rtc.year, DEC);
+ control_port->print('/');
+ control_port->print(rtc.month, DEC);
+ control_port->print('/');
+ control_port->print(rtc.day, DEC);
+ control_port->print(' ');
+ control_port->print(rtc.hour, DEC);
+ control_port->print(':');
+ control_port->print(rtc.minute, DEC);
+ control_port->print(':');
+ control_port->println(rtc.second, DEC);
+ #endif // DEBUG_RTC
+ }
+ #endif //#FEATURE_RTC_PCF8583
+
+
+
+ }
+} /* service_rtc */
+#endif // FEATURE_RTC
+
+// -------------------------------------------------------------
+
+byte process_backslash_command(byte input_buffer[], int input_buffer_index, byte source_port, char * return_string){
+
+ strcpy(return_string,"");
+ static unsigned long serial_led_time = 0;
+ float tempfloat = 0;
+
+ #if !defined(FEATURE_AZ_POSITION_ROTARY_ENCODER) && !defined(FEATURE_AZ_POSITION_PULSE_INPUT)
+ long place_multiplier = 0;
+ byte decimalplace = 0;
+ #endif
+
+ #ifdef FEATURE_CLOCK
+ int temp_year = 0;
+ byte temp_month = 0;
+ byte temp_day = 0;
+ byte temp_minute = 0;
+ byte temp_hour = 0;
+ #endif // FEATURE_CLOCK
+
+ #if defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)
+ char grid[10] = "";
+ byte hit_error = 0;
+ #endif // defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)
+
+ #if defined(FEATURE_AZ_POSITION_ROTARY_ENCODER) || defined(FEATURE_AZ_POSITION_PULSE_INPUT)
+ int new_azimuth = 9999;
+ #endif
+ #ifdef FEATURE_ELEVATION_CONTROL
+ #if defined(FEATURE_EL_POSITION_ROTARY_ENCODER) || defined(FEATURE_EL_POSITION_PULSE_INPUT)
+ int new_elevation = 9999;
+ #endif // FEATURE_ELEVATION_CONTROL
+ #endif // defined(FEATURE_AZ_POSITION_ROTARY_ENCODER) || defined(FEATURE_AZ_POSITION_PULSE_INPUT)
+
+ char temp_string[20] = "";
+
+ switch (input_buffer[1]) {
+
+ #if defined(FEATURE_AZ_POSITION_ROTARY_ENCODER) || defined(FEATURE_AZ_POSITION_PULSE_INPUT)
+ case 'A': // \Ax[x][x] - manually set azimuth
+ new_azimuth = 9999;
+ switch (input_buffer_index) {
+ case 3:
+ new_azimuth = (input_buffer[2] - 48);
+ break;
+ case 4:
+ new_azimuth = ((input_buffer[2] - 48) * 10) + (input_buffer[3] - 48);
+ break;
+ case 5:
+ new_azimuth = ((input_buffer[2] - 48) * 100) + ((input_buffer[3] - 48) * 10) + (input_buffer[4] - 48);
+ break;
+ }
+ if ((new_azimuth >= 0) && (new_azimuth < 360)) {
+ azimuth = new_azimuth * HEADING_MULTIPLIER;
+ configuration.last_azimuth = new_azimuth;
+ raw_azimuth = new_azimuth * HEADING_MULTIPLIER;
+ configuration_dirty = 1;
+ strcpy(return_string, "Azimuth set to ");
+ dtostrf(new_azimuth, 0, 0, temp_string);
+ strcat(return_string, temp_string);
+ } else {
+ strcpy(return_string, "Error. Format: \\Ax[x][x] ");
+ }
+ break;
+ #else // defined(FEATURE_AZ_POSITION_ROTARY_ENCODER) || defined(FEATURE_AZ_POSITION_PULSE_INPUT)
+ case 'A': // \Ax[xxx][.][xxxx] - manually set azimuth
+ place_multiplier = 1;
+ for (int x = input_buffer_index - 1; x > 1; x--) {
+ if (char(input_buffer[x]) != '.') {
+ tempfloat += (input_buffer[x] - 48) * place_multiplier;
+ place_multiplier = place_multiplier * 10;
+ } else {
+ decimalplace = x;
+ }
+ }
+ if (decimalplace) {
+ tempfloat = tempfloat / pow(10, (input_buffer_index - decimalplace - 1));
+ }
+ if ((tempfloat >= 0) && (tempfloat <= 360)) {
+ configuration.azimuth_offset = 0;
+ read_azimuth(1);
+ configuration.azimuth_offset = tempfloat - float(azimuth / HEADING_MULTIPLIER);
+ configuration_dirty = 1;
+ strcpy(return_string, "Azimuth calibrated to ");
+ dtostrf(tempfloat, 0, 2, temp_string);
+ strcat(return_string, temp_string);
+ } else {
+ strcpy(return_string, "Error.");
+ }
+
+ break;
+ #endif // defined(FEATURE_AZ_POSITION_ROTARY_ENCODER) || defined(FEATURE_AZ_POSITION_PULSE_INPUT)
+
+
+ #if defined(FEATURE_ELEVATION_CONTROL)
+ #if defined(FEATURE_EL_POSITION_ROTARY_ENCODER) || defined(FEATURE_EL_POSITION_PULSE_INPUT)
+ case 'B': // \Ax[x][x] - manually set elevation
+ new_elevation = 9999;
+ switch (input_buffer_index) {
+ case 3:
+ new_elevation = (input_buffer[2] - 48);
+ break;
+ case 4:
+ new_elevation = ((input_buffer[2] - 48) * 10) + (input_buffer[3] - 48);
+ break;
+ case 5:
+ new_elevation = ((input_buffer[2] - 48) * 100) + ((input_buffer[3] - 48) * 10) + (input_buffer[4] - 48);
+ break;
+ }
+ if ((new_elevation >= 0) && (new_elevation <= 180)) {
+ elevation = new_elevation * HEADING_MULTIPLIER;
+ configuration.last_elevation = new_elevation;
+ configuration_dirty = 1;
+ strcpy(return_string, "Elevation set to ");
+ dtostrf(new_elevation, 0, 0, temp_string);
+ strcat(return_string, temp_string);
+ } else {
+ strcpy(return_string, "Error. Format: \\Bx[x][x]");
+ }
+ break;
+ #else // defined(FEATURE_EL_POSITION_ROTARY_ENCODER) || defined(FEATURE_EL_POSITION_PULSE_INPUT)
+ case 'B': // \Bx[xxx][.][xxxx] - manually set elevation
+ place_multiplier = 1;
+ for (int x = input_buffer_index - 1; x > 1; x--) {
+ if (char(input_buffer[x]) != '.') {
+ tempfloat += (input_buffer[x] - 48) * place_multiplier;
+ place_multiplier = place_multiplier * 10;
+ } else {
+ decimalplace = x;
+ }
+ }
+ if (decimalplace) {
+ tempfloat = tempfloat / pow(10, (input_buffer_index - decimalplace - 1));
+ }
+ if ((tempfloat >= 0) && (tempfloat <= 180)) {
+ configuration.elevation_offset = 0;
+ read_elevation(1);
+ configuration.elevation_offset = tempfloat - float(elevation / HEADING_MULTIPLIER);
+ configuration_dirty = 1;
+ strcpy(return_string, "Elevation calibrated to ");
+ dtostrf(tempfloat, 0, 2, temp_string);
+ strcat(return_string, temp_string);
+ } else {
+ strcpy(return_string, "Error.");
+ }
+ break;
+ #endif // defined(FEATURE_EL_POSITION_ROTARY_ENCODER) || defined(FEATURE_EL_POSITION_PULSE_INPUT)
+ #endif //FEATURE_ELEVATION_CONTROL
+
+ #ifdef FEATURE_CLOCK
+ case 'C': // show clock
+ update_time();
+ sprintf(return_string, "%s", clock_string());
+
+
+ break;
+ case 'O': // set clock
+ temp_year = ((input_buffer[2] - 48) * 1000) + ((input_buffer[3] - 48) * 100) + ((input_buffer[4] - 48) * 10) + (input_buffer[5] - 48);
+ temp_month = ((input_buffer[6] - 48) * 10) + (input_buffer[7] - 48);
+ temp_day = ((input_buffer[8] - 48) * 10) + (input_buffer[9] - 48);
+ temp_hour = ((input_buffer[10] - 48) * 10) + (input_buffer[11] - 48);
+ temp_minute = ((input_buffer[12] - 48) * 10) + (input_buffer[13] - 48);
+ if ((temp_year > 2013) && (temp_year < 2070) &&
+ (temp_month > 0) && (temp_month < 13) &&
+ (temp_day > 0) && (temp_day < 32) &&
+ (temp_hour >= 0) && (temp_hour < 24) &&
+ (temp_minute >= 0) && (temp_minute < 60) &&
+ (input_buffer_index == 14)) {
+
+ clock_year_set = temp_year;
+ clock_month_set = temp_month;
+ clock_day_set = temp_day;
+ clock_hour_set = temp_hour;
+ clock_min_set = temp_minute;
+ clock_sec_set = 0;
+ millis_at_last_calibration = millis();
+
+
+
+
+
+ #if defined(FEATURE_RTC_DS1307)
+ rtc.adjust(DateTime(temp_year, temp_month, temp_day, temp_hour, temp_minute, 0));
+ #endif // defined(FEATURE_RTC_DS1307)
+ #if defined(FEATURE_RTC_PCF8583)
+ rtc.year = temp_year;
+ rtc.month = temp_month;
+ rtc.day = temp_day;
+ rtc.hour = temp_hour;
+ rtc.minute = temp_minute;
+ rtc.second = 0;
+ rtc.set_time();
+ #endif // defined(FEATURE_RTC_PCF8583)
+
+ #if (!defined(FEATURE_RTC_DS1307) && !defined(FEATURE_RTC_PCF8583))
+ strcpy(return_string, "Clock set to ");
+ update_time();
+ strcat(return_string, clock_string());
+ #else
+ strcpy(return_string, "Internal clock and RTC set to ");
+ update_time();
+ strcat(return_string, clock_string());
+ #endif
+
+
+ } else {
+ strcpy(return_string, "Error. Usage: \\CYYYYMMDDHHmm");
+ }
+ break;
+ #endif // FEATURE_CLOCK
+
+
+ case 'D':
+ if (debug_mode & source_port) {
+ debug_mode = debug_mode & (~source_port);
+ } else {
+ debug_mode = debug_mode | source_port;
+ }
+ break; // D - Debug
+
+ case 'E': // E - Initialize eeprom
+ initialize_eeprom_with_defaults();
+ strcpy(return_string, "Initialized eeprom, please reset...");
+ break;
+
+ case 'L': // L - rotate to long path
+ if (azimuth < (180 * HEADING_MULTIPLIER)) {
+ submit_request(AZ, REQUEST_AZIMUTH, (azimuth + (180 * HEADING_MULTIPLIER)), 15);
+ } else {
+ submit_request(AZ, REQUEST_AZIMUTH, (azimuth - (180 * HEADING_MULTIPLIER)), 16);
+ }
+ break;
+
+ #if defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)
+ case 'G': // G - set coordinates using grid square
+ if (isalpha(input_buffer[2])) {
+ grid[0] = input_buffer[2];
+ } else { hit_error = 1; }
+ if (isalpha(input_buffer[3])) {
+ grid[1] = input_buffer[3];
+ } else { hit_error = 1; }
+ if (isdigit(input_buffer[4])) {
+ grid[2] = input_buffer[4];
+ } else { hit_error = 1; }
+ if (isdigit(input_buffer[5])) {
+ grid[3] = input_buffer[5];
+ } else { hit_error = 1; }
+ if (isalpha(input_buffer[6])) {
+ grid[4] = input_buffer[6];
+ } else { hit_error = 1; }
+ if (isalpha(input_buffer[7])) {
+ grid[5] = input_buffer[7];
+ } else { hit_error = 1; }
+ if ((input_buffer_index != 8) || (hit_error)) {
+ strcpy(return_string, "Error. Usage \\Gxxxxxx");
+ } else {
+ grid2deg(grid, &longitude, &latitude);
+ strcpy(return_string, "Coordinates set to: ");
+ dtostrf(latitude, 0, 4, temp_string);
+ strcat(return_string, temp_string);
+ strcat(return_string, " ");
+ dtostrf(longitude, 0, 4, temp_string);
+ strcat(return_string, temp_string);
+ }
+ break;
+ #endif // defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)
+
+ #ifdef FEATURE_MOON_TRACKING
+ case 'M':
+ switch (input_buffer[2]) {
+ case '0':
+ submit_request(AZ, REQUEST_STOP, 0, 17);
+ submit_request(EL, REQUEST_STOP, 0, 18);
+ strcpy(return_string, "Moon tracking deactivated.");
+ break;
+ case '1':
+ moon_tracking_active = 1;
+ #ifdef FEATURE_SUN_TRACKING
+ sun_tracking_active = 0;
+ #endif // FEATURE_SUN_TRACKING
+ strcpy(return_string, "Moon tracking activated.");
+ break;
+ default: strcpy(return_string, "Error."); break;
+ }
+ break;
+ #endif // FEATURE_MOON_TRACKING
+
+ #if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+ case 'R':
+ strcpy(return_string, "Remote port rx sniff o");
+ if (remote_port_rx_sniff) {
+ remote_port_rx_sniff = 0;
+ strcat(return_string, "ff");
+ } else {
+ remote_port_rx_sniff = 1;
+ strcat(return_string, "n");
+ }
+ break;
+ case 'S':
+ #if defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+ ethernetslavelinkclient0.print(ETHERNET_PREAMBLE);
+ #endif
+ for (int x = 2; x < input_buffer_index; x++) {
+ #if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE)
+ remote_unit_port->write(input_buffer[x]);
+ #endif
+ #if defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+ ethernetslavelinkclient0.write(input_buffer[x]);
+ #endif
+ if (remote_port_tx_sniff) {
+ control_port->write(input_buffer[x]);
+ }
+ }
+ #if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE)
+ remote_unit_port->write(13);
+ #endif
+ #if defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+ ethernetslavelinkclient0.write(13);
+ #endif
+ if (remote_port_tx_sniff) {
+ control_port->write(13);
+ }
+ break;
+ case 'T':
+ strcpy(return_string, "Remote port tx sniff o");
+ if (remote_port_tx_sniff) {
+ remote_port_tx_sniff = 0;
+ strcat(return_string, "ff");
+ } else {
+ remote_port_tx_sniff = 1;
+ strcat(return_string, "n");
+ }
+ break;
+ case 'Z':
+ strcpy(return_string, "Suspend auto remote commands o");
+ if (suspend_remote_commands) {
+ suspend_remote_commands = 0;
+ strcat(return_string, "ff");
+ } else {
+ suspend_remote_commands = 1;
+ strcat(return_string, "n");
+ }
+ break;
+ #endif // defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)
+
+ #ifdef FEATURE_SUN_TRACKING
+ case 'U': // activate / deactivate sun tracking
+ switch (input_buffer[2]) {
+ case '0':
+ submit_request(AZ, REQUEST_STOP, 0, 19);
+ submit_request(EL, REQUEST_STOP, 0, 20);
+ strcpy(return_string, "Sun tracking deactivated.");
+ break;
+ case '1':
+ sun_tracking_active = 1;
+ strcpy(return_string, "Sun tracking activated.");
+ #ifdef FEATURE_MOON_TRACKING
+ moon_tracking_active = 0;
+ #endif // FEATURE_MOON_TRACKING
+ break;
+ default: strcpy(return_string, "Error."); break;
+ }
+ break;
+
+ #endif // FEATURE_SUN_TRACKING
+
+ #if defined(FEATURE_SUN_TRACKING) || defined(FEATURE_MOON_TRACKING)
+ case 'X':
+ switch (toupper(input_buffer[2])) {
+ #if defined(FEATURE_SUN_TRACKING)
+ case 'S':
+ update_sun_position();
+ if (calibrate_az_el(sun_azimuth, sun_elevation)) {
+ strcpy(return_string, az_el_calibrated_string());
+ } else {
+ strcpy(return_string, "Error.");
+ }
+ break;
+ #endif // FEATURE_SUN_TRACKING
+ #if defined(FEATURE_MOON_TRACKING)
+ case 'M':
+ update_moon_position();
+ if (calibrate_az_el(moon_azimuth, moon_elevation)) {
+ strcpy(return_string, az_el_calibrated_string());
+ } else {
+ strcpy(return_string, "Error.");
+ }
+ break;
+ #endif // FEATURE_MOON_TRACKING
+ case '0':
+ configuration.azimuth_offset = 0;
+ configuration.elevation_offset = 0;
+ configuration_dirty = 1;
+ break;
+ default: strcpy(return_string, "?>"); break;
+
+
+ } /* switch */
+ break;
+ #endif // defined(FEATURE_SUN_TRACKING) || defined(FEATURE_MOON_TRACKING)
+
+ #ifdef FEATURE_PARK
+ case 'P': // Park
+ strcpy(return_string, "Parking...");
+ initiate_park();
+ park_serial_initiated = 1;
+ break;
+ #endif // FEATURE_PARK
+
+ #ifdef FEATURE_ANCILLARY_PIN_CONTROL
+ case 'N': // \Nxx - turn pin on; xx = pin number
+ if ((((input_buffer[2] > 47) && (input_buffer[2] < 58)) || (toupper(input_buffer[2]) == 'A')) && (input_buffer[3] > 47) && (input_buffer[3] < 58) && (input_buffer_index == 4)) {
+ byte pin_value = 0;
+ if (toupper(input_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(input_buffer[3] - 48);
+ } else {
+ pin_value = ((input_buffer[2] - 48) * 10) + (input_buffer[3] - 48);
+ }
+ pinModeEnhanced(pin_value, OUTPUT);
+ digitalWriteEnhanced(pin_value, HIGH);
+ strcpy(return_string, "OK");
+ } else {
+ strcpy(return_string, "Error");
+ }
+ break;
+ case 'F': // \Fxx - turn pin off; xx = pin number
+ if ((((input_buffer[2] > 47) && (input_buffer[2] < 58)) || (toupper(input_buffer[2]) == 'A')) && (input_buffer[3] > 47) && (input_buffer[3] < 58) && (input_buffer_index == 4)) {
+ byte pin_value = 0;
+ if (toupper(input_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(input_buffer[3] - 48);
+ } else {
+ pin_value = ((input_buffer[2] - 48) * 10) + (input_buffer[3] - 48);
+ }
+ pinModeEnhanced(pin_value, OUTPUT);
+ digitalWriteEnhanced(pin_value, LOW);
+ strcpy(return_string, "OK");
+ } else {
+ strcpy(return_string, "Error");
+ }
+ break;
+ case 'W': // \Wxxyyy - turn on pin PWM; xx = pin number, yyy = PWM value (0-255)
+ if (((input_buffer[2] > 47) && (input_buffer[2] < 58)) && (input_buffer[3] > 47) && (input_buffer[3] < 58) && (input_buffer_index == 7)) {
+ byte pin_value = 0;
+ if (toupper(input_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(input_buffer[3] - 48);
+ } else {
+ pin_value = ((input_buffer[2] - 48) * 10) + (input_buffer[3] - 48);
+ }
+ int write_value = ((input_buffer[4] - 48) * 100) + ((input_buffer[5] - 48) * 10) + (input_buffer[6] - 48);
+ if ((write_value >= 0) && (write_value < 256)) {
+ pinModeEnhanced(pin_value, OUTPUT);
+ analogWriteEnhanced(pin_value, write_value);
+ strcpy(return_string, "OK");
+ } else {
+ strcpy(return_string, "Error");
+ }
+ } else {
+ strcpy(return_string, "Error");
+ }
+ break;
+ #endif // FEATURE_ANCILLARY_PIN_CONTROL
+
+
+ default: strcpy(return_string, "Error.");
+
+
+
+ } /* switch */
+} /* process_backslash_command */
+
+
+// --------------------------------------------------------------
+#ifdef FEATURE_CLOCK
+char * clock_string(){
+
+ char return_string[32] = "";
+ char temp_string[16] = "";
+
+
+
+ dtostrf(clock_years, 0, 0, temp_string);
+ strcpy(return_string, temp_string);
+ strcat(return_string, "-");
+ if (clock_months < 10) {
+ strcat(return_string, "0");
+ }
+ dtostrf(clock_months, 0, 0, temp_string);
+ strcat(return_string, temp_string);
+ strcat(return_string, "-");
+ if (clock_days < 10) {
+ strcat(return_string, "0");
+ }
+ dtostrf(clock_days, 0, 0, temp_string);
+ strcat(return_string, temp_string);
+ strcat(return_string, " ");
+
+ if (clock_hours < 10) {
+ strcat(return_string, "0");
+ }
+ dtostrf(clock_hours, 0, 0, temp_string);
+ strcat(return_string, temp_string);
+ strcat(return_string, ":");
+ if (clock_minutes < 10) {
+ strcat(return_string, "0");
+ }
+ dtostrf(clock_minutes, 0, 0, temp_string);
+ strcat(return_string, temp_string);
+ strcat(return_string, ":");
+ if (clock_seconds < 10) {
+ strcat(return_string, "0");
+ }
+ dtostrf(clock_seconds, 0, 0, temp_string);
+ strcat(return_string, temp_string);
+ strcat(return_string,"Z");
+ return return_string;
+
+} /* clock_string */
+#endif // FEATURE_CLOCK
+
+
+// --------------------------------------------------------------
+#if defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)
+char * az_el_calibrated_string(){
+
+ char return_string[48] = "";
+ char tempstring[16] = "";
+
+ read_azimuth(1);
+ read_elevation(1);
+ strcpy(return_string, "Heading calibrated. Az: ");
+ dtostrf((azimuth / LCD_HEADING_MULTIPLIER), 0, LCD_DECIMAL_PLACES, tempstring);
+ strcat(return_string, tempstring);
+ #ifdef FEATURE_ELEVATION_CONTROL
+ strcat(return_string, " El: ");
+ dtostrf((elevation / LCD_HEADING_MULTIPLIER), 0, LCD_DECIMAL_PLACES, tempstring);
+ strcat(return_string, tempstring);
+ #endif //FEATURE_ELEVATION_CONTROL
+ return return_string;
+
+}
+#endif // defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)
+// --------------------------------------------------------------
+void debug_print(char * print_string){
+
+ if (debug_mode & CONTROL_PORT0){
+ control_port->print(print_string);
+ }
+
+ #ifdef FEATURE_ETHERNET
+ if (debug_mode & ETHERNET_PORT0){
+ ethernetclient0.print(print_string);
+ }
+ #endif //FEATURE_ETHERNET
+
+ #if defined(FEATURE_ETHERNET) && defined(ETHERNET_TCP_PORT_1)
+ if (debug_mode & ETHERNET_PORT1){
+ ethernetclient1.print(print_string);
+ }
+ #endif //defined(FEATURE_ETHERNET) && defined(ETHERNET_TCP_PORT_1)
+
+}
+// --------------------------------------------------------------
+void debug_println(char * print_string){
+
+ if (debug_mode & CONTROL_PORT0){
+ control_port->println(print_string);
+ }
+
+ #ifdef FEATURE_ETHERNET
+ if (debug_mode & ETHERNET_PORT0){
+ ethernetclient0.println(print_string);
+ }
+ #endif //FEATURE_ETHERNET
+
+ #if defined(FEATURE_ETHERNET) && defined(ETHERNET_TCP_PORT_1)
+ if (debug_mode & ETHERNET_PORT1){
+ ethernetclient1.println(print_string);
+ }
+ #endif //defined(FEATURE_ETHERNET) && defined(ETHERNET_TCP_PORT_1)
+
+}
+// --------------------------------------------------------------
+void debug_print_char(char print_char){
+
+ if (debug_mode & CONTROL_PORT0){
+ control_port->print(print_char);
+ }
+
+ #ifdef FEATURE_ETHERNET
+ if (debug_mode & ETHERNET_PORT0){
+ ethernetclient0.print(print_char);
+ }
+ #endif //FEATURE_ETHERNET
+
+ #if defined(FEATURE_ETHERNET) && defined(ETHERNET_TCP_PORT_1)
+ if (debug_mode & ETHERNET_PORT1){
+ ethernetclient1.print(print_char);
+ }
+ #endif //defined(FEATURE_ETHERNET) && defined(ETHERNET_TCP_PORT_1)
+}
+// --------------------------------------------------------------
+void debug_write(char * print_string){
+
+ if (debug_mode & CONTROL_PORT0){
+ control_port->write(print_string);
+ }
+
+ #ifdef FEATURE_ETHERNET
+ if (debug_mode & ETHERNET_PORT0){
+ ethernetclient0.write(print_string);
+ }
+ #endif //FEATURE_ETHERNET
+
+ #if defined(FEATURE_ETHERNET) && defined(ETHERNET_TCP_PORT_1)
+ if (debug_mode & ETHERNET_PORT1){
+ ethernetclient1.write(print_string);
+ }
+ #endif //defined(FEATURE_ETHERNET) && defined(ETHERNET_TCP_PORT_1)
+
+}
+// --------------------------------------------------------------
+void debug_print_int(int print_int){
+
+ if (debug_mode & CONTROL_PORT0){
+ control_port->print(print_int);
+ }
+
+ #ifdef FEATURE_ETHERNET
+ if (debug_mode & ETHERNET_PORT0){
+ ethernetclient0.print(print_int);
+ }
+ #endif //FEATURE_ETHERNET
+
+ #if defined(FEATURE_ETHERNET) && defined(ETHERNET_TCP_PORT_1)
+ if (debug_mode & ETHERNET_PORT1){
+ ethernetclient1.print(print_int);
+ }
+ #endif //defined(FEATURE_ETHERNET) && defined(ETHERNET_TCP_PORT_1)
+
+
+}
+// --------------------------------------------------------------
+void debug_write_int(int write_int){
+
+ if (debug_mode & CONTROL_PORT0){
+ control_port->write(write_int);
+ }
+
+ #ifdef FEATURE_ETHERNET
+ if (debug_mode & ETHERNET_PORT0){
+ ethernetclient0.write(write_int);
+ }
+ #endif //FEATURE_ETHERNET
+
+ #if defined(FEATURE_ETHERNET) && defined(ETHERNET_TCP_PORT_1)
+ if (debug_mode & ETHERNET_PORT1){
+ ethernetclient1.write(write_int);
+ }
+ #endif //defined(FEATURE_ETHERNET) && defined(ETHERNET_TCP_PORT_1)
+
+}
+// --------------------------------------------------------------
+void debug_print_float(float print_float,byte places){
+
+ char tempstring[16] = "";
+
+ dtostrf(print_float,0,places,tempstring);
+
+ if (debug_mode & CONTROL_PORT0){
+ control_port->print(tempstring);
+ }
+
+ #ifdef FEATURE_ETHERNET
+ if (debug_mode & ETHERNET_PORT0){
+ ethernetclient0.print(tempstring);
+ }
+ #endif //FEATURE_ETHERNET
+
+ #if defined(FEATURE_ETHERNET) && defined(ETHERNET_TCP_PORT_1)
+ if (debug_mode & ETHERNET_PORT1){
+ ethernetclient1.print(tempstring);
+ }
+ #endif //defined(FEATURE_ETHERNET) && defined(ETHERNET_TCP_PORT_1)
+
+}
+// --------------------------------------------------------------
+#ifdef FEATURE_MOON_TRACKING
+char * moon_status_string(){
+
+ char returnstring[128] = "";
+ char tempstring[16] = "";
+
+ strcpy(returnstring,"\tmoon: AZ: ");
+ dtostrf(moon_azimuth,0,2,tempstring);
+ strcat(returnstring,tempstring);
+ strcat(returnstring," EL: ");
+ dtostrf(moon_elevation,0,2,tempstring);
+ strcat(returnstring,tempstring);
+ strcat(returnstring,"\tTRACKING_");
+ if (!moon_tracking_active) {
+ strcat(returnstring,"IN");
+ }
+ strcat(returnstring,"ACTIVE ");
+ if (moon_tracking_active) {
+ if (!moon_visible) {
+ strcat(returnstring,"NOT_");
+ }
+ strcat(returnstring,"VISIBLE");
+ }
+ return returnstring;
+}
+#endif // FEATURE_MOON_TRACKING
+// --------------------------------------------------------------
+#ifdef FEATURE_SUN_TRACKING
+char * sun_status_string(){
+
+ char returnstring[128] = "";
+ char tempstring[16] = "";
+
+ strcpy(returnstring,"\tsun: AZ: ");
+ dtostrf(sun_azimuth,0,2,tempstring);
+ strcat(returnstring,tempstring);
+ strcat(returnstring," EL: ");
+ dtostrf(sun_elevation,0,2,tempstring);
+ strcat(returnstring,tempstring);
+ strcat(returnstring,"\tTRACKING_");
+ if (!sun_tracking_active) {
+ strcat(returnstring,"IN");
+ }
+ strcat(returnstring,"ACTIVE ");
+ if (sun_tracking_active) {
+ if (!sun_visible) {
+ strcat(returnstring,"NOT_");
+ }
+ strcat(returnstring,"VISIBLE");
+ }
+ return returnstring;
+}
+#endif // FEATURE_SUN_TRACKING
+// --------------------------------------------------------------
+#ifdef FEATURE_CLOCK
+char * clock_status_string(){
+
+ switch (clock_status) {
+ case FREE_RUNNING: return("FREE_RUNNING"); break;
+ case GPS_SYNC: return("GPS_SYNC"); break;
+ case RTC_SYNC: return("RTC_SYNC"); break;
+ case SLAVE_SYNC: return("SLAVE_SYNC"); break;
+ }
+}
+#endif //FEATURE_CLOCK
+// --------------------------------------------------------------
+#if defined(FEATURE_SUN_TRACKING) || defined(FEATURE_MOON_TRACKING)
+char * coordinate_string(){
+
+ char returnstring[32] = "";
+ char tempstring[12] = "";
+
+ dtostrf(latitude,0,4,returnstring);
+ strcat(returnstring," ");
+ dtostrf(longitude,0,4,tempstring);
+ strcat(returnstring,tempstring);
+ return returnstring;
+
+}
+#endif //defined(FEATURE_SUN_TRACKING) || defined(FEATURE_MOON_TRACKING)
+
+
+
+
+
+
+
+
+
+
+// --------------------------------------------------------------
+#ifdef FEATURE_YAESU_EMULATION
+void process_yaesu_command(byte * yaesu_command_buffer, int yaesu_command_buffer_index, byte source_port, char * return_string){
+
+
+
+ char tempstring[11] = "";
+ int parsed_value = 0;
+
+ int parsed_elevation = 0;
+
+
+ #ifdef FEATURE_TIMED_BUFFER
+ int parsed_value2 = 0;
+ #endif //FEATURE_TIMED_BUFFER
+
+ strcpy(return_string,"");
+
+ switch (yaesu_command_buffer[0]) { // look at the first character of the command
+ case 'C': // C - return current azimuth
+ #ifdef DEBUG_PROCESS_YAESU
+ if (debug_mode) {
+ debug_print("yaesu_serial_command: C\n");
+ }
+ #endif // DEBUG_PROCESS_YAESU
+ #ifdef OPTION_DELAY_C_CMD_OUTPUT
+ delay(400);
+ #endif
+ //strcpy(return_string,"");
+ #ifndef OPTION_GS_232B_EMULATION
+ strcat(return_string,"+0");
+ #else
+ strcat(return_string,"AZ=");
+ #endif
+ dtostrf(int(azimuth / HEADING_MULTIPLIER),0,0,tempstring);
+ if (int(azimuth / HEADING_MULTIPLIER) < 10) {
+ strcat(return_string,"0");
+ }
+ if (int(azimuth / HEADING_MULTIPLIER) < 100) {
+ strcat(return_string,"0");
+ }
+ strcat(return_string,tempstring);
+
+ #ifdef FEATURE_ELEVATION_CONTROL
+ #ifndef OPTION_C_COMMAND_SENDS_AZ_AND_EL
+ if ((yaesu_command_buffer[1] == '2') && (yaesu_command_buffer_index > 1)) { // did we get the C2 command?
+ #endif
+
+
+ #ifndef OPTION_GS_232B_EMULATION
+ if (elevation < 0) {
+ strcat(return_string,"-0");
+ } else {
+ strcat(return_string,"+0");
+ }
+ #endif
+ #ifdef OPTION_GS_232B_EMULATION
+ strcat(return_string,"EL=");
+ #endif
+ dtostrf(int(elevation / HEADING_MULTIPLIER),0,0,tempstring);
+ if (int(elevation / HEADING_MULTIPLIER) < 10) {
+ strcat(return_string,("0"));
+ }
+ if (int(elevation / HEADING_MULTIPLIER) < 100) {
+ strcat(return_string,"0");
+ }
+ strcat(return_string,tempstring);
+
+ #ifndef OPTION_C_COMMAND_SENDS_AZ_AND_EL
+ } else {
+ //strcat(return_string,"\n");
+ }
+ #endif // OPTION_C_COMMAND_SENDS_AZ_AND_EL
+ #endif // FEATURE_ELEVATION_CONTROL
+
+ #ifndef FEATURE_ELEVATION_CONTROL
+ if ((yaesu_command_buffer[1] == '2') && (yaesu_command_buffer_index > 1)) { // did we get the C2 command?
+ #ifndef OPTION_GS_232B_EMULATION
+ strcat(return_string,"+0000"); // return a dummy elevation since we don't have the elevation feature turned on
+ #else
+ strcat(return_string,"EL=000");
+ #endif
+ } else {
+ //strcat(return_string,"\n");
+ }
+ #endif // FEATURE_ELEVATION_CONTROL
+ break;
+
+
+ //-----------------end of C command-----------------
+
+ #ifdef FEATURE_AZ_POSITION_POTENTIOMETER
+ case 'F': // F - full scale calibration
+ #ifdef DEBUG_PROCESS_YAESU
+ if (debug_mode) {
+ debug_print("yaesu_serial_command: F\n");
+ }
+ #endif // DEBUG_PROCESS_YAESU
+
+
+ #ifdef FEATURE_ELEVATION_CONTROL
+ if ((yaesu_command_buffer[1] == '2') && (yaesu_command_buffer_index > 1)) { // did we get the F2 command?
+
+ clear_serial_buffer();
+ if (source_port == CONTROL_PORT0){
+ control_port->println(F("Elevate to 180 (or max elevation) and send keystroke..."));
+ }
+ get_keystroke();
+ read_elevation(1);
+ configuration.analog_el_max_elevation = analog_el;
+ write_settings_to_eeprom();
+ strcpy(return_string,"Wrote to memory");
+ return;
+ }
+ #endif
+
+ clear_serial_buffer();
+ if (source_port == CONTROL_PORT0){
+ control_port->println(F("Rotate to full CW and send keystroke..."));
+ get_keystroke();
+ }
+ read_azimuth(1);
+ configuration.analog_az_full_cw = analog_az;
+ write_settings_to_eeprom();
+ strcpy(return_string,"Wrote to memory");
+ break;
+ #endif // FEATURE_AZ_POSITION_POTENTIOMETER
+ case 'H': print_help(source_port); break; // H - print help - depricated
+ case 'L': // L - manual left (CCW) rotation
+ #ifdef DEBUG_PROCESS_YAESU
+ if (debug_mode) {
+ debug_print("yaesu_serial_command: L\n");
+ }
+ #endif // DEBUG_PROCESS_YAESU
+ submit_request(AZ, REQUEST_CCW, 0, 21);
+ //strcpy(return_string,"\n");
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+ break;
+
+ #ifdef FEATURE_AZ_POSITION_POTENTIOMETER
+ case 'O': // O - offset calibration
+ #ifdef DEBUG_PROCESS_YAESU
+ if (debug_mode) {
+ debug_print("yaesu_serial_command: O\n");
+ }
+ #endif // DEBUG_PROCESS_YAESU
+
+ #ifdef FEATURE_ELEVATION_CONTROL
+ if ((yaesu_command_buffer[1] == '2') && (yaesu_command_buffer_index > 1)) { // did we get the O2 command?
+ clear_serial_buffer();
+ if (source_port == CONTROL_PORT0){
+ control_port->println(F("Elevate to 0 degrees and send keystroke..."));
+ }
+ get_keystroke();
+ read_elevation(1);
+ configuration.analog_el_0_degrees = analog_el;
+ write_settings_to_eeprom();
+ strcpy(return_string,"Wrote to memory");
+ return;
+ }
+ #endif
+
+ clear_serial_buffer();
+ if (source_port == CONTROL_PORT0){
+ control_port->println(F("Rotate to full CCW and send keystroke..."));
+ }
+ get_keystroke();
+ read_azimuth(1);
+ configuration.analog_az_full_ccw = analog_az;
+ write_settings_to_eeprom();
+ strcpy(return_string,"Wrote to memory");
+ break;
+ #endif // FEATURE_AZ_POSITION_POTENTIOMETER
+
+ case 'R': // R - manual right (CW) rotation
+ #ifdef DEBUG_PROCESS_YAESU
+ if (debug_mode) {
+ debug_print("yaesu_serial_command: R\n");
+ }
+ #endif // DEBUG_PROCESS_YAESU
+ submit_request(AZ, REQUEST_CW, 0, 22);
+ strcpy(return_string,"\n");
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+ break;
+
+ case 'A': // A - CW/CCW rotation stop
+ #ifdef DEBUG_PROCESS_YAESU
+ if (debug_mode) {
+ debug_print("yaesu_serial_command: A\n");
+ }
+ #endif // DEBUG_PROCESS_YAESU
+ submit_request(AZ, REQUEST_STOP, 0, 23);
+ //strcpy(return_string,"\n");
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+ break;
+
+ case 'S': // S - all stop
+ #ifdef DEBUG_PROCESS_YAESU
+ if (debug_mode) {
+ debug_print("yaesu_serial_command: S\n");
+ }
+ #endif // DEBUG_PROCESS_YAESU
+ submit_request(AZ, REQUEST_STOP, 0, 24);
+ #ifdef FEATURE_ELEVATION_CONTROL
+ submit_request(EL, REQUEST_STOP, 0, 25);
+ #endif
+ #ifdef FEATURE_TIMED_BUFFER
+ clear_timed_buffer();
+ #endif // FEATURE_TIMED_BUFFER
+ //strcpy(return_string,"");
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+ break;
+
+ case 'M': // M - auto azimuth rotation
+ #ifdef DEBUG_PROCESS_YAESU
+ if (debug_mode) {
+ debug_print("yaesu_serial_command: M\n");
+ }
+ #endif // DEBUG_PROCESS_YAESU
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+
+ if (yaesu_command_buffer_index > 4) { // if there are more than 4 characters in the command buffer, we got a timed interval command
+ #ifdef FEATURE_TIMED_BUFFER
+ clear_timed_buffer();
+ parsed_value = ((int(yaesu_command_buffer[1]) - 48) * 100) + ((int(yaesu_command_buffer[2]) - 48) * 10) + (int(yaesu_command_buffer[3]) - 48);
+ if ((parsed_value > 0) && (parsed_value < 1000)) {
+ timed_buffer_interval_value_seconds = parsed_value;
+ for (int x = 5; x < yaesu_command_buffer_index; x = x + 4) {
+ parsed_value = ((int(yaesu_command_buffer[x]) - 48) * 100) + ((int(yaesu_command_buffer[x + 1]) - 48) * 10) + (int(yaesu_command_buffer[x + 2]) - 48);
+ if ((parsed_value >= 0) && (parsed_value <= 360)) { // is it a valid azimuth?
+ timed_buffer_azimuths[timed_buffer_number_entries_loaded] = parsed_value * HEADING_MULTIPLIER;
+ timed_buffer_number_entries_loaded++;
+ timed_buffer_status = LOADED_AZIMUTHS;
+ if (timed_buffer_number_entries_loaded > TIMED_INTERVAL_ARRAY_SIZE) { // is the array full?
+ submit_request(AZ, REQUEST_AZIMUTH, timed_buffer_azimuths[0], 26); // array is full, go to the first azimuth
+ timed_buffer_entry_pointer = 1;
+ return;
+ }
+ } else { // we hit an invalid bearing
+ timed_buffer_status = EMPTY;
+ timed_buffer_number_entries_loaded = 0;
+ strcpy(return_string,"?>"); // error
+ return;
+ }
+ }
+ submit_request(AZ, REQUEST_AZIMUTH, timed_buffer_azimuths[0], 27); // go to the first azimuth
+ timed_buffer_entry_pointer = 1;
+ } else {
+ strcpy(return_string,"?>"); // error
+ }
+ #else
+ strcpy(return_string,"?>");
+ #endif // FEATURE_TIMED_BUFFER
+ return;
+ } else { // if there are four characters, this is just a single direction setting
+ if (yaesu_command_buffer_index == 4) {
+ parsed_value = ((int(yaesu_command_buffer[1]) - 48) * 100) + ((int(yaesu_command_buffer[2]) - 48) * 10) + (int(yaesu_command_buffer[3]) - 48);
+ #ifdef FEATURE_TIMED_BUFFER
+ clear_timed_buffer();
+ #endif // FEATURE_TIMED_BUFFER
+ if ((parsed_value >= 0) && (parsed_value <= (azimuth_starting_point + azimuth_rotation_capability))) {
+ submit_request(AZ, REQUEST_AZIMUTH, (parsed_value * HEADING_MULTIPLIER), 28);
+ return;
+ }
+ }
+ }
+ strcpy(return_string,"?>");
+ break;
+
+ #ifdef FEATURE_TIMED_BUFFER
+ case 'N': // N - number of loaded timed interval entries
+ #ifdef DEBUG_PROCESS_YAESU
+ if (debug_mode) {
+ debug_print("yaesu_serial_command: N\n");
+ }
+ #endif // DEBUG_PROCESS_YAESU
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+ sprintf(return_string,"%d",timed_buffer_number_entries_loaded);
+ break;
+ #endif // FEATURE_TIMED_BUFFER
+
+ #ifdef FEATURE_TIMED_BUFFER
+ case 'T': // T - initiate timed tracking
+ initiate_timed_buffer(source_port);
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+ break;
+ #endif // FEATURE_TIMED_BUFFER
+
+ case 'X': // X - azimuth speed change
+ #ifdef DEBUG_PROCESS_YAESU
+ if (debug_mode) {
+ debug_print("yaesu_serial_command: X\n");
+ }
+ #endif // DEBUG_PROCESS_YAESU
+
+
+ if (yaesu_command_buffer_index > 1) {
+ switch (yaesu_command_buffer[1]) {
+ case '4':
+ normal_az_speed_voltage = PWM_SPEED_VOLTAGE_X4;
+ update_az_variable_outputs(PWM_SPEED_VOLTAGE_X4);
+ #if defined(FEATURE_ELEVATION_CONTROL) && defined(OPTION_EL_SPEED_FOLLOWS_AZ_SPEED)
+ normal_el_speed_voltage = PWM_SPEED_VOLTAGE_X4;
+ update_el_variable_outputs(PWM_SPEED_VOLTAGE_X4);
+ #endif
+ strcpy(return_string,"Speed X4");
+ break;
+ case '3':
+ normal_az_speed_voltage = PWM_SPEED_VOLTAGE_X3;
+ update_az_variable_outputs(PWM_SPEED_VOLTAGE_X3);
+ #if defined(FEATURE_ELEVATION_CONTROL) && defined(OPTION_EL_SPEED_FOLLOWS_AZ_SPEED)
+ normal_el_speed_voltage = PWM_SPEED_VOLTAGE_X3;
+ update_el_variable_outputs(PWM_SPEED_VOLTAGE_X3);
+ #endif
+ strcpy(return_string,"Speed X3");
+ break;
+ case '2':
+ normal_az_speed_voltage = PWM_SPEED_VOLTAGE_X2;
+ update_az_variable_outputs(PWM_SPEED_VOLTAGE_X2);
+ #if defined(FEATURE_ELEVATION_CONTROL) && defined(OPTION_EL_SPEED_FOLLOWS_AZ_SPEED)
+ normal_el_speed_voltage = PWM_SPEED_VOLTAGE_X2;
+ update_el_variable_outputs(PWM_SPEED_VOLTAGE_X2);
+ #endif
+ strcpy(return_string,"Speed X2");
+ break;
+ case '1':
+ normal_az_speed_voltage = PWM_SPEED_VOLTAGE_X1;
+ update_az_variable_outputs(PWM_SPEED_VOLTAGE_X1);
+ #if defined(FEATURE_ELEVATION_CONTROL) && defined(OPTION_EL_SPEED_FOLLOWS_AZ_SPEED)
+ normal_el_speed_voltage = PWM_SPEED_VOLTAGE_X1;
+ update_el_variable_outputs(PWM_SPEED_VOLTAGE_X1);
+ #endif
+ strcpy(return_string,"Speed X1");
+ break;
+ default: strcpy(return_string,"?>"); break;
+ } /* switch */
+ } else {
+ strcpy(return_string,"?>");
+ }
+ break;
+
+ #ifdef FEATURE_ELEVATION_CONTROL
+ case 'U': // U - manual up rotation
+ #ifdef DEBUG_PROCESS_YAESU
+ if (debug_mode) {
+ debug_print("yaesu_serial_command: U\n");
+ }
+ #endif // DEBUG_PROCESS_YAESU
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+ submit_request(EL, REQUEST_UP, 0, 29);
+ //strcpy(return_string,"\n");
+ break;
+
+ case 'D': // D - manual down rotation
+ #ifdef DEBUG_PROCESS_YAESU
+ if (debug_mode) {
+ debug_print("yaesu_serial_command: D\n");
+ }
+ #endif // DEBUG_PROCESS_YAESU
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+ submit_request(EL, REQUEST_DOWN, 0, 30);
+ //strcpy(return_string,"\n");
+ break;
+
+ case 'E': // E - stop elevation rotation
+ #ifdef DEBUG_PROCESS_YAESU
+ if (debug_mode) {
+ debug_print("yaesu_serial_command: E\n");
+ }
+ #endif // DEBUG_PROCESS_YAESU
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+ submit_request(EL, REQUEST_STOP, 0, 31);
+ //strcpy(return_string,"\n");
+ break;
+
+ case 'B': // B - return current elevation
+ #ifndef OPTION_GS_232B_EMULATION
+ if (elevation < 0) {
+ strcat(return_string,"-0");
+ } else {
+ strcat(return_string,"+0");
+ }
+ #else
+ strcat(return_string,"EL=");
+ #endif //OPTION_GS_232B_EMULATION
+ dtostrf(int(elevation / HEADING_MULTIPLIER),0,0,tempstring);
+ if (int(elevation / HEADING_MULTIPLIER) < 10) {
+ strcat(return_string,("0"));
+ }
+ if (int(elevation / HEADING_MULTIPLIER) < 100) {
+ strcat(return_string,"0");
+ }
+ strcat(return_string,tempstring);
+ break;
+
+ #endif /* ifdef FEATURE_ELEVATION_CONTROL */
+
+ case 'W': // W - auto elevation rotation
+ #ifdef DEBUG_PROCESS_YAESU
+ if (debug_mode) {
+ debug_print("yaesu_serial_command: W\n");
+ }
+ #endif // DEBUG_PROCESS_YAESU
+ #ifdef FEATURE_PARK
+ deactivate_park();
+ #endif // FEATURE_PARK
+
+
+ // parse out W command
+ // Short Format: WXXX YYYY XXX = azimuth YYY = elevation
+ // Long Format : WSSS XXX YYY SSS = timed interval XXX = azimuth YYY = elevation
+
+ if (yaesu_command_buffer_index > 8) { // if there are more than 4 characters in the command buffer, we got a timed interval command
+ #if defined(FEATURE_TIMED_BUFFER) && defined(FEATURE_ELEVATION_CONTROL)
+ parsed_value = ((int(yaesu_command_buffer[1]) - 48) * 100) + ((int(yaesu_command_buffer[2]) - 48) * 10) + (int(yaesu_command_buffer[3]) - 48);
+ if ((parsed_value > 0) && (parsed_value < 1000)) {
+ timed_buffer_interval_value_seconds = parsed_value;
+ for (int x = 5; x < yaesu_command_buffer_index; x = x + 8) {
+ parsed_value = ((int(yaesu_command_buffer[x]) - 48) * 100) + ((int(yaesu_command_buffer[x + 1]) - 48) * 10) + (int(yaesu_command_buffer[x + 2]) - 48);
+ parsed_value2 = ((int(yaesu_command_buffer[x + 4]) - 48) * 100) + ((int(yaesu_command_buffer[x + 5]) - 48) * 10) + (int(yaesu_command_buffer[x + 6]) - 48);
+ if ((parsed_value > -1) && (parsed_value < 361) && (parsed_value2 > -1) && (parsed_value2 < 181)) { // is it a valid azimuth?
+ timed_buffer_azimuths[timed_buffer_number_entries_loaded] = (parsed_value * HEADING_MULTIPLIER);
+ timed_buffer_elevations[timed_buffer_number_entries_loaded] = (parsed_value2 * HEADING_MULTIPLIER);
+ timed_buffer_number_entries_loaded++;
+ timed_buffer_status = LOADED_AZIMUTHS_ELEVATIONS;
+ if (timed_buffer_number_entries_loaded > TIMED_INTERVAL_ARRAY_SIZE) { // is the array full?
+ x = yaesu_command_buffer_index; // array is full, go to the first azimuth and elevation
+
+ }
+ } else { // we hit an invalid bearing
+ timed_buffer_status = EMPTY;
+ timed_buffer_number_entries_loaded = 0;
+ strcpy(return_string,"?>"); // error
+ return;
+ }
+ }
+ }
+ timed_buffer_entry_pointer = 1; // go to the first bearings
+ parsed_value = timed_buffer_azimuths[0];
+ parsed_elevation = timed_buffer_elevations[0];
+ #else /* ifdef FEATURE_TIMED_BUFFER FEATURE_ELEVATION_CONTROL*/
+ strcpy(return_string,"?>");
+ #endif // FEATURE_TIMED_BUFFER FEATURE_ELEVATION_CONTROL
+ } else {
+ // this is a short form W command, just parse the azimuth and elevation and initiate rotation
+ parsed_value = (((int(yaesu_command_buffer[1]) - 48) * 100) + ((int(yaesu_command_buffer[2]) - 48) * 10) + (int(yaesu_command_buffer[3]) - 48)) * HEADING_MULTIPLIER;
+ parsed_elevation = (((int(yaesu_command_buffer[5]) - 48) * 100) + ((int(yaesu_command_buffer[6]) - 48) * 10) + (int(yaesu_command_buffer[7]) - 48)) * HEADING_MULTIPLIER;
+ }
+
+ #ifndef FEATURE_ELEVATION_CONTROL
+ if ((parsed_value >= 0) && (parsed_value <= (360 * HEADING_MULTIPLIER))) {
+ submit_request(AZ, REQUEST_AZIMUTH, parsed_value, 32);
+ } else {
+ #ifdef DEBUG_PROCESS_YAESU
+ if (debug_mode) {
+ debug_print("process_yaesu_command: W cmd az error");
+ }
+ #endif // DEBUG_PROCESS_YAESU
+ strcpy(return_string,"?>"); // bogus elevation - return and error and don't do anything
+ }
+
+ #else
+ if ((parsed_value >= 0) && (parsed_value <= (360 * HEADING_MULTIPLIER)) && (parsed_elevation >= 0) && (parsed_elevation <= (180 * HEADING_MULTIPLIER))) {
+ submit_request(AZ, REQUEST_AZIMUTH, parsed_value, 33);
+ submit_request(EL, REQUEST_ELEVATION, parsed_elevation, 34);
+ } else {
+ #ifdef DEBUG_PROCESS_YAESU
+ if (debug_mode) {
+ debug_print("process_yaesu_command: W cmd az/el error");
+ }
+ #endif // DEBUG_PROCESS_YAESU
+ strcpy(return_string,"?>"); // bogus elevation - return and error and don't do anything
+ }
+ #endif // FEATURE_ELEVATION_CONTROL
+
+
+ break;
+
+ #ifdef OPTION_GS_232B_EMULATION
+ case 'P': // P - switch between 360 and 450 degree mode
+
+ if ((yaesu_command_buffer[1] == '3') && (yaesu_command_buffer_index > 2)) { // P36 command
+ azimuth_rotation_capability = 360;
+ strcpy(return_string,"Mode 360 degree");
+ // write_settings_to_eeprom();
+ } else {
+ if ((yaesu_command_buffer[1] == '4') && (yaesu_command_buffer_index > 2)) { // P45 command
+ azimuth_rotation_capability = 450;
+ strcpy(return_string,"Mode 450 degree");
+ // write_settings_to_eeprom();
+ } else {
+ strcpy(return_string,"?>");
+ }
+ }
+
+
+ break;
+ case 'Z': // Z - Starting point toggle
+ if (azimuth_starting_point == 180) {
+ azimuth_starting_point = 0;
+ strcpy(return_string,"N");
+ } else {
+ azimuth_starting_point = 180;
+ strcpy(return_string,"S");
+ }
+ strcat(return_string," Center");
+ // write_settings_to_eeprom();
+ break;
+ #endif
+
+ default:
+ strcpy(return_string,"?>");
+ #ifdef DEBUG_PROCESS_YAESU
+ if (debug_mode) {
+ debug_print("process_yaesu_command: yaesu_command_buffer_index: ");
+ debug_print_int(yaesu_command_buffer_index);
+ for (int debug_x = 0; debug_x < yaesu_command_buffer_index; debug_x++) {
+ debug_print("process_yaesu_command: yaesu_command_buffer[");
+ debug_print_int(debug_x);
+ debug_print("]: ");
+ debug_print_int(yaesu_command_buffer[debug_x]);
+ debug_print(" ");
+ debug_write_int(yaesu_command_buffer[debug_x]);
+ debug_print("\n");;
+ }
+ }
+ #endif // DEBUG_PROCESS_YAESU
+ } /* switch */
+
+} /* yaesu_serial_command */
+ #endif // FEATURE_YAESU_EMULATION
+// --------------------------------------------------------------
+#ifdef FEATURE_ETHERNET
+void service_ethernet(){
+
+
+ byte incoming_byte = 0;
+ static unsigned long last_incoming_byte_receive_time = 0;
+ char return_string[100] = "";
+ static byte ethernet_port_buffer0[COMMAND_BUFFER_SIZE];
+ static int ethernet_port_buffer_index0 = 0;
+ static byte first_connect_occurred = 0;
+ static long last_received_byte0 = 0;
+
+ #ifdef FEATURE_REMOTE_UNIT_SLAVE
+ static byte preamble_received = 0;
+ #endif //FEATURE_REMOTE_UNIT_SLAVE
+
+ /* this is the server side (receiving bytes from a client such as a master unit receiving commands from a computer
+ or a slave receiving commands from a master unit
+
+ */
+
+
+ // clear things out if we received a partial message and it's been awhile
+ if ((ethernet_port_buffer_index0) && ((millis()-last_received_byte0) > ETHERNET_MESSAGE_TIMEOUT_MS)){
+ ethernet_port_buffer_index0 = 0;
+ #ifdef FEATURE_REMOTE_UNIT_SLAVE
+ preamble_received = 0;
+ #endif //FEATURE_REMOTE_UNIT_SLAVE
+ }
+
+
+ if (ethernetserver0.available()){
+ ethernetclient0 = ethernetserver0.available();
+
+ last_received_byte0 = millis();
+
+ if (!first_connect_occurred){ // clean out the cruft that's alway spit out on first connect
+ while(ethernetclient0.available()){ethernetclient0.read();}
+ first_connect_occurred = 1;
+ return;
+ }
+
+ if (ethernetclient0.available() > 0){ // the client has sent something
+ incoming_byte = ethernetclient0.read();
+ last_incoming_byte_receive_time = millis();
+
+ #ifdef DEBUG_ETHERNET
+ debug_print("service_ethernet: client:") ;
+ debug_print(" char:");
+ debug_print_char((char) incoming_byte);
+ debug_print("\n");
+ #endif //DEBUG_ETHERNET
+
+ if ((incoming_byte > 96) && (incoming_byte < 123)) { // uppercase it
+ incoming_byte = incoming_byte - 32;
+ }
+
+ char ethernet_preamble[] = ETHERNET_PREAMBLE;
+
+ #ifdef FEATURE_REMOTE_UNIT_SLAVE
+ if (preamble_received < 254){ // the master/slave ethernet link has each message prefixed with a preamble
+ if (ethernet_preamble[preamble_received] == 0){
+ preamble_received = 254;
+ } else {
+ if (incoming_byte == ethernet_preamble[preamble_received]){
+ preamble_received++;
+ } else {
+ preamble_received = 0;
+ }
+ }
+ }
+ // add it to the buffer if it's not a line feed or carriage return and we've received the preamble
+ if ((incoming_byte != 10) && (incoming_byte != 13) && (preamble_received == 254)) {
+ ethernet_port_buffer0[ethernet_port_buffer_index0] = incoming_byte;
+ ethernet_port_buffer_index0++;
+ }
+ #else
+ if ((incoming_byte != 10) && (incoming_byte != 13)) { // add it to the buffer if it's not a line feed or carriage return
+ ethernet_port_buffer0[ethernet_port_buffer_index0] = incoming_byte;
+ ethernet_port_buffer_index0++;
+ }
+ #endif //FEATURE_REMOTE_UNIT_SLAVE
+
+
+ if (((incoming_byte == 13) || (ethernet_port_buffer_index0 >= COMMAND_BUFFER_SIZE)) && (ethernet_port_buffer_index0 > 0)){ // do we have a carriage return?
+ if ((ethernet_port_buffer0[0] == '\\') or (ethernet_port_buffer0[0] == '/')) {
+ process_backslash_command(ethernet_port_buffer0, ethernet_port_buffer_index0, ETHERNET_PORT0, return_string);
+ } else {
+ #ifdef FEATURE_YAESU_EMULATION
+ process_yaesu_command(ethernet_port_buffer0,ethernet_port_buffer_index0,ETHERNET_PORT0,return_string);
+ #endif //FEATURE_YAESU_EMULATION
+ #ifdef FEATURE_EASYCOM_EMULATION
+ process_easycom_command(ethernet_port_buffer0,ethernet_port_buffer_index0,ETHERNET_PORT0,return_string);
+ #endif //FEATURE_EASYCOM_EMULATION
+ #ifdef FEATURE_REMOTE_UNIT_SLAVE
+ process_remote_slave_command(ethernet_port_buffer0,ethernet_port_buffer_index0,ETHERNET_PORT0,return_string);
+ #endif //FEATURE_REMOTE_UNIT_SLAVE
+ }
+ ethernetclient0.println(return_string);
+ ethernet_port_buffer_index0 = 0;
+ #ifdef FEATURE_REMOTE_UNIT_SLAVE
+ preamble_received = 0;
+ #endif //FEATURE_REMOTE_UNIT_SLAVE
+ }
+
+ }
+ }
+
+
+ #ifdef ETHERNET_TCP_PORT_1
+ static byte ethernet_port_buffer1[COMMAND_BUFFER_SIZE];
+ static int ethernet_port_buffer_index1 = 0;
+
+ if (ethernetserver1.available()){
+
+ ethernetclient1 = ethernetserver1.available();
+
+ if (ethernetclient1.available() > 0){ // the client has sent something
+ incoming_byte = ethernetclient1.read();
+ last_incoming_byte_receive_time = millis();
+
+ #ifdef DEBUG_ETHERNET
+ debug_print("service_ethernet: client:") ;
+ debug_print(" char:");
+ debug_print_char((char) incoming_byte);
+ debug_print("\n");
+ #endif //DEBUG_ETHERNET
+
+ if ((incoming_byte > 96) && (incoming_byte < 123)) { // uppercase it
+ incoming_byte = incoming_byte - 32;
+ }
+ if ((incoming_byte != 10) && (incoming_byte != 13)) { // add it to the buffer if it's not a line feed or carriage return
+ ethernet_port_buffer1[ethernet_port_buffer_index1] = incoming_byte;
+ ethernet_port_buffer_index1++;
+ }
+ if (incoming_byte == 13) { // do we have a carriage return?
+ if ((ethernet_port_buffer1[0] == '\\') or (ethernet_port_buffer1[0] == '/')) {
+ process_backslash_command(ethernet_port_buffer1, ethernet_port_buffer_index1, ETHERNET_PORT1, return_string);
+ } else {
+ #ifdef FEATURE_YAESU_EMULATION
+ process_yaesu_command(ethernet_port_buffer1,ethernet_port_buffer_index1,ETHERNET_PORT1,return_string);
+ #endif //FEATURE_YAESU_EMULATION
+ #ifdef FEATURE_EASYCOM_EMULATION
+ process_easycom_command(ethernet_port_buffer1,ethernet_port_buffer_index1,ETHERNET_PORT1,return_string);
+ #endif //FEATURE_EASYCOM_EMULATION
+ #ifdef FEATURE_REMOTE_UNIT_SLAVE
+ process_remote_slave_command(ethernet_port_buffer1,ethernet_port_buffer_index1,ETHERNET_PORT1,return_string);
+ #endif //FEATURE_REMOTE_UNIT_SLAVE
+ }
+ ethernetclient1.println(return_string);
+ ethernet_port_buffer_index1 = 0;
+ }
+
+ }
+ }
+ #endif //ETHERNET_TCP_PORT_1
+
+ #ifdef FEATURE_MASTER_WITH_ETHERNET_SLAVE
+ static long last_connect_try = 0;
+ static long last_received_byte_time = 0;
+ byte incoming_ethernet_byte = 0;
+ static byte first_ethernet_slave_connect_occurred = 0;
+
+ // are we disconnected and is it time to reconnect?
+ if ((ethernetslavelinkclient0_state == ETHERNET_SLAVE_DISCONNECTED) && (((millis()-last_connect_try) >= ETHERNET_SLAVE_RECONNECT_TIME_MS) || (last_connect_try == 0))){
+
+ #ifdef DEBUG_ETHERNET
+ debug_println("service_ethernet: master_slave_ethernet: connecting");
+ #endif //DEBUG_ETHERNET
+
+ if (ethernetslavelinkclient0.connect(slave_unit_ip, ETHERNET_SLAVE_TCP_PORT)){
+ ethernetslavelinkclient0_state = ETHERNET_SLAVE_CONNECTED;
+ if (!first_ethernet_slave_connect_occurred){
+ first_ethernet_slave_connect_occurred = 1;
+ ethernet_slave_reconnects = 65535;
+ }
+ } else {
+ ethernetslavelinkclient0.stop();
+ #ifdef DEBUG_ETHERNET
+ debug_println("service_ethernet: master_slave_ethernet: connect failed");
+ #endif //DEBUG_ETHERNET
+ }
+
+ ethernet_slave_reconnects++;
+ last_connect_try = millis();
+ }
+
+
+ if (ethernetslavelinkclient0.available()) {
+ incoming_ethernet_byte = ethernetslavelinkclient0.read();
+
+ #ifdef DEBUG_ETHERNET
+ debug_print("service_ethernet: slave rx: ");
+ debug_print_char(incoming_ethernet_byte);
+ debug_print(" : ");
+ debug_print_int(incoming_ethernet_byte);
+ debug_println("");
+ #endif //DEBUG_ETHERNET
+
+ if (remote_port_rx_sniff) {
+ control_port->write(incoming_ethernet_byte);
+ }
+
+ if ((incoming_ethernet_byte != 10) && (remote_unit_port_buffer_index < COMMAND_BUFFER_SIZE)) {
+ remote_unit_port_buffer[remote_unit_port_buffer_index] = incoming_ethernet_byte;
+ remote_unit_port_buffer_index++;
+ if ((incoming_ethernet_byte == 13) || (remote_unit_port_buffer_index >= COMMAND_BUFFER_SIZE)) {
+ remote_unit_port_buffer_carriage_return_flag = 1;
+ #ifdef DEBUG_ETHERNET
+ debug_println("service_ethernet: remote_unit_port_buffer_carriage_return_flag");
+ #endif //DEBUG_ETHERNET
+ }
+ }
+ last_received_byte_time = millis();
+
+ }
+
+ if (((millis() - last_received_byte_time) >= ETHERNET_MESSAGE_TIMEOUT_MS) && (remote_unit_port_buffer_index > 1) && (!remote_unit_port_buffer_carriage_return_flag)){
+ remote_unit_port_buffer_index = 0;
+ #ifdef DEBUG_ETHERNET
+ debug_println("service_ethernet: master_slave_ethernet: remote_unit_incoming_buffer_timeout");
+ #endif //DEBUG_ETHERNET
+ remote_unit_incoming_buffer_timeouts++;
+ }
+
+ if ((ethernetslavelinkclient0_state == ETHERNET_SLAVE_CONNECTED) && (!ethernetslavelinkclient0.connected())){
+ ethernetslavelinkclient0.stop();
+ ethernetslavelinkclient0_state = ETHERNET_SLAVE_DISCONNECTED;
+ remote_unit_port_buffer_index = 0;
+ #ifdef DEBUG_ETHERNET
+ debug_println("service_ethernet: master_slave_ethernet: lost connection");
+ #endif //DEBUG_ETHERNET
+ }
+
+
+ #endif //FEATURE_MASTER_WITH_ETHERNET_SLAVE
+
+}
+#endif //FEATURE_ETHERNET
+// --------------------------------------------------------------
+#ifdef FEATURE_EASYCOM_EMULATION
+void process_easycom_command(byte * easycom_command_buffer, int easycom_command_buffer_index, byte source_port, char * return_string){
+
+
+ /* Easycom protocol implementation
+ *
+ * Implemented commands:
+ *
+ * Command Meaning Parameters
+ * ------- ------- ----------
+ *
+ * ML Move Left
+ * MR Move Right
+ * MU Move Up
+ * MD Move Down
+ * SA Stop azimuth moving
+ * SE Stop elevation moving
+ *
+ * VE Request Version
+ * AZ Azimuth number - 1 decimal place (activated with OPTION_EASYCOM_AZ_QUERY_COMMAND)
+ * EL Elevation number - 1 decimal place (activated with OPTION_EASYCOM_EL_QUERY_COMMAND)
+ *
+ *
+ */
+
+
+
+ char tempstring[11] = "";
+ float heading = -1;
+ strcpy(return_string,"");
+
+ switch (easycom_command_buffer[0]) { // look at the first character of the command
+ case 'A': // AZ
+ if (easycom_command_buffer[1] == 'Z') { // format is AZx.x or AZxx.x or AZxxx.x (why didn't they make it fixed length?)
+ switch (easycom_command_buffer_index) {
+ #ifdef OPTION_EASYCOM_AZ_QUERY_COMMAND
+ case 2:
+ strcpy(return_string,"AZ");
+ dtostrf((float)azimuth/(float)HEADING_MULTIPLIER,0,1,tempstring);
+ strcat(return_string,tempstring);
+ return;
+ break;
+ #endif // OPTION_EASYCOM_AZ_QUERY_COMMAND
+ case 5: // format AZx.x
+ heading = (easycom_command_buffer[2] - 48) + ((easycom_command_buffer[4] - 48) / 10.);
+ break;
+ case 6: // format AZxx.x
+ heading = ((easycom_command_buffer[2] - 48) * 10.) + (easycom_command_buffer[3] - 48) + ((easycom_command_buffer[5] - 48) / 10.);
+ break;
+ case 7: // format AZxxx.x
+ heading = ((easycom_command_buffer[2] - 48) * 100.) + ((easycom_command_buffer[3] - 48) * 10.) + (easycom_command_buffer[4] - 48.) + ((easycom_command_buffer[6] - 48) / 10.);
+ break;
+ // default: control_port->println("?"); break;
+ }
+ if (((heading >= 0) && (heading < 451)) && (easycom_command_buffer[easycom_command_buffer_index - 2] == '.')) {
+ submit_request(AZ, REQUEST_AZIMUTH, (heading * HEADING_MULTIPLIER), 36);
+ } else {
+ strcpy(return_string,"?");
+ }
+ } else {
+ strcpy(return_string,"?");
+ }
+ break;
+ #ifdef FEATURE_ELEVATION_CONTROL
+ case 'E': // EL
+ if (easycom_command_buffer[1] == 'L') {
+ switch (easycom_command_buffer_index) {
+ #ifdef OPTION_EASYCOM_EL_QUERY_COMMAND
+ case 2:
+ strcpy(return_string,"EL");
+ dtostrf((float)elevation/(float)HEADING_MULTIPLIER,0,1,tempstring);
+ strcat(return_string,tempstring);
+ return;
+ break;
+ #endif // OPTION_EASYCOM_EL_QUERY_COMMAND
+ case 5: // format ELx.x
+ heading = (easycom_command_buffer[2] - 48) + ((easycom_command_buffer[4] - 48) / 10.);
+ break;
+ case 6: // format ELxx.x
+ heading = ((easycom_command_buffer[2] - 48) * 10.) + (easycom_command_buffer[3] - 48) + ((easycom_command_buffer[5] - 48) / 10.);
+ break;
+ case 7: // format ELxxx.x
+ heading = ((easycom_command_buffer[2] - 48) * 100.) + ((easycom_command_buffer[3] - 48) * 10.) + (easycom_command_buffer[4] - 48) + ((easycom_command_buffer[6] - 48) / 10.);
+ break;
+ // default: control_port->println("?"); break;
+ }
+ if (((heading >= 0) && (heading < 181)) && (easycom_command_buffer[easycom_command_buffer_index - 2] == '.')) {
+ submit_request(EL, REQUEST_ELEVATION, (heading * HEADING_MULTIPLIER), 37);
+ } else {
+ strcpy(return_string,"?");
+ }
+ } else {
+ strcpy(return_string,"?");
+ }
+ break;
+ #endif // #FEATURE_ELEVATION_CONTROL
+ case 'S': // SA or SE - stop azimuth, stop elevation
+ switch (easycom_command_buffer[1]) {
+ case 'A':
+ submit_request(AZ, REQUEST_STOP, 0, 38);
+ break;
+ #ifdef FEATURE_ELEVATION_CONTROL
+ case 'E':
+ submit_request(EL, REQUEST_STOP, 0, 39);
+ break;
+ #endif // FEATURE_ELEVATION_CONTROL
+ default: strcpy(return_string,"?"); break;
+ }
+ break;
+ case 'M': // ML, MR, MU, MD - move left, right, up, down
+ switch (easycom_command_buffer[1]) {
+ case 'L': // ML - move left
+ submit_request(AZ, REQUEST_CCW, 0, 40);
+ break;
+ case 'R': // MR - move right
+ submit_request(AZ, REQUEST_CW, 0, 41);
+ break;
+ #ifdef FEATURE_ELEVATION_CONTROL
+ case 'U': // MU - move up
+ submit_request(EL, REQUEST_UP, 0, 42);
+ break;
+ case 'D': // MD - move down
+ submit_request(EL, REQUEST_DOWN, 0, 43);
+ break;
+ #endif // FEATURE_ELEVATION_CONTROL
+ default: strcpy(return_string,"?"); break;
+ }
+ break;
+ case 'V': // VE - version query
+ if (easycom_command_buffer[1] == 'E') {
+ strcpy(return_string,"VE002");
+ } // not sure what to send back, sending 002 because this is easycom version 2?
+ break;
+ default: strcpy(return_string,"?"); break;
+ } /* switch */
+
+
+
+} /* easycom_serial_commmand */
+#endif // FEATURE_EASYCOM_EMULATION
+
+
+
+
+
+// --------------------------------------------------------------
+
+#ifdef FEATURE_REMOTE_UNIT_SLAVE
+void process_remote_slave_command(byte * slave_command_buffer, int slave_command_buffer_index, byte source_port, char * return_string){
+
+
+/*
+ *
+ * This implements a protocol for host unit to remote unit communications
+ *
+ *
+ * Remote Slave Unit Protocol Reference
+ *
+ * PG - ping
+ * AZ - read azimuth (returns AZxxx.xxxxxx)
+ * EL - read elevation (returns ELxxx.xxxxxx)
+ * DOxx - digital pin initialize as output;
+ * DIxx - digital pin initialize as input
+ * DPxx - digital pin initialize as input with pullup
+ * DRxx - digital pin read
+ * DLxx - digital pin write low
+ * DHxx - digital pin write high
+ * DTxxyyyy - digital pin tone output
+ * NTxx - no tone
+ * ARxx - analog pin read
+ * AWxxyyy - analog pin write
+ * SWxy - serial write byte
+ * SDx - deactivate serial read event; x = port #
+ * SSxyyyyyy... - serial write string; x = port #, yyyy = string of characters to send
+ * SAx - activate serial read event; x = port #
+ * RB - reboot
+ * CL - return clock date and time
+ *
+ * Responses
+ *
+ * ER - report an error (remote to host only)
+ * EV - report an event (remote to host only)
+ * OK - report success (remote to host only)
+ * CS - report a cold start (remote to host only)
+ *
+ * Error Codes
+ *
+ * ER01 - Serial port buffer timeout
+ * ER02 - Command syntax error
+ *
+ * Events
+ *
+ * EVSxy - Serial port read event; x = serial port number, y = byte returned
+ *
+ *
+ */
+
+
+
+ byte command_good = 0;
+ strcpy(return_string,"");
+ char tempstring[25] = "";
+
+ if (slave_command_buffer_index < 2) {
+ strcpy(return_string,"ER02"); // we don't have enough characters - syntax error
+ } else {
+
+ #ifdef DEBUG_PROCESS_SLAVE
+ debug_print("serial_serial_buffer: command_string: ");
+ debug_print((char*)slave_command_buffer);
+ debug_print("$ slave_command_buffer_index: ");
+ debug_print_int(slave_command_buffer_index);
+ debug_print("\n");
+ #endif // DEBUG_PROCESS_SLAVE
+
+ if (((slave_command_buffer[0] == 'S') && (slave_command_buffer[1] == 'S')) && (slave_command_buffer[2] > 47) && (slave_command_buffer[2] < 53)) { // this is a variable length command
+ command_good = 1;
+ for (byte x = 3; x < slave_command_buffer_index; x++) {
+ switch (slave_command_buffer[2] - 48) {
+ case 0: control_port->write(slave_command_buffer[x]); break;
+ #if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE)
+ case 1: remote_unit_port->write(slave_command_buffer[x]); break;
+ #endif
+ }
+ }
+ }
+
+ if (slave_command_buffer_index == 2) {
+
+ #ifdef FEATURE_CLOCK
+ if ((slave_command_buffer[0] == 'C') && (slave_command_buffer[1] == 'L')) {
+ strcpy(return_string,"CL");
+ update_time();
+ strcat(return_string,clock_string());
+ command_good = 1;
+ }
+ #endif //FEATURE_CLOCK
+
+ if ((slave_command_buffer[0] == 'P') && (slave_command_buffer[1] == 'G')) {
+ strcpy(return_string,"PG"); command_good = 1;
+ } // PG - ping
+ if ((slave_command_buffer[0] == 'R') && (slave_command_buffer[1] == 'B')) {
+ wdt_enable(WDTO_30MS); while (1) {
+ }
+ } // RB - reboot
+ if ((slave_command_buffer[0] == 'A') && (slave_command_buffer[1] == 'Z')) {
+ strcpy(return_string,"AZ");
+ //if ((raw_azimuth/HEADING_MULTIPLIER) < 1000) {
+ // strcat(return_string,"0");
+ //}
+ if ((raw_azimuth/HEADING_MULTIPLIER) < 100) {
+ strcat(return_string,"0");
+ }
+ if ((raw_azimuth/HEADING_MULTIPLIER) < 10) {
+ strcat(return_string,"0");
+ }
+ dtostrf(float(raw_azimuth/HEADING_MULTIPLIER),0,6,tempstring);
+ strcat(return_string,tempstring);
+ command_good = 1;
+ }
+ #ifdef FEATURE_ELEVATION_CONTROL
+ if ((slave_command_buffer[0] == 'E') && (slave_command_buffer[1] == 'L')) {
+ strcpy(return_string,"EL");
+ if ((elevation/HEADING_MULTIPLIER) >= 0) {
+ strcat(return_string,"+");
+ } else {
+ strcat(return_string,"-");
+ }
+ //if (abs(elevation/HEADING_MULTIPLIER) < 1000) {
+ // strcat(return_string,"0");
+ //}
+ if (abs(elevation/HEADING_MULTIPLIER) < 100) {
+ strcat(return_string,"0");
+ }
+ if (abs(elevation/HEADING_MULTIPLIER) < 10) {
+ strcat(return_string,"0");
+ }
+ dtostrf(float(abs(elevation/HEADING_MULTIPLIER)),0,6,tempstring);
+ strcat(return_string,tempstring);
+ command_good = 1;
+ }
+ #endif // FEATURE_ELEVATION_CONTROL
+ } // end of two byte commands
+
+
+
+ if (slave_command_buffer_index == 3) {
+ if (((slave_command_buffer[0] == 'S') && (slave_command_buffer[1] == 'A')) & (slave_command_buffer[2] > 47) && (slave_command_buffer[2] < 53)) {
+ serial_read_event_flag[slave_command_buffer[2] - 48] = 1;
+ command_good = 1;
+ strcpy(return_string,"OK");
+ }
+ if (((slave_command_buffer[0] == 'S') && (slave_command_buffer[1] == 'D')) & (slave_command_buffer[2] > 47) && (slave_command_buffer[2] < 53)) {
+ serial_read_event_flag[slave_command_buffer[2] - 48] = 0;
+ command_good = 1;
+ strcpy(return_string,"OK");
+ }
+
+ }
+
+
+ if (slave_command_buffer_index == 4) {
+ if ((slave_command_buffer[0] == 'S') && (slave_command_buffer[1] == 'W')) { // Serial Write command
+ switch (slave_command_buffer[2]) {
+ case '0': control_port->write(slave_command_buffer[3]); command_good = 1; break;
+ #if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE)
+ case '1': remote_unit_port->write(slave_command_buffer[3]); command_good = 1; break;
+ #endif
+ }
+ }
+
+ if ((slave_command_buffer[0] == 'D') && (slave_command_buffer[1] == 'O')) {
+ if ((((slave_command_buffer[2] > 47) && (slave_command_buffer[2] < 58)) || (toupper(slave_command_buffer[2]) == 'A')) && (slave_command_buffer[3] > 47) && (slave_command_buffer[3] < 58)) {
+ command_good = 1;
+ byte pin_value = 0;
+ if (toupper(slave_command_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(slave_command_buffer[3] - 48);
+ } else {
+ pin_value = ((slave_command_buffer[2] - 48) * 10) + (slave_command_buffer[3] - 48);
+ }
+ #ifdef DEBUG_PROCESS_SLAVE
+ debug_print("service_serial_buffer: pin_value: ");
+ debug_print_int(pin_value);
+ #endif // DEBUG_PROCESS_SLAVE
+ strcpy(return_string,"OK");
+ pinModeEnhanced(pin_value, OUTPUT);
+ }
+ }
+
+ if ((slave_command_buffer[0] == 'D') && (slave_command_buffer[1] == 'H')) {
+ if ((((slave_command_buffer[2] > 47) && (slave_command_buffer[2] < 58)) || (toupper(slave_command_buffer[2]) == 'A')) && (slave_command_buffer[3] > 47) && (slave_command_buffer[3] < 58)) {
+ command_good = 1;
+ byte pin_value = 0;
+ if (toupper(slave_command_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(slave_command_buffer[3] - 48);
+ } else {
+ pin_value = ((slave_command_buffer[2] - 48) * 10) + (slave_command_buffer[3] - 48);
+ }
+ digitalWriteEnhanced(pin_value, HIGH);
+ strcpy(return_string,"OK");
+ }
+ }
+
+ if ((slave_command_buffer[0] == 'D') && (slave_command_buffer[1] == 'L')) {
+ if ((((slave_command_buffer[2] > 47) && (slave_command_buffer[2] < 58)) || (toupper(slave_command_buffer[2]) == 'A')) && (slave_command_buffer[3] > 47) && (slave_command_buffer[3] < 58)) {
+ command_good = 1;
+ byte pin_value = 0;
+ if (toupper(slave_command_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(slave_command_buffer[3] - 48);
+ } else {
+ pin_value = ((slave_command_buffer[2] - 48) * 10) + (slave_command_buffer[3] - 48);
+ }
+ digitalWriteEnhanced(pin_value, LOW);
+ strcpy(return_string,"OK");
+ }
+ }
+
+ if ((slave_command_buffer[0] == 'D') && (slave_command_buffer[1] == 'I')) {
+ if ((((slave_command_buffer[2] > 47) && (slave_command_buffer[2] < 58)) || (toupper(slave_command_buffer[2]) == 'A')) && (slave_command_buffer[3] > 47) && (slave_command_buffer[3] < 58)) {
+ command_good = 1;
+ byte pin_value = 0;
+ if (toupper(slave_command_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(slave_command_buffer[3] - 48);
+ } else {
+ pin_value = ((slave_command_buffer[2] - 48) * 10) + (slave_command_buffer[3] - 48);
+ }
+ pinModeEnhanced(pin_value, INPUT);
+ strcpy(return_string,"OK");
+ }
+ }
+
+ if ((slave_command_buffer[0] == 'D') && (slave_command_buffer[1] == 'P')) {
+ if ((((slave_command_buffer[2] > 47) && (slave_command_buffer[2] < 58)) || (toupper(slave_command_buffer[2]) == 'A')) && (slave_command_buffer[3] > 47) && (slave_command_buffer[3] < 58)) {
+ command_good = 1;
+ byte pin_value = 0;
+ if (toupper(slave_command_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(slave_command_buffer[3] - 48);
+ } else {
+ pin_value = ((slave_command_buffer[2] - 48) * 10) + (slave_command_buffer[3] - 48);
+ }
+ pinModeEnhanced(pin_value, INPUT);
+ digitalWriteEnhanced(pin_value, HIGH);
+ strcpy(return_string,"OK");
+ }
+ }
+
+ if ((slave_command_buffer[0] == 'D') && (slave_command_buffer[1] == 'R')) {
+ if ((((slave_command_buffer[2] > 47) && (slave_command_buffer[2] < 58)) || (toupper(slave_command_buffer[2]) == 'A')) && (slave_command_buffer[3] > 47) && (slave_command_buffer[3] < 58)) {
+ command_good = 1;
+ byte pin_value = 0;
+ if (toupper(slave_command_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(slave_command_buffer[3] - 48);
+ } else {
+ pin_value = ((slave_command_buffer[2] - 48) * 10) + (slave_command_buffer[3] - 48);
+ }
+ byte pin_read = digitalReadEnhanced(pin_value);
+ strcpy(return_string,"DR");
+ dtostrf((slave_command_buffer[2]-48),0,0,tempstring);
+ strcat(return_string,tempstring);
+ dtostrf((slave_command_buffer[3]-48),0,0,tempstring);
+ strcat(return_string,tempstring);
+ if (pin_read) {
+ strcat(return_string,"1");
+ } else {
+ strcat(return_string,"0");
+ }
+ }
+ }
+ if ((slave_command_buffer[0] == 'A') && (slave_command_buffer[1] == 'R')) {
+ if ((((slave_command_buffer[2] > 47) && (slave_command_buffer[2] < 58)) || (toupper(slave_command_buffer[2]) == 'A')) && (slave_command_buffer[3] > 47) && (slave_command_buffer[3] < 58)) {
+ command_good = 1;
+ byte pin_value = 0;
+ if (toupper(slave_command_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(slave_command_buffer[3] - 48);
+ } else {
+ pin_value = ((slave_command_buffer[2] - 48) * 10) + (slave_command_buffer[3] - 48);
+ }
+ int pin_read = analogReadEnhanced(pin_value);
+ strcpy(return_string,"AR");
+ if (toupper(slave_command_buffer[2]) == 'A') {
+ strcat(return_string,"A");
+ } else {
+ dtostrf((slave_command_buffer[2]-48),0,0,tempstring);
+ strcat(return_string,tempstring);
+ }
+
+ dtostrf((slave_command_buffer[3]-48),0,0,tempstring);
+ strcat(return_string,tempstring);
+ if (pin_read < 1000) {
+ strcat(return_string,"0");
+ }
+ if (pin_read < 100) {
+ strcat(return_string,"0");
+ }
+ if (pin_read < 10) {
+ strcat(return_string,"0");
+ }
+ dtostrf(pin_read,0,0,tempstring);
+ strcat(return_string,tempstring);
+ }
+ }
+
+ if ((slave_command_buffer[0] == 'N') && (slave_command_buffer[1] == 'T')) {
+ if ((((slave_command_buffer[2] > 47) && (slave_command_buffer[2] < 58)) || (toupper(slave_command_buffer[2]) == 'A')) && (slave_command_buffer[3] > 47) && (slave_command_buffer[3] < 58)) {
+ command_good = 1;
+ byte pin_value = 0;
+ if (toupper(slave_command_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(slave_command_buffer[3] - 48);
+ } else {
+ pin_value = ((slave_command_buffer[2] - 48) * 10) + (slave_command_buffer[3] - 48);
+ }
+ noTone(pin_value);
+ strcpy(return_string,"OK");
+ }
+ }
+
+ } // if (slave_command_buffer_index == 4)
+
+ if (slave_command_buffer_index == 7) {
+ if ((slave_command_buffer[0] == 'A') && (slave_command_buffer[1] == 'W')) {
+ if ((((slave_command_buffer[2] > 47) && (slave_command_buffer[2] < 58)) || (toupper(slave_command_buffer[2]) == 'A')) && (slave_command_buffer[3] > 47) && (slave_command_buffer[3] < 58)) {
+ byte pin_value = 0;
+ if (toupper(slave_command_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(slave_command_buffer[3] - 48);
+ } else {
+ pin_value = ((slave_command_buffer[2] - 48) * 10) + (slave_command_buffer[3] - 48);
+ }
+ int write_value = ((slave_command_buffer[4] - 48) * 100) + ((slave_command_buffer[5] - 48) * 10) + (slave_command_buffer[6] - 48);
+ if ((write_value >= 0) && (write_value < 256)) {
+ analogWriteEnhanced(pin_value, write_value);
+ strcpy(return_string,"OK");
+ command_good = 1;
+ }
+ }
+ }
+ }
+
+ if (slave_command_buffer_index == 8) {
+ if ((slave_command_buffer[0] == 'D') && (slave_command_buffer[1] == 'T')) {
+ if ((((slave_command_buffer[2] > 47) && (slave_command_buffer[2] < 58)) || (toupper(slave_command_buffer[2]) == 'A')) && (slave_command_buffer[3] > 47) && (slave_command_buffer[3] < 58)) {
+ byte pin_value = 0;
+ if (toupper(slave_command_buffer[2]) == 'A') {
+ pin_value = get_analog_pin(slave_command_buffer[3] - 48);
+ } else {
+ pin_value = ((slave_command_buffer[2] - 48) * 10) + (slave_command_buffer[3] - 48);
+ }
+ int write_value = ((slave_command_buffer[4] - 48) * 1000) + ((slave_command_buffer[5] - 48) * 100) + ((slave_command_buffer[6] - 48) * 10) + (slave_command_buffer[7] - 48);
+ if ((write_value >= 0) && (write_value <= 9999)) {
+ tone(pin_value, write_value);
+ strcpy(return_string,"OK");
+ command_good = 1;
+ }
+ }
+ }
+ }
+
+
+ if (!command_good) {
+ strcpy(return_string,"ER0289");
+ }
+ }
+
+ slave_command_buffer_index = 0;
+
+}
+#endif //FEATURE_REMOTE_UNIT_SLAVE
+
+// --------------------------------------------------------------
+void port_flush(){
+
+ #ifdef CONTROL_PORT_MAPPED_TO
+ control_port->flush();
+ #endif //CONTROL_PORT_MAPPED_TO
+
+ #if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE)
+ remote_unit_port->flush();
+ #endif
+
+ #if defined(GPS_PORT_MAPPED_TO) && defined(FEATURE_GPS)
+ gps_port->flush();
+ #endif //defined(GPS_PORT_MAPPED_TO) && defined(FEATURE_GPS)
+
+
+}
+// --------------------------------------------------------------
+#ifdef FEATURE_POWER_SWITCH
+void service_power_switch(){
+
+ static byte power_switch_state = 1;
+
+ #ifdef FEATURE_ELEVATION_CONTROL
+ if ((az_state != IDLE) || (el_state != IDLE)){
+ last_activity_time = millis();
+ }
+ #else //FEATURE_ELEVATION_CONTROL
+ if (az_state != IDLE){
+ last_activity_time = millis();
+ }
+ #endif //FEATURE_ELEVATION_CONTROL
+
+
+ if ((millis()-last_activity_time) > (60000 * POWER_SWITCH_IDLE_TIMEOUT)) {
+ if (power_switch_state){
+ digitalWriteEnhanced(power_switch, LOW);
+ power_switch_state = 0;
+ }
+ } else {
+ if (!power_switch_state){
+ digitalWriteEnhanced(power_switch, HIGH);
+ power_switch_state = 1;
+ }
+ }
+
+
+}
+#endif //FEATURE_POWER_SWITCH
+
+
+//------------------------------------------------------
+char * coordinates_to_maidenhead(float latitude_degrees,float longitude_degrees){
+
+ char temp_string[8] = "";
+
+ const char* asciiuppercase[] = {"A","B","C","D","E","F","G","H","I","J","K","L","M","N","O","P","Q","R"};
+ const char* asciinumbers[] = {"0","1","2","3","4","5","6","7","8","9"};
+ const char* asciilowercase[] = {"a","b","c","d","e","f","g","h","i","j","k","l","m","n","o","p","q","r","s","t","u","v","w","x"};
+
+ latitude_degrees += 90.0;
+ longitude_degrees += 180.0;
+
+ strcat(temp_string,asciiuppercase[int(longitude_degrees/20)]);
+ strcat(temp_string,asciiuppercase[int(latitude_degrees/10)]);
+ strcat(temp_string,asciinumbers[int((longitude_degrees - int(longitude_degrees/20)*20)/2)]);
+ strcat(temp_string,asciinumbers[int(latitude_degrees - int(latitude_degrees/10)*10)]);
+ strcat(temp_string,asciilowercase[int((longitude_degrees - (int(longitude_degrees/2)*2)) / (5.0/60.0))]);
+ strcat(temp_string,asciilowercase[int((latitude_degrees - (int(latitude_degrees/1)*1)) / (2.5/60.0))]);
+
+ return temp_string;
+
+}
+//------------------------------------------------------
+#ifdef FEATURE_MASTER_WITH_ETHERNET_SLAVE
+byte ethernet_slave_link_send(char * string_to_send){
+
+ if (ethernetslavelinkclient0_state == ETHERNET_SLAVE_CONNECTED){
+ ethernetslavelinkclient0.print(ETHERNET_PREAMBLE);
+ ethernetslavelinkclient0.println(string_to_send);
+ #ifdef DEBUG_ETHERNET
+ debug_print("ethernet_slave_link_send: ");
+ debug_println(string_to_send);
+ #endif //DEBUG_ETHERNET
+ return 1;
+ } else {
+ #ifdef DEBUG_ETHERNET
+ debug_print("ethernet_slave_link_send: link down not sending:");
+ debug_println(string_to_send);
+ #endif //DEBUG_ETHERNET
+ return 0;
+ }
+
+}
+#endif //FEATURE_MASTER_WITH_ETHERNET_SLAVE
+
+//------------------------------------------------------
+
+
+#if defined(FEATURE_CLOCK) && defined(OPTION_SYNC_MASTER_CLOCK_TO_SLAVE) && (defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE))
+void sync_master_clock_to_slave(){
+
+ static unsigned long last_sync_master_clock_to_slave = 5000;
+
+ if ((millis() - last_sync_master_clock_to_slave) >= (SYNC_MASTER_CLOCK_TO_SLAVE_CLOCK_SECS * 1000)){
+ if (submit_remote_command(REMOTE_UNIT_CL_COMMAND, 0, 0)) {
+ #ifdef DEBUG_SYNC_MASTER_CLOCK_TO_SLAVE
+ debug_println("sync_master_clock_to_slave: submitted REMOTE_UNIT_CL_COMMAND");
+ #endif //DEBUG_SYNC_MASTER_CLOCK_TO_SLAVE
+ last_sync_master_clock_to_slave = millis();
+ }
+ }
+
+}
+#endif //defined(FEATURE_CLOCK) && defined(OPTION_SYNC_MASTER_CLOCK_TO_SLAVE)
+
+//------------------------------------------------------
+#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
+void set_az_stepper_freq(int frequency){
+
+ az_stepper_pulse_period_us = 1000000 / frequency;
+
+}
+
+#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
+//------------------------------------------------------
+#if defined(FEATURE_ELEVATION_CONTROL) && defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE)
+void set_el_stepper_freq(int frequency){
+
+ el_stepper_pulse_period_us = 1000000 / frequency;
+
+}
+
+#endif //defined(FEATURE_ELEVATION_CONTROL) && defined(FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE)
+//------------------------------------------------------
+#ifdef FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
+void service_stepper_pins(){
+
+
+//az_stepper_pulses_remaining
+
+//el_stepper_pulses_remaining
+
+}
+#endif //FEATURE_STEPPER_MOTOR_EXPERIMENTAL_CODE
\ No newline at end of file
diff --git a/moon2.cpp b/moon2.cpp
new file mode 100755
index 0000000..00a573a
--- /dev/null
+++ b/moon2.cpp
@@ -0,0 +1,330 @@
+#include
+#include
+
+#include
+#include
+
+// 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;
+}
diff --git a/moon2.h b/moon2.h
new file mode 100755
index 0000000..35ed8a6
--- /dev/null
+++ b/moon2.h
@@ -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);
diff --git a/pins_m0upu.h b/pins_m0upu.h
new file mode 100755
index 0000000..bb54c2a
--- /dev/null
+++ b/pins_m0upu.h
@@ -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
+
diff --git a/rotator.h b/rotator.h
new file mode 100755
index 0000000..655c832
--- /dev/null
+++ b/rotator.h
@@ -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 ------- */
+
diff --git a/rotator_dependencies.h b/rotator_dependencies.h
new file mode 100755
index 0000000..5fef513
--- /dev/null
+++ b/rotator_dependencies.h
@@ -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
+
+
+
+
diff --git a/rotator_features.h b/rotator_features.h
index 68603e4..4d18001 100644
--- a/rotator_features.h
+++ b/rotator_features.h
@@ -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
diff --git a/rotator_features_ea4tx_ars_usb.h b/rotator_features_ea4tx_ars_usb.h
new file mode 100644
index 0000000..8069a0a
--- /dev/null
+++ b/rotator_features_ea4tx_ars_usb.h
@@ -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
+
+
+
+
+
+
diff --git a/rotator_hardware.h b/rotator_hardware.h
new file mode 100644
index 0000000..ea77452
--- /dev/null
+++ b/rotator_hardware.h
@@ -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)
\ No newline at end of file
diff --git a/rotator_pins.h b/rotator_pins.h
index 76e003e..8ebc525 100644
--- a/rotator_pins.h
+++ b/rotator_pins.h
@@ -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
diff --git a/rotator_pins_ea4tx_ars_usb.h b/rotator_pins_ea4tx_ars_usb.h
new file mode 100644
index 0000000..4e24f13
--- /dev/null
+++ b/rotator_pins_ea4tx_ars_usb.h
@@ -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)
+
diff --git a/rotator_pins_k3ng_g1000.h b/rotator_pins_k3ng_g1000.h
new file mode 100755
index 0000000..4c0af49
--- /dev/null
+++ b/rotator_pins_k3ng_g1000.h
@@ -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
+
diff --git a/rotator_pins_m0upu.h b/rotator_pins_m0upu.h
new file mode 100644
index 0000000..ec088d0
--- /dev/null
+++ b/rotator_pins_m0upu.h
@@ -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
+
diff --git a/rotator_settings.h b/rotator_settings.h
new file mode 100755
index 0000000..25574e1
--- /dev/null
+++ b/rotator_settings.h
@@ -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
+
diff --git a/sunpos.cpp b/sunpos.cpp
new file mode 100755
index 0000000..d8f010d
--- /dev/null
+++ b/sunpos.cpp
@@ -0,0 +1,137 @@
+// This file is available in electronic form at http://www.psa.es/sdg/sunpos.htm
+
+#include "sunpos.h"
+#include
+
+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;
+ }
+}
+
diff --git a/sunpos.h b/sunpos.h
new file mode 100755
index 0000000..427ded3
--- /dev/null
+++ b/sunpos.h
@@ -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
+