├── k3ng_rotator_controller ├── rotator_ethernet.h ├── rotator_stepper.h ├── rotator_clock_and_gps.h ├── rotator_moon_and_sun.h ├── rotator_command_processing.h ├── Nextion │ ├── calibri24all.zi │ ├── calibri32all.zi │ ├── calibri40all.zi │ ├── calibri48all.zi │ ├── calibri64all.zi │ ├── calibri24boldall.zi │ ├── K3NG Rotator Controller - BASE - NX4832TO35 - v2020.05.07.01.HMI │ └── K3NG Rotator Controller - NX3224TO24 - ZS1VDV - v2020.04.27.01.HMI ├── rotator_debug.h ├── rotator_hardware.h ├── rotator_debug_log_activation.h ├── rotator_features_ea4tx_ars_usb.h ├── rotator_pins_ea4tx_ars_usb.h ├── rotator_k3ngdisplay.h ├── rotator_dependencies.h ├── rotator.h ├── rotator_pins_k3ng_g1000.h └── rotator_pins_m0upu.h ├── libraries ├── TimerOne │ ├── examples │ │ ├── ReadReciver │ │ │ ├── .svn │ │ │ │ ├── dir-prop-base │ │ │ │ ├── all-wcprops │ │ │ │ ├── entries │ │ │ │ └── text-base │ │ │ │ │ └── ReadReciver.pde.svn-base │ │ │ └── ReadReciver.pde │ │ └── ISRBlink │ │ │ └── ISRBlink.pde │ ├── keywords.txt │ ├── TimerOne.h │ └── TimerOne.cpp ├── moon2 │ └── moon2.h ├── hh12 │ ├── hh12.h │ └── hh12.cpp ├── Mecha_QMC5883L │ ├── example │ │ ├── raw │ │ │ └── raw.ino │ │ └── azimuth │ │ │ └── azimuth.ino │ ├── MechaQMC5883.h │ ├── test.ino │ ├── MechaQMC5883.cpp │ ├── README_KO.md │ └── README.md ├── sunpos │ ├── sunpos.h │ └── sunpos.cpp ├── k3ng_remote_rotator_controller │ ├── k3ng_remote_rotator_controller.cpp │ └── k3ng_remote_rotator_controller.h ├── LCD_C0220BIZ │ ├── keywords.txt │ ├── LCD_C0220BiZ.h │ ├── LCD_C0220BiZ.cpp │ ├── examples │ │ ├── lcd_c0220Biz_test.ino │ │ └── lcd_c0220Biz_test │ │ │ └── lcd_c0220Biz_test.ino │ ├── lcd.h │ └── ST7036.h ├── TimerFive │ ├── TimerFive.h │ └── TimerFive.cpp ├── RTClib │ ├── RTClib.h │ └── RTClib.cpp ├── HMC5883L │ ├── HMC5883L.h │ └── HMC5883L.cpp ├── PCF8583 │ ├── PCF8583.h │ └── PCF8583.cpp ├── FaBoLCD_PCF8574 │ ├── FaBoLCD_PCF8574.h │ └── FaBoLCD_PCF8574.cpp ├── P13 │ ├── README │ └── P13.h ├── TinyGPS │ └── TinyGPS.h └── LSM303 │ └── LSM303.h └── README.md /k3ng_rotator_controller/rotator_ethernet.h: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /k3ng_rotator_controller/rotator_stepper.h: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /k3ng_rotator_controller/rotator_clock_and_gps.h: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /k3ng_rotator_controller/rotator_moon_and_sun.h: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /k3ng_rotator_controller/rotator_command_processing.h: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /libraries/TimerOne/examples/ReadReciver/.svn/dir-prop-base: -------------------------------------------------------------------------------- 1 | K 14 2 | bugtraq:number 3 | V 4 4 | true 5 | END 6 | -------------------------------------------------------------------------------- /k3ng_rotator_controller/Nextion/calibri24all.zi: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ok1hra/k3ng_rotator_controller/master/k3ng_rotator_controller/Nextion/calibri24all.zi -------------------------------------------------------------------------------- /k3ng_rotator_controller/Nextion/calibri32all.zi: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ok1hra/k3ng_rotator_controller/master/k3ng_rotator_controller/Nextion/calibri32all.zi -------------------------------------------------------------------------------- /k3ng_rotator_controller/Nextion/calibri40all.zi: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ok1hra/k3ng_rotator_controller/master/k3ng_rotator_controller/Nextion/calibri40all.zi -------------------------------------------------------------------------------- /k3ng_rotator_controller/Nextion/calibri48all.zi: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ok1hra/k3ng_rotator_controller/master/k3ng_rotator_controller/Nextion/calibri48all.zi -------------------------------------------------------------------------------- /k3ng_rotator_controller/Nextion/calibri64all.zi: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ok1hra/k3ng_rotator_controller/master/k3ng_rotator_controller/Nextion/calibri64all.zi -------------------------------------------------------------------------------- /k3ng_rotator_controller/Nextion/calibri24boldall.zi: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ok1hra/k3ng_rotator_controller/master/k3ng_rotator_controller/Nextion/calibri24boldall.zi -------------------------------------------------------------------------------- /k3ng_rotator_controller/Nextion/K3NG Rotator Controller - BASE - NX4832TO35 - v2020.05.07.01.HMI: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ok1hra/k3ng_rotator_controller/master/k3ng_rotator_controller/Nextion/K3NG Rotator Controller - BASE - NX4832TO35 - v2020.05.07.01.HMI -------------------------------------------------------------------------------- /k3ng_rotator_controller/Nextion/K3NG Rotator Controller - NX3224TO24 - ZS1VDV - v2020.04.27.01.HMI: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ok1hra/k3ng_rotator_controller/master/k3ng_rotator_controller/Nextion/K3NG Rotator Controller - NX3224TO24 - ZS1VDV - v2020.04.27.01.HMI -------------------------------------------------------------------------------- /libraries/moon2/moon2.h: -------------------------------------------------------------------------------- 1 | void grid2deg(char *grid0,double *dlong,double *dlat); 2 | 3 | void moon2(int y,int m,int Day, 4 | double UT, 5 | double lon,double lat, 6 | double *RA,double *Dec, 7 | double *topRA,double *topDec, 8 | double *LST,double *HA, 9 | double *Az,double *El,double *dist); 10 | -------------------------------------------------------------------------------- /libraries/TimerOne/examples/ReadReciver/.svn/all-wcprops: -------------------------------------------------------------------------------- 1 | K 25 2 | svn:wc:ra_dav:version-url 3 | V 51 4 | /svn/!svn/ver/3/trunk/Release%20Quality/ReadReciver 5 | END 6 | ReadReciver.pde 7 | K 25 8 | svn:wc:ra_dav:version-url 9 | V 67 10 | /svn/!svn/ver/7/trunk/Release%20Quality/ReadReciver/ReadReciver.pde 11 | END 12 | -------------------------------------------------------------------------------- /libraries/hh12/hh12.h: -------------------------------------------------------------------------------- 1 | #ifndef hh12_h 2 | #define hh12_h 3 | 4 | #define HH12_DELAY 100 // microseconds 5 | //#define OPTION_HH12_10_BIT_READINGS 6 | 7 | 8 | class hh12 { 9 | 10 | public: 11 | hh12(); 12 | void initialize(int _hh12_clock_pin, int _hh12_cs_pin, int _hh12_data_pin); 13 | float heading(); 14 | 15 | private: 16 | int hh12_clock_pin; 17 | int hh12_cs_pin; 18 | int hh12_data_pin; 19 | 20 | }; 21 | 22 | 23 | #endif //hh12_h 24 | -------------------------------------------------------------------------------- /libraries/Mecha_QMC5883L/example/raw/raw.ino: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | 4 | MechaQMC5883 qmc; 5 | 6 | void setup() { 7 | Wire.begin(); 8 | Serial.begin(9600); 9 | qmc.init(); 10 | //qmc.setMode(Mode_Continuous,ODR_200Hz,RNG_2G,OSR_256); 11 | } 12 | 13 | void loop() { 14 | int x,y,z; 15 | qmc.read(&x,&y,&z); 16 | 17 | Serial.print("x: "); 18 | Serial.print(x); 19 | Serial.print(" y: "); 20 | Serial.print(y); 21 | Serial.print(" z: "); 22 | Serial.print(z); 23 | Serial.println(); 24 | delay(100); 25 | } 26 | -------------------------------------------------------------------------------- /libraries/Mecha_QMC5883L/example/azimuth/azimuth.ino: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | 4 | MechaQMC5883 qmc; 5 | 6 | void setup() { 7 | Wire.begin(); 8 | Serial.begin(9600); 9 | qmc.init(); 10 | //qmc.setMode(Mode_Continuous,ODR_200Hz,RNG_2G,OSR_256); 11 | } 12 | 13 | void loop() { 14 | int x, y, z; 15 | int azimuth; 16 | //float azimuth; //is supporting float too 17 | qmc.read(&x, &y, &z,&azimuth); 18 | //azimuth = qmc.azimuth(&y,&x);//you can get custom azimuth 19 | Serial.print("x: "); 20 | Serial.print(x); 21 | Serial.print(" y: "); 22 | Serial.print(y); 23 | Serial.print(" z: "); 24 | Serial.print(z); 25 | Serial.print(" a: "); 26 | Serial.print(azimuth); 27 | Serial.println(); 28 | delay(100); 29 | } 30 | -------------------------------------------------------------------------------- /libraries/TimerOne/examples/ReadReciver/.svn/entries: -------------------------------------------------------------------------------- 1 | 10 2 | 3 | dir 4 | 6 5 | https://lex-arduino-sketchbook.googlecode.com/svn/trunk/Release%20Quality/ReadReciver 6 | https://lex-arduino-sketchbook.googlecode.com/svn 7 | 8 | 9 | 10 | 2011-06-24T22:05:24.141546Z 11 | 3 12 | lex.v.talionis@gmail.com 13 | has-props 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | c9f85be5-ce43-0359-81d1-43f08a9217a6 28 | 29 | ReadReciver.pde 30 | file 31 | 7 32 | 33 | 34 | 35 | 2011-06-25T03:21:57.149370Z 36 | 7554a9104cd32bca8710cff214402bb2 37 | 2011-06-25T03:22:33.720706Z 38 | 7 39 | lex.v.talionis@gmail.com 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 3527 62 | 63 | -------------------------------------------------------------------------------- /libraries/TimerOne/examples/ISRBlink/ISRBlink.pde: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | void setup() 4 | { 5 | // Initialize the digital pin as an output. 6 | // Pin 13 has an LED connected on most Arduino boards 7 | pinMode(13, OUTPUT); 8 | 9 | Timer1.initialize(100000); // set a timer of length 100000 microseconds (or 0.1 sec - or 10Hz => the led will blink 5 times, 5 cycles of on-and-off, per second) 10 | Timer1.attachInterrupt( timerIsr ); // attach the service routine here 11 | } 12 | 13 | void loop() 14 | { 15 | // Main code loop 16 | // TODO: Put your regular (non-ISR) logic here 17 | } 18 | 19 | /// -------------------------- 20 | /// Custom ISR Timer Routine 21 | /// -------------------------- 22 | void timerIsr() 23 | { 24 | // Toggle LED 25 | digitalWrite( 13, digitalRead( 13 ) ^ 1 ); 26 | } -------------------------------------------------------------------------------- /libraries/sunpos/sunpos.h: -------------------------------------------------------------------------------- 1 | // This file is available in electronic form at http://www.psa.es/sdg/sunpos.htm 2 | 3 | #ifndef __SUNPOS_H 4 | #define __SUNPOS_H 5 | 6 | 7 | // Declaration of some constants 8 | #define PI_SUNPOS 3.14159265358979323846 9 | #define TWOPI_SUNPOS (2*PI_SUNPOS) 10 | #define RAD_SUNPOS (PI_SUNPOS/180) 11 | #define dEarthMeanRadius 6371.01 // In km 12 | #define dAstronomicalUnit 149597890 // In km 13 | 14 | struct cTime 15 | { 16 | int iYear; 17 | int iMonth; 18 | int iDay; 19 | double dHours; 20 | double dMinutes; 21 | double dSeconds; 22 | }; 23 | 24 | struct cLocation 25 | { 26 | double dLongitude; 27 | double dLatitude; 28 | }; 29 | 30 | struct cSunCoordinates 31 | { 32 | double dZenithAngle; 33 | double dAzimuth; 34 | }; 35 | 36 | void sunpos(cTime udtTime, cLocation udtLocation, cSunCoordinates *udtSunCoordinates); 37 | 38 | #endif 39 | 40 | -------------------------------------------------------------------------------- /libraries/k3ng_remote_rotator_controller/k3ng_remote_rotator_controller.cpp: -------------------------------------------------------------------------------- 1 | 2 | #ifndef K3NG_REMOTE_H 3 | #define K3NG_REMOTE_H 4 | 5 | // K3NG_DISPLAY_LIBRARY_VERSION "1.0.2015061901" 6 | 7 | 8 | #if defined(ARDUINO) && ARDUINO >= 100 9 | #include "Arduino.h" 10 | #else 11 | #include "WProgram.h" 12 | #endif 13 | 14 | #include "k3ng_remote_rotator_controller.h" 15 | 16 | 17 | uint8_t automatic_polling_active = 0; 18 | 19 | 20 | 21 | //----------------------------------------------------------------------------------------------------- 22 | 23 | K3NGremoteunit::K3NGremoteunit(){ 24 | 25 | 26 | 27 | } 28 | 29 | //----------------------------------------------------------------------------------------------------- 30 | 31 | void K3NGremoteunit::initialize(){ 32 | 33 | 34 | 35 | 36 | 37 | } 38 | 39 | //----------------------------------------------------------------------------------------------------- 40 | 41 | void K3NGremoteunit::service(){ 42 | 43 | 44 | if (automatic_polling_active){ 45 | 46 | 47 | } 48 | 49 | 50 | } 51 | 52 | #endif //K3NG_REMOTE_H -------------------------------------------------------------------------------- /libraries/LCD_C0220BIZ/keywords.txt: -------------------------------------------------------------------------------- 1 | ####################################### 2 | # Syntax Coloring Map For Ultrasound 3 | ####################################### 4 | 5 | ####################################### 6 | # Datatypes (KEYWORD1) 7 | ####################################### 8 | 9 | LCD_C0220BIZ KEYWORD1 10 | 11 | ####################################### 12 | # Methods and Functions (KEYWORD2) 13 | ####################################### 14 | init KEYWORD2 15 | setDelay KEYWORD2 16 | command KEYWORD2 17 | write KEYWORD2 18 | clear KEYWORD2 19 | home KEYWORD2 20 | on KEYWORD2 21 | off KEYWORD2 22 | cursor_on KEYWORD2 23 | cursor_off KEYWORD2 24 | blink_on KEYWORD2 25 | blink_off KEYWORD2 26 | setCursor KEYWORD2 27 | status KEYWORD2 28 | load_custom_character KEYWORD2 29 | keypad KEYWORD2 30 | setBacklight KEYWORD2 31 | setContrast KEYWORD2 32 | 33 | ####################################### 34 | # Constants (LITERAL1) 35 | ####################################### 36 | -------------------------------------------------------------------------------- /libraries/TimerOne/keywords.txt: -------------------------------------------------------------------------------- 1 | ####################################### 2 | # Syntax Coloring Map For TimerOne 3 | ####################################### 4 | 5 | ####################################### 6 | # Datatypes (KEYWORD1) 7 | ####################################### 8 | 9 | TimerOne KEYWORD1 10 | 11 | ####################################### 12 | # Methods and Functions (KEYWORD2) 13 | ####################################### 14 | 15 | initialize KEYWORD2 16 | start KEYWORD2 17 | stop KEYWORD2 18 | restart KEYWORD2 19 | resume KEYWORD2 20 | read KEYWORD2 21 | pwm KEYWORD2 22 | disablePwm KEYWORD2 23 | attachInterrupt KEYWORD2 24 | detachInterrupt KEYWORD2 25 | setPeriod KEYWORD2 26 | setPwmDuty KEYWORD2 27 | 28 | ####################################### 29 | # Constants (LITERAL1) 30 | ####################################### 31 | 32 | 33 | -------------------------------------------------------------------------------- /libraries/Mecha_QMC5883L/MechaQMC5883.h: -------------------------------------------------------------------------------- 1 | #ifndef Mecha_QMC5883 2 | #define Mecha_QMC5883 3 | 4 | #include "Arduino.h" 5 | #include "Wire.h" 6 | 7 | #define QMC5883_ADDR 0x0D 8 | 9 | 10 | //REG CONTROL 11 | 12 | //0x09 13 | 14 | #define Mode_Standby 0b00000000 15 | #define Mode_Continuous 0b00000001 16 | 17 | #define ODR_10Hz 0b00000000 18 | #define ODR_50Hz 0b00000100 19 | #define ODR_100Hz 0b00001000 20 | #define ODR_200Hz 0b00001100 21 | 22 | #define RNG_2G 0b00000000 23 | #define RNG_8G 0b00010000 24 | 25 | #define OSR_512 0b00000000 26 | #define OSR_256 0b01000000 27 | #define OSR_128 0b10000000 28 | #define OSR_64 0b11000000 29 | 30 | 31 | class MechaQMC5883{ 32 | public: 33 | 34 | 35 | void setAddress(uint8_t addr); 36 | 37 | void init(); //init qmc5883 38 | 39 | void setMode(uint16_t mode,uint16_t odr,uint16_t rng,uint16_t osr); // setting 40 | 41 | void softReset(); //soft RESET 42 | 43 | void read(uint16_t* x,uint16_t* y,uint16_t* z); //reading 44 | void read(uint16_t* x,uint16_t* y,uint16_t* z,int* a); 45 | void read(uint16_t* x,uint16_t* y,uint16_t* z,float* a); 46 | 47 | float azimuth(uint16_t* a,uint16_t* b); 48 | 49 | private: 50 | 51 | void WriteReg(uint8_t Reg,uint8_t val); 52 | 53 | 54 | 55 | uint8_t address = QMC5883_ADDR; 56 | 57 | }; 58 | 59 | 60 | 61 | #endif 62 | -------------------------------------------------------------------------------- /libraries/Mecha_QMC5883L/test.ino: -------------------------------------------------------------------------------- 1 | #include //I2C Arduino Library 2 | 3 | #define addr 0x0D //I2C Address for The HMC5883 4 | 5 | void setup() { 6 | 7 | Serial.begin(9600); 8 | Wire.begin(); 9 | 10 | 11 | Wire.beginTransmission(addr); //start talking 12 | Wire.write(0x0B); // Tell the HMC5883 to Continuously Measure 13 | Wire.write(0x01); // Set the Register 14 | Wire.endTransmission(); 15 | Wire.beginTransmission(addr); //start talking 16 | Wire.write(0x09); // Tell the HMC5883 to Continuously Measure 17 | Wire.write(0x1D); // Set the Register 18 | Wire.endTransmission(); 19 | } 20 | 21 | void loop() { 22 | 23 | int x, y, z; //triple axis data 24 | 25 | //Tell the HMC what regist to begin writing data into 26 | 27 | 28 | Wire.beginTransmission(addr); 29 | Wire.write(0x00); //start with register 3. 30 | Wire.endTransmission(); 31 | 32 | //Read the data.. 2 bytes for each axis.. 6 total bytes 33 | Wire.requestFrom(addr, 6); 34 | if (6 <= Wire.available()) { 35 | x = Wire.read(); //MSB x 36 | x |= Wire.read() << 8; //LSB x 37 | z = Wire.read(); //MSB z 38 | z |= Wire.read() << 8; //LSB z 39 | y = Wire.read(); //MSB y 40 | y |= Wire.read() << 8; //LSB y 41 | } 42 | 43 | // Show Values 44 | Serial.print("X Value: "); 45 | Serial.println(x); 46 | Serial.print("Y Value: "); 47 | Serial.println(y); 48 | Serial.print("Z Value: "); 49 | Serial.println(z); 50 | Serial.println(); 51 | 52 | delay(500); 53 | } 54 | -------------------------------------------------------------------------------- /libraries/k3ng_remote_rotator_controller/k3ng_remote_rotator_controller.h: -------------------------------------------------------------------------------- 1 | 2 | #if defined(ARDUINO) && ARDUINO >= 100 3 | #include "Arduino.h" 4 | #else 5 | #include "WProgram.h" 6 | #endif 7 | 8 | 9 | #define K3NG_REMOTE_UNIT_LIBRARY_VERSION "1.0.2015061901" 10 | 11 | /* 12 | 13 | How this thing works.... 14 | 15 | +-----------+ 16 | | |------serial/ethernet----->byte_in --> { } <-- send_command() 17 | | remote | { class K3NGremoteunit } --> azimuth 18 | | unit |<-----serial/ethernet-----byte_out <-- { } --> elevation 19 | | | 20 | +-----------+ 21 | 22 | 23 | */ 24 | 25 | class K3NGremoteunit { 26 | 27 | public: 28 | 29 | K3NGremoteunit(); 30 | void initialize(); 31 | void service(); 32 | /* 33 | void byte_in(uint8_t byte_received); 34 | void byte_out(uint8_t byte_to_send); 35 | uint8_t bytes_out_available(); 36 | uint8_t send_command(uint8_t command_to_send); 37 | uint8_t send_command(uint8_t command_to_send,float float_parameter); 38 | void stop_automatic_polling(); 39 | void resume_automatic_polling(); 40 | 41 | 42 | unsigned long last_valid_response_received_time; 43 | uint8_t link_state; 44 | int poll_rate_ms; 45 | 46 | float azimuth; 47 | float elevation; 48 | uint8_t gps_state; 49 | uint8_t azimuth_state; 50 | uint8_t elevation_state;*/ 51 | 52 | 53 | 54 | 55 | 56 | private: 57 | 58 | 59 | 60 | }; -------------------------------------------------------------------------------- /libraries/TimerFive/TimerFive.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Interrupt and PWM utilities for 16 bit Timer5 on ATmega640/1280/2560 3 | * Original code by Jesse Tane for http://labs.ideo.com August 2008 4 | * Modified March 2009 by Jérôme Despatis and Jesse Tane for ATmega328 support 5 | * Modified June 2009 by Michael Polli and Jesse Tane to fix a bug in setPeriod() which caused the timer to stop 6 | * Modified Aug 2011 by RobotFreak to work with timer5 of the ATMega640/1280/2560 or Arduino Mega/ADK 7 | * 8 | * This is free software. You can redistribute it and/or modify it under 9 | * the terms of Creative Commons Attribution 3.0 United States License. 10 | * To view a copy of this license, visit http://creativecommons.org/licenses/by/3.0/us/ 11 | * or send a letter to Creative Commons, 171 Second Street, Suite 300, San Francisco, California, 94105, USA. 12 | * 13 | */ 14 | 15 | #include 16 | #include 17 | 18 | #define RESOLUTION 65536 // Timer5 is 16 bit 19 | 20 | class TimerFive 21 | { 22 | public: 23 | 24 | // properties 25 | unsigned int pwmPeriod; 26 | unsigned char clockSelectBits; 27 | 28 | // methods 29 | void initialize(long microseconds=1000000); 30 | void start(); 31 | void stop(); 32 | void restart(); 33 | void pwm(char pin, int duty, long microseconds=-1); 34 | void disablePwm(char pin); 35 | void attachInterrupt(void (*isr)(), long microseconds=-1); 36 | void detachInterrupt(); 37 | void setPeriod(long microseconds); 38 | void setPwmDuty(char pin, int duty); 39 | void (*isrCallback)(); 40 | }; 41 | 42 | extern TimerFive Timer5; 43 | -------------------------------------------------------------------------------- /k3ng_rotator_controller/rotator_debug.h: -------------------------------------------------------------------------------- 1 | // debug.h contributed by Matt VK5ZM 2 | 3 | #ifndef _ROTATOR_DEBUG_h 4 | #define _ROTATOR_DEBUG_h 5 | 6 | #if defined(ARDUINO) && ARDUINO >= 100 7 | #include "Arduino.h" 8 | #else 9 | #include "WProgram.h" 10 | #endif 11 | 12 | #include "rotator.h" 13 | 14 | #ifdef HARDWARE_EA4TX_ARS_USB 15 | #include "rotator_features_ea4tx_ars_usb.h" 16 | #endif 17 | #ifdef HARDWARE_WB6KCN 18 | #include "rotator_features_wb6kcn.h" 19 | #endif 20 | #ifdef HARDWARE_M0UPU 21 | #include "rotator_features_m0upu.h" 22 | #endif 23 | #ifdef HARDWARE_TEST 24 | #include "rotator_features_test.h" 25 | #endif 26 | #if !defined(HARDWARE_CUSTOM) 27 | #include "rotator_features.h" 28 | #endif 29 | 30 | #include "rotator_hardware.h" 31 | 32 | 33 | class DebugClass 34 | { 35 | protected: 36 | 37 | 38 | public: 39 | void init(); 40 | 41 | void print(const char *str); 42 | void print(const __FlashStringHelper *str); 43 | void print(char ch); 44 | void print(int i); 45 | void print(float f); 46 | void print(float f, byte places); 47 | void print(unsigned int i); 48 | void print(long unsigned int i); 49 | void print(long i); 50 | void print(double i); 51 | 52 | void println(int i); 53 | void println(long i); 54 | void println(double i); 55 | void println(const char *str); 56 | void println(const __FlashStringHelper *str); 57 | 58 | void write(const char *str); 59 | void write(int i); 60 | }; 61 | 62 | 63 | extern uint8_t debug_mode; 64 | extern CONTROL_PORT_SERIAL_PORT_CLASS * control_port; 65 | 66 | #endif //_ROTATOR_DEBUG_h 67 | 68 | -------------------------------------------------------------------------------- /libraries/RTClib/RTClib.h: -------------------------------------------------------------------------------- 1 | // Code by JeeLabs http://news.jeelabs.org/code/ 2 | // Released to the public domain! Enjoy! 3 | 4 | #ifndef _RTCLIB_H_ 5 | #define _RTCLIB_H_ 6 | 7 | // Simple general-purpose date/time class (no TZ / DST / leap second handling!) 8 | class DateTime { 9 | public: 10 | DateTime (uint32_t t =0); 11 | DateTime (uint16_t year, uint8_t month, uint8_t day, 12 | uint8_t hour =0, uint8_t min =0, uint8_t sec =0); 13 | DateTime (const char* date, const char* time); 14 | uint16_t year() const { return 2000 + yOff; } 15 | uint8_t month() const { return m; } 16 | uint8_t day() const { return d; } 17 | uint8_t hour() const { return hh; } 18 | uint8_t minute() const { return mm; } 19 | uint8_t second() const { return ss; } 20 | uint8_t dayOfWeek() const; 21 | 22 | // 32-bit times as seconds since 1/1/2000 23 | long secondstime() const; 24 | // 32-bit times as seconds since 1/1/1970 25 | uint32_t unixtime(void) const; 26 | 27 | protected: 28 | uint8_t yOff, m, d, hh, mm, ss; 29 | }; 30 | 31 | // RTC based on the DS1307 chip connected via I2C and the Wire library 32 | class RTC_DS1307 { 33 | public: 34 | static uint8_t begin(void); 35 | static void adjust(const DateTime& dt); 36 | uint8_t isrunning(void); 37 | static DateTime now(); 38 | }; 39 | 40 | // RTC using the internal millis() clock, has to be initialized before use 41 | // NOTE: this clock won't be correct once the millis() timer rolls over (>49d?) 42 | class RTC_Millis { 43 | public: 44 | static void begin(const DateTime& dt) { adjust(dt); } 45 | static void adjust(const DateTime& dt); 46 | static DateTime now(); 47 | 48 | protected: 49 | static long offset; 50 | }; 51 | 52 | #endif // _RTCLIB_H_ 53 | -------------------------------------------------------------------------------- /libraries/Mecha_QMC5883L/MechaQMC5883.cpp: -------------------------------------------------------------------------------- 1 | #include "MechaQMC5883.h" 2 | 3 | #include 4 | 5 | void MechaQMC5883::setAddress(uint8_t addr){ 6 | address = addr; 7 | } 8 | 9 | void MechaQMC5883::WriteReg(byte Reg,byte val){ 10 | Wire.beginTransmission(address); //start talking 11 | Wire.write(Reg); // Tell the HMC5883 to Continuously Measure 12 | Wire.write(val); // Set the Register 13 | Wire.endTransmission(); 14 | } 15 | 16 | void MechaQMC5883::init(){ 17 | WriteReg(0x0B,0x01); 18 | //Define Set/Reset period 19 | setMode(Mode_Continuous,ODR_200Hz,RNG_8G,OSR_512); 20 | /* 21 | Define 22 | OSR = 512 23 | Full Scale Range = 8G(Gauss) 24 | ODR = 200HZ 25 | set continuous measurement mode 26 | */ 27 | } 28 | 29 | void MechaQMC5883::setMode(uint16_t mode,uint16_t odr,uint16_t rng,uint16_t osr){ 30 | WriteReg(0x09,mode|odr|rng|osr); 31 | } 32 | 33 | 34 | void MechaQMC5883::softReset(){ 35 | WriteReg(0x0A,0x80); 36 | } 37 | 38 | void MechaQMC5883::read(uint16_t* x,uint16_t* y,uint16_t* z){ 39 | Wire.beginTransmission(address); 40 | Wire.write(0x00); 41 | Wire.endTransmission(); 42 | Wire.requestFrom((int) address, (int) 6); // Modified by Goody 2018-05-16 43 | *x = Wire.read(); //LSB x 44 | *x |= Wire.read() << 8; //MSB x 45 | *y = Wire.read(); //LSB z 46 | *y |= Wire.read() << 8; //MSB z 47 | *z = Wire.read(); //LSB y 48 | *z |= Wire.read() << 8; //MSB y 49 | } 50 | 51 | void MechaQMC5883::read(uint16_t* x,uint16_t* y,uint16_t* z,int* a){ 52 | read(x,y,z); 53 | *a = azimuth(y,x); 54 | } 55 | 56 | void MechaQMC5883::read(uint16_t* x,uint16_t* y,uint16_t* z,float* a){ 57 | read(x,y,z); 58 | *a = azimuth(y,x); 59 | } 60 | 61 | 62 | float MechaQMC5883::azimuth(uint16_t *a, uint16_t *b){ 63 | float azimuth = atan2((int)*a,(int)*b) * 180.0/PI; 64 | return azimuth < 0?360 + azimuth:azimuth; 65 | } 66 | -------------------------------------------------------------------------------- /libraries/LCD_C0220BIZ/LCD_C0220BiZ.h: -------------------------------------------------------------------------------- 1 | // --------------------------------------------------------------------------- 2 | // Created by Francisco Malpartida on 20/08/11. 3 | // Copyright 2011 - Under creative commons license 3.0: 4 | // Attribution-ShareAlike CC BY-SA 5 | // 6 | // This software is furnished "as is", without technical support, and with no 7 | // warranty, express or implied, as to its usefulness for any purpose. 8 | // 9 | // Thread Safe: No 10 | // Extendable: No 11 | // 12 | // @file LCD_C0220BiZ.h 13 | // NHD C0220BiZ display class definition. 14 | // 15 | // @brief Based on the LCD API 1.0 by dale@wentztech.com 16 | // This library implements the driver to drive the Newhaven Display 17 | // NHD-C0220BiZ-FSW-FBW-3V3M. The display is build around the ST7036 18 | // i2c LCD controller. This is a 3.3V display. 19 | // I2C displays based on the ST7632 should also be compatible. 20 | // 21 | // Other compatible displays: 22 | // - NHD-C0220BiZ-FSW-FBW-3V3M 23 | // - NHD-C0220BiZ-FS(RGB)-FBW-3VM 24 | // Non tested but should be compatible with no or little changes 25 | // - NHD-C0216CiZ-FSW-FBW-3V3 26 | // - NHD-C0216CiZ-FN-FBW-3V 27 | // 28 | // @author F. Malpartida - fmalpartida@gmail.com 29 | // --------------------------------------------------------------------------- 30 | 31 | #ifndef LCD_C0220BIZ_h 32 | #define LCD_C0220BIZ_h 33 | 34 | #define _LCDEXPANDED // If defined turn on advanced functions 35 | 36 | #include 37 | #include "ST7036.h" 38 | 39 | #define _LCD_C0220BIZ_VERSION "1.2.0" 40 | #define _LCD_API_VERSION "1.0" 41 | 42 | class LCD_C0220BIZ : public ST7036 43 | { 44 | 45 | public: 46 | 47 | /** 48 | Constructor for the display class 49 | 50 | @return None 51 | 52 | LCD_C0220BIZ( ); 53 | */ 54 | LCD_C0220BIZ( ); 55 | 56 | /** 57 | Constructor for the display class with backlight allowcation pin. 58 | 59 | @param backlightPin initiales the backlight pin. 60 | 61 | @return None 62 | 63 | LCD_C0220BIZ(int8_t backlightPin ); 64 | */ 65 | LCD_C0220BIZ( int8_t backlightPin ); 66 | 67 | }; 68 | 69 | #endif 70 | 71 | -------------------------------------------------------------------------------- /libraries/HMC5883L/HMC5883L.h: -------------------------------------------------------------------------------- 1 | /* 2 | HMC5883L.h - Header file for the HMC5883L Triple Axis Magnetometer Arduino Library. 3 | Copyright (C) 2011 Love Electronics (loveelectronics.co.uk) / 2012 bildr.org (Arduino 1.0 compatible) 4 | 5 | This program is free software: you can redistribute it and/or modify 6 | it under the terms of the version 3 GNU General Public License as 7 | published by the Free Software Foundation. 8 | 9 | This program is distributed in the hope that it will be useful, 10 | but WITHOUT ANY WARRANTY; without even the implied warranty of 11 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 12 | GNU General Public License for more details. 13 | 14 | You should have received a copy of the GNU General Public License 15 | along with this program. If not, see . 16 | 17 | WARNING: THE HMC5883L IS NOT IDENTICAL TO THE HMC5883! 18 | Datasheet for HMC5883L: 19 | http://www51.honeywell.com/aero/common/documents/myaerospacecatalog-documents/Defense_Brochures-documents/HMC5883L_3-Axis_Digital_Compass_IC.pdf 20 | 21 | */ 22 | 23 | #ifndef HMC5883L_h 24 | #define HMC5883L_h 25 | 26 | #include 27 | #include 28 | 29 | 30 | 31 | #define HMC5883L_Address 0x1E 32 | #define ConfigurationRegisterA 0x00 33 | #define ConfigurationRegisterB 0x01 34 | #define ModeRegister 0x02 35 | #define DataRegisterBegin 0x03 36 | 37 | #define Measurement_Continuous 0x00 38 | #define Measurement_SingleShot 0x01 39 | #define Measurement_Idle 0x03 40 | 41 | #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" 42 | #define ErrorCode_1_Num 1 43 | 44 | struct MagnetometerScaled 45 | { 46 | float XAxis; 47 | float YAxis; 48 | float ZAxis; 49 | }; 50 | 51 | struct MagnetometerRaw 52 | { 53 | int XAxis; 54 | int YAxis; 55 | int ZAxis; 56 | }; 57 | 58 | class HMC5883L 59 | { 60 | public: 61 | HMC5883L(); 62 | 63 | MagnetometerRaw ReadRawAxis(); 64 | MagnetometerScaled ReadScaledAxis(); 65 | 66 | int SetMeasurementMode(uint8_t mode); 67 | int SetScale(float gauss); 68 | 69 | char* GetErrorText(int errorCode); 70 | 71 | protected: 72 | void Write(int address, int byte); 73 | uint8_t* Read(int address, int length); 74 | 75 | private: 76 | float m_Scale; 77 | }; 78 | #endif -------------------------------------------------------------------------------- /k3ng_rotator_controller/rotator_hardware.h: -------------------------------------------------------------------------------- 1 | /* rotator_hardware.h 2 | 3 | Uncomment defines below if you're specifically using any of this hardware and edit the appropriate special features, pins, and settings files 4 | 5 | */ 6 | 7 | #if !defined(rotator_hardware_h) // can't touch this 8 | #define rotator_hardware_h // can't touch this 9 | 10 | // #define HARDWARE_M0UPU // customize rotator_features_m0upu.h, rotators_pins_m0upu.h, rotator_settings_m0upu.h 11 | // #define HARDWARE_EA4TX_ARS_USB // customize rotator_features_e4tx_ars_usb.h, rotators_pins_e4tx_ars_usb.h, rotator_settings_e4tx_ars_usb.h 12 | // #define HARDWARE_WB6KCN // customize rotator_features_wb6kcn.h, rotators_pins_wb6kcn.h, rotator_settings_wb6kcn.h 13 | // #define HARDWARE_TEST // customize rotator_features_test.h, rotators_pins_test.h, rotator_settings_test.h 14 | 15 | 16 | /* Serial port class definitions for various devices 17 | 18 | 19 | For Arduino Leonardo, Micro, and Yún, PLEASE READ THIS ! : 20 | 21 | If using Serial (USB Serial) for the control (main) port, set CONTROL_PORT_SERIAL_PORT_CLASS to Serial_ 22 | If using Serial1 (Board pins 0 and 1 Serial) for the control (main) port, set CONTROL_PORT_SERIAL_PORT_CLASS to HardwareSerial 23 | 24 | For more information on serial ports on various boards: https://www.arduino.cc/reference/en/language/functions/communication/serial/ 25 | 26 | */ 27 | 28 | #if defined(ARDUINO_MAPLE_MINI) 29 | #define CONTROL_PORT_SERIAL_PORT_CLASS USBSerial 30 | #elif defined(ARDUINO_AVR_MICRO) || defined(ARDUINO_AVR_LEONARDO) || defined(ARDUINO_AVR_YUN) 31 | #define CONTROL_PORT_SERIAL_PORT_CLASS Serial_ // <- Arduino Leonardo, Micro, and Yún - Configure this 32 | #elif defined(ARDUINO_AVR_PROMICRO) || defined(ARDUINO_AVR_ESPLORA) || defined(ARDUINO_AVR_LILYPAD_USB) || defined(ARDUINO_AVR_ROBOT_CONTROL) || defined(ARDUINO_AVR_ROBOT_MOTOR) || defined(ARDUINO_AVR_LEONARDO_ETH) 33 | #define CONTROL_PORT_SERIAL_PORT_CLASS Serial_ 34 | #elif defined(TEENSYDUINO) 35 | #define CONTROL_PORT_SERIAL_PORT_CLASS usb_serial_class 36 | #else 37 | #define CONTROL_PORT_SERIAL_PORT_CLASS HardwareSerial 38 | #endif 39 | 40 | 41 | 42 | // do not modify anything below this line 43 | 44 | #if defined(HARDWARE_M0UPU) || defined(HARDWARE_EA4TX_ARS_USB) || defined(HARDWARE_WB6KCN) || defined(HARDWARE_TEST) 45 | #define HARDWARE_CUSTOM 46 | #endif 47 | 48 | 49 | #endif //!defined(rotator_hardware_h) stop. hammer time. 50 | -------------------------------------------------------------------------------- /libraries/PCF8583/PCF8583.h: -------------------------------------------------------------------------------- 1 | /* 2 | Implements a simple interface to the time function of the PCF8583 RTC chip 3 | 4 | Works around the device's limited year storage by keeping the year in the 5 | first two bytes of user accessible storage 6 | 7 | Assumes device is attached in the standard location - Analog pins 4 and 5 8 | Device address is the 8 bit address (as in the device datasheet - normally A0) 9 | 10 | Copyright (c) 2009, Erik DeBill 11 | 12 | 13 | This library is free software; you can redistribute it and/or 14 | modify it under the terms of the GNU Lesser General Public 15 | License as published by the Free Software Foundation; either 16 | version 2.1 of the License, or (at your option) any later version. 17 | 18 | This library is distributed in the hope that it will be useful, 19 | but WITHOUT ANY WARRANTY; without even the implied warranty of 20 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 21 | Lesser General Public License for more details. 22 | 23 | You should have received a copy of the GNU Lesser General Public 24 | License along with this library; if not, write to the Free Software 25 | Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA 26 | */ 27 | 28 | 29 | /* 30 | 31 | Usage: 32 | PCF8583 pcf(0xA0); 33 | pcf.get_time(); 34 | 35 | Serial.print("year: "); 36 | Serial.println(pcf.year); 37 | 38 | 39 | pcf.hour = 14; 40 | pcf.minute = 30 41 | pcf.second = 0 42 | pcf.year = 2009 43 | pcf.month = 9 44 | pcf.day = 12 45 | pcf.set_time(); 46 | 47 | 48 | */ 49 | 50 | #ifndef PCF8583_H 51 | #define PCF8583_H 52 | 53 | #include 54 | #include 55 | 56 | class PCF8583 { 57 | int address; 58 | int dow; 59 | public: 60 | int second; 61 | int minute; 62 | int hour; 63 | int day; 64 | int month; 65 | int year; 66 | int year_base; 67 | 68 | int alarm_milisec; 69 | int alarm_second; 70 | int alarm_minute; 71 | int alarm_hour; 72 | int alarm_day; 73 | 74 | PCF8583(int device_address); 75 | void init (); 76 | 77 | void get_time(); 78 | void set_time(); 79 | void get_alarm(); 80 | int get_day_of_week() const { 81 | return dow; 82 | } 83 | 84 | void set_daily_alarm(); 85 | int bcd_to_byte(byte bcd); 86 | byte int_to_bcd(int in); 87 | }; 88 | 89 | 90 | #endif //PCF8583_H 91 | -------------------------------------------------------------------------------- /libraries/LCD_C0220BIZ/LCD_C0220BiZ.cpp: -------------------------------------------------------------------------------- 1 | // --------------------------------------------------------------------------- 2 | // Created by Francisco Malpartida on 20/08/11. 3 | // Copyright 2011 - Under creative commons license 3.0: 4 | // Attribution-ShareAlike CC BY-SA 5 | // 6 | // This software is furnished "as is", without technical support, and with no 7 | // warranty, express or implied, as to its usefulness for any purpose. 8 | // 9 | // Thread Safe: No 10 | // Extendable: No 11 | // 12 | // @file LCD_C0220BiZ.cpp 13 | // Display class implementation of the LCD API 1.0 14 | // 15 | // @brief Based on the LCD API 1.0 by dale@wentztech.com 16 | // This library implements the driver to drive the Newhaven Display 17 | // NHD‐C0220BiZ‐FSW‐FBW‐3V3M. The display is build around the ST7036 18 | // i2c LCD controller. This is a 3.3V display. 19 | // I2C displays based on the ST7032i should also be compatible. 20 | // 21 | // Other compatible displays: 22 | // - NHD‐C0220BiZ‐FSW‐FBW‐3V3M 23 | // - NHD-C0220BiZ-FS(RGB)-FBW-3VM 24 | // Non tested but should be compatible with no or little changes 25 | // - NHD-C0216CiZ-FSW-FBW-3V3 26 | // - NHD‐C0216CiZ‐FN‐FBW‐3V 27 | // 28 | // 29 | // @author F. Malpartida - fmalpartida@gmail.com 30 | // --------------------------------------------------------------------------- 31 | #include "LCD_C0220BiZ.h" 32 | 33 | // Class private constants and definition 34 | // ---------------------------------------------------------------------------- 35 | const int NUM_LINES = 2; // Number of lines in the display 36 | const int NUM_COLUMNS = 20; // Number of columns in the display 37 | const int I2C_ADDRS = 0x78; // I2C address of the display 38 | 39 | // Static member variable definitions 40 | // ---------------------------------------------------------------------------- 41 | 42 | // Static file scope variable definitions 43 | // ---------------------------------------------------------------------------- 44 | 45 | // Private support functions 46 | // ---------------------------------------------------------------------------- 47 | 48 | // CLASS METHODS 49 | // ---------------------------------------------------------------------------- 50 | 51 | // Constructors: 52 | // --------------------------------------------------------------------------- 53 | LCD_C0220BIZ::LCD_C0220BIZ( ):ST7036 ( NUM_LINES, NUM_COLUMNS, I2C_ADDRS ) 54 | { 55 | 56 | } 57 | 58 | LCD_C0220BIZ::LCD_C0220BIZ(int8_t backlightPin ) : 59 | ST7036 ( NUM_LINES, NUM_COLUMNS, I2C_ADDRS, backlightPin ) 60 | { 61 | 62 | } 63 | -------------------------------------------------------------------------------- /libraries/Mecha_QMC5883L/README_KO.md: -------------------------------------------------------------------------------- 1 | # Mechasolution QMC5883 Library 2 | 3 | HMC5883 지자기 나침반 센서의 수명 만료(EOL)로인해 그동안의 HMC5883 센서는 생산이 중단 되었고, 대체 상품인 QMC5883으로 변경이 되었습니다. 4 | 5 | ## Arduino Code 6 | 7 | 해당 라이브러리를 이용하기 위한 몇가지 간단한 규칙이 있습니다. 아래 정리된 내용을 읽어주시고 사용하시는 프로젝트에 적용해 주세요 8 | 9 | ### 기본 요소 10 | 11 | 필수적으로 필요한 헤더파일(#include...)과 Setup 쪽 코드 입니다. 12 | 13 | ```cpp 14 | #include 15 | #include 16 | 17 | void setup(){ 18 | Wire.begin(); 19 | } 20 | ``` 21 | 22 | ### 객체 선언 23 | 24 | 객체 선언 방식입니다. setup문 밖에서 사용이 되며 qmc와 같은 이름은 사용자가 원하는 다른 이름으로 변경이 가능합니다. 25 | 26 | ```cpp 27 | #include 28 | #include 29 | 30 | MechaQMC5883 qmc; 31 | ``` 32 | 33 | ### 사용 설정 34 | 35 | QMC5883 센서의 설정 함수 입니다. 36 | 37 | init 함수를 사용하면 기본 설정으로 QMC5883센서의 기능을 이용할 수 있습니다. 38 | 39 | ```cpp 40 | void setup(){ 41 | Wire.begin(); 42 | qmc.init(); 43 | } 44 | ``` 45 | 46 | 좀더 세세한 설정을 원한다면 다음과 같이 사용이 가능합니다. 47 | 48 | ```cpp 49 | void setup(){ 50 | Wire.begin(); 51 | qmc.init(); 52 | qmc.setMode(Mode_Standby,ODR_200Hz,RNG_8G,OSR_512); 53 | } 54 | ``` 55 | 56 | setMode에 사용되는 값들은 다음 값들을 이용할 수 있습니다. 57 | 58 | ``` 59 | Mode : Mode_Standby / Mode_Continuous 60 | 61 | ODR : ODR_10Hz / ODR_50Hz / ODR_100Hz / ODR_200Hz 62 | ouput data update rate 63 | 64 | RNG : RNG_2G / RNG_8G 65 | magneticfield measurement range 66 | 67 | OSR : OSR_512 / OSR_256 / OSR_128 / OSR_64 68 | over sampling rate 69 | ``` 70 | 71 | ### 값 읽기 72 | 73 | 측정한 센서의 값을 읽는 법은 다음과 같습니다. 74 | 75 | ```cpp 76 | void loop(){ 77 | int x,y,z; 78 | 79 | qmc.read(&x,&y,&z); 80 | } 81 | ``` 82 | 83 | 방위각에 대한 값입니다. 84 | 85 | ```cpp 86 | void loop(){ 87 | int x,y,z; 88 | int a; 89 | //float a; //float 형도 지원됩니다. 90 | 91 | qmc.read(&x,&y,&z,&a); 92 | } 93 | ``` 94 | 95 | 별도로 원하는 방위각도 구할 수 있습니다. 96 | 97 | ```cpp 98 | void loop(){ 99 | int x,y,z; 100 | int a; 101 | 102 | qmc.read(&x,&y,&z); 103 | a = qmc.azimuth(&y,&x); 104 | } 105 | ``` 106 | ### 기본 예제 107 | 108 | 다음은 라이브러리 기본 예제인 raw입니다. 109 | 110 | 위에 소개된 내용의 총집합으로 볼 수 있습니다. 111 | 112 | ```cpp 113 | #include 114 | #include 115 | 116 | MechaQMC5883 qmc; 117 | 118 | void setup() { 119 | Wire.begin(); 120 | Serial.begin(9600); 121 | qmc.init(); 122 | //qmc.setMode(Mode_Continuous,ODR_200Hz,RNG_2G,OSR_256); 123 | } 124 | 125 | void loop() { 126 | int x,y,z; 127 | qmc.read(&x,&y,&z); 128 | 129 | Serial.print("x: "); 130 | Serial.print(x); 131 | Serial.print(" y: "); 132 | Serial.print(y); 133 | Serial.print(" z: "); 134 | Serial.print(z); 135 | Serial.println(); 136 | delay(100); 137 | } 138 | ``` 139 | -------------------------------------------------------------------------------- /libraries/Mecha_QMC5883L/README.md: -------------------------------------------------------------------------------- 1 | # Mechasolution QMC5883L Library 2 | 3 | [한글 설명 바로가기](https://github.com/keepworking/Mecha_QMC5883/blob/master/README_KO.md) 4 | 5 | 6 | ## Arduino Code 7 | 8 | There are a few simple rules for using that library. Please read the following summary and apply it to your project 9 | 10 | ### Basic Elements 11 | 12 | Required header files (#include ...) and Setup side code. 13 | 14 | ```cpp 15 | #include 16 | #include 17 | 18 | void setup(){ 19 | Wire.begin(); 20 | } 21 | ``` 22 | 23 | ### Object Declaration 24 | 25 | The object declaration method. It is used outside the setup statement, and a name such as qmc can be changed to any other name you want. 26 | 27 | ```cpp 28 | #include 29 | #include 30 | 31 | MechaQMC5883 qmc; 32 | ``` 33 | 34 | ### initialization 35 | 36 | QMC5883 Sensor's setting function. 37 | 38 | The init function allows you to take advantage of the features of the QMC5883 sensor by default. 39 | 40 | ```cpp 41 | void setup(){ 42 | Wire.begin(); 43 | qmc.init(); 44 | } 45 | ``` 46 | 47 | If you want more detailed settings, you can use it as follows. 48 | 49 | ```cpp 50 | void setup(){ 51 | Wire.begin(); 52 | qmc.init(); 53 | qmc.setMode(Mode_Standby,ODR_200Hz,RNG_8G,OSR_512); 54 | } 55 | ``` 56 | 57 | The values ​​used for setMode can take the following values: 58 | 59 | ``` 60 | Mode : Mode_Standby / Mode_Continuous 61 | 62 | ODR : ODR_10Hz / ODR_50Hz / ODR_100Hz / ODR_200Hz 63 | ouput data update rate 64 | 65 | RNG : RNG_2G / RNG_8G 66 | magneticfield measurement range 67 | 68 | OSR : OSR_512 / OSR_256 / OSR_128 / OSR_64 69 | over sampling rate 70 | ``` 71 | 72 | ### Read values 73 | 74 | How to read the measured sensor value is as follows. 75 | 76 | ```cpp 77 | void loop(){ 78 | int x,y,z; 79 | 80 | qmc.read(&x,&y,&z); 81 | } 82 | ``` 83 | 84 | and we can get azimuth too. 85 | 86 | ```cpp 87 | void loop(){ 88 | int x,y,z; 89 | int a; 90 | //float a; //can get float value 91 | 92 | qmc.read(&x,&y,&z,&a); 93 | } 94 | ``` 95 | 96 | also can claculate azimuth you want 97 | 98 | ```cpp 99 | void loop(){ 100 | int x,y,z; 101 | int a; 102 | 103 | qmc.read(&x,&y,&z); 104 | a = qmc.azimuth(&y,&x); 105 | } 106 | ``` 107 | 108 | ## Basic example 109 | 110 | It can be seen as a collection of the contents mentioned above. 111 | 112 | ```cpp 113 | #include 114 | #include 115 | 116 | MechaQMC5883 qmc; 117 | 118 | void setup() { 119 | Wire.begin(); 120 | Serial.begin(9600); 121 | qmc.init(); 122 | //qmc.setMode(Mode_Continuous,ODR_200Hz,RNG_2G,OSR_256); 123 | } 124 | 125 | void loop() { 126 | int x,y,z; 127 | qmc.read(&x,&y,&z); 128 | 129 | Serial.print("x: "); 130 | Serial.print(x); 131 | Serial.print(" y: "); 132 | Serial.print(y); 133 | Serial.print(" z: "); 134 | Serial.print(z); 135 | Serial.println(); 136 | delay(100); 137 | } 138 | ``` 139 | -------------------------------------------------------------------------------- /k3ng_rotator_controller/rotator_debug_log_activation.h: -------------------------------------------------------------------------------- 1 | /* ---------------------- debug stuff - don't touch unless you know what you are doing --------------------------- */ 2 | 3 | 4 | 5 | #define DEFAULT_DEBUG_STATE 0 // 1 = activate debug mode at startup; this should be set to zero unless you're debugging something at startup 6 | 7 | // #define DEBUG_DUMP // normally compile with this activated unless you're really trying to save memory 8 | // #define DEBUG_LOOP 9 | // #define DEBUG_PROCESSES 10 | // #define DEBUG_BUTTONS 11 | // #define DEBUG_SERIAL 12 | // #define DEBUG_SERVICE_REQUEST_QUEUE 13 | // #define DEBUG_EEPROM 14 | // #define DEBUG_AZ_SPEED_POT 15 | // #define DEBUG_AZ_PRESET_POT 16 | // #define DEBUG_PRESET_ENCODERS 17 | // #define DEBUG_AZ_MANUAL_ROTATE_LIMITS 18 | // #define DEBUG_EL_MANUAL_ROTATE_LIMITS 19 | // #define DEBUG_BRAKE 20 | // #define DEBUG_OVERLAP 21 | // #define DEBUG_DISPLAY 22 | // #define DEBUG_AZ_CHECK_OPERATION_TIMEOUT 23 | // #define DEBUG_TIMED_BUFFER 24 | // #define DEBUG_EL_CHECK_OPERATION_TIMEOUT 25 | // #define DEBUG_VARIABLE_OUTPUTS 26 | // #define DEBUG_ROTATOR 27 | // #define DEBUG_SUBMIT_REQUEST 28 | // #define DEBUG_SERVICE_ROTATION 29 | // #define DEBUG_POSITION_ROTARY_ENCODER 30 | // #define DEBUG_POSITION_ROTARY_ENCODER_USE_PJRC_LIBRARY 31 | // #define DEBUG_PROFILE_LOOP_TIME 32 | // #define DEBUG_POSITION_PULSE_INPUT 33 | // #define DEBUG_ACCEL 34 | // #define DEBUG_SVC_REMOTE_COMM_INCOMING_BUFFER 35 | // #define DEBUG_SVC_REMOTE_COMM_INCOMING_BUFFER_BAD_DATA 36 | // #define DEBUG_HEADING_READING_TIME 37 | // #define DEBUG_JOYSTICK 38 | // #define DEBUG_ROTATION_INDICATION_PIN 39 | // #define DEBUG_HH12 40 | // #define DEBUG_PARK 41 | // #define DEBUG_LIMIT_SENSE 42 | // #define DEBUG_AZ_POSITION_INCREMENTAL_ENCODER 43 | // #define DEBUG_EL_POSITION_INCREMENTAL_ENCODER 44 | // #define DEBUG_MOON_TRACKING 45 | // #define DEBUG_SUN_TRACKING 46 | // #define DEBUG_GPS 47 | // #define DEBUG_GPS_SERIAL 48 | // #define DEBUG_OFFSET 49 | // #define DEBUG_RTC 50 | // #define DEBUG_PROCESS_YAESU 51 | // #define DEBUG_ETHERNET 52 | // #define DEBUG_PROCESS_SLAVE 53 | // #define DEBUG_MEMSIC_2125 54 | // #define DEBUG_SYNC_MASTER_CLOCK_TO_SLAVE 55 | // #define DEBUG_SYNC_MASTER_COORDINATES_TO_SLAVE 56 | // #define DEBUG_HMC5883L 57 | // #define DEBUG_POLOLU_LSM303_CALIBRATION 58 | // #define DEBUG_STEPPER 59 | // #define DEBUG_AUTOCORRECT 60 | // #define DEBUG_A2_ENCODER 61 | // #define DEBUG_A2_ENCODER_LOOPBACK_TEST 62 | // #define DEBUG_QMC5883 63 | // #define DEBUG_ROTATION_STALL_DETECTION 64 | // #define DEBUG_NEXTION_DISPLAY 65 | // #define DEBUG_NEXTION_DISPLAY_SERIAL_SEND 66 | // #define DEBUG_NEXTION_DISPLAY_SERIAL_RECV 67 | // #define DEBUG_NEXTION_DISPLAY_INIT // set DEFAULT_DEBUG_STATE to 1 above 68 | // #define DEBUG_TEST_POLAR_TO_CARTESIAN 69 | // #define DEBUG_SATELLITE_TRACKING 70 | // #define DEBUG_SATELLITE_TRACKING_LOAD 71 | // #define DEBUG_SATELLITE_TRACKING_CALC 72 | // #define DEBUG_SATELLITE_SERVICE 73 | // #define DEBUG_SATELLITE_TLE_EEPROM 74 | // #define DEBUG_SATELLITE_ARRAY_ORDER 75 | // #define DEBUG_SATELLITE_TRACKING_CALC_PROFILE 76 | // #define DEBUG_SATELLITE_POPULATE_LIST_ARRAY 77 | -------------------------------------------------------------------------------- /libraries/TimerOne/TimerOne.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Interrupt and PWM utilities for 16 bit Timer1 on ATmega168/328 3 | * Original code by Jesse Tane for http://labs.ideo.com August 2008 4 | * Modified March 2009 by Jérôme Despatis and Jesse Tane for ATmega328 support 5 | * Modified June 2009 by Michael Polli and Jesse Tane to fix a bug in setPeriod() which caused the timer to stop 6 | * Modified June 2011 by Lex Talionis to add a function to read the timer 7 | * Modified Oct 2011 by Andrew Richards to avoid certain problems: 8 | * - Add (long) assignments and casts to TimerOne::read() to ensure calculations involving tmp, ICR1 and TCNT1 aren't truncated 9 | * - Ensure 16 bit registers accesses are atomic - run with interrupts disabled when accessing 10 | * - Remove global enable of interrupts (sei())- could be running within an interrupt routine) 11 | * - Disable interrupts whilst TCTN1 == 0. Datasheet vague on this, but experiment shows that overflow interrupt 12 | * flag gets set whilst TCNT1 == 0, resulting in a phantom interrupt. Could just set to 1, but gets inaccurate 13 | * at very short durations 14 | * - startBottom() added to start counter at 0 and handle all interrupt enabling. 15 | * - start() amended to enable interrupts 16 | * - restart() amended to point at startBottom() 17 | * Modiied 7:26 PM Sunday, October 09, 2011 by Lex Talionis 18 | * - renamed start() to resume() to reflect it's actual role 19 | * - renamed startBottom() to start(). This breaks some old code that expects start to continue counting where it left off 20 | * 21 | * This program is free software: you can redistribute it and/or modify 22 | * it under the terms of the GNU General Public License as published by 23 | * the Free Software Foundation, either version 3 of the License, or 24 | * (at your option) any later version. 25 | * 26 | * This program is distributed in the hope that it will be useful, 27 | * but WITHOUT ANY WARRANTY; without even the implied warranty of 28 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 29 | * GNU General Public License for more details. 30 | * 31 | * You should have received a copy of the GNU General Public License 32 | * along with this program. If not, see . 33 | * 34 | * See Google Code project http://code.google.com/p/arduino-timerone/ for latest 35 | */ 36 | #ifndef TIMERONE_h 37 | #define TIMERONE_h 38 | 39 | #include 40 | #include 41 | 42 | #define RESOLUTION 65536 // Timer1 is 16 bit 43 | 44 | class TimerOne 45 | { 46 | public: 47 | 48 | // properties 49 | unsigned int pwmPeriod; 50 | unsigned char clockSelectBits; 51 | char oldSREG; // To hold Status Register while ints disabled 52 | 53 | // methods 54 | void initialize(long microseconds=1000000); 55 | void start(); 56 | void stop(); 57 | void restart(); 58 | void resume(); 59 | unsigned long read(); 60 | void pwm(char pin, int duty, long microseconds=-1); 61 | void disablePwm(char pin); 62 | void attachInterrupt(void (*isr)(), long microseconds=-1); 63 | void detachInterrupt(); 64 | void setPeriod(long microseconds); 65 | void setPwmDuty(char pin, int duty); 66 | void (*isrCallback)(); 67 | }; 68 | 69 | extern TimerOne Timer1; 70 | #endif -------------------------------------------------------------------------------- /libraries/FaBoLCD_PCF8574/FaBoLCD_PCF8574.h: -------------------------------------------------------------------------------- 1 | /** 2 | @file FaBoLCD_PCF8574.h 3 | @brief This is a library for the FaBo LCD I2C Brick. 4 | 5 | http://fabo.io/212.html 6 | 7 | Released under APACHE LICENSE, VERSION 2.0 8 | 9 | http://www.apache.org/licenses/ 10 | 11 | @author FaBo 12 | */ 13 | 14 | #ifndef FABOLCD_PCF8574_H 15 | #define FABOLCD_PCF8574_H 16 | 17 | #include 18 | #include 19 | #include "Print.h" 20 | 21 | #define PCF8574_SLAVE_ADDRESS 0x20 ///< PCF8574 Default I2C Slave Address 22 | 23 | // commands 24 | #define LCD_CLEARDISPLAY 0x01 25 | #define LCD_RETURNHOME 0x02 26 | #define LCD_ENTRYMODESET 0x04 27 | #define LCD_DISPLAYCONTROL 0x08 28 | #define LCD_CURSORSHIFT 0x10 29 | #define LCD_FUNCTIONSET 0x20 30 | #define LCD_SETCGRAMADDR 0x40 31 | #define LCD_SETDDRAMADDR 0x80 32 | 33 | // flags for display entry mode 34 | #define LCD_ENTRYRIGHT 0x00 35 | #define LCD_ENTRYLEFT 0x02 36 | #define LCD_ENTRYSHIFTINCREMENT 0x01 37 | #define LCD_ENTRYSHIFTDECREMENT 0x00 38 | 39 | // flags for display on/off control 40 | #define LCD_DISPLAYON 0x04 41 | #define LCD_DISPLAYOFF 0x00 42 | #define LCD_CURSORON 0x02 43 | #define LCD_CURSOROFF 0x00 44 | #define LCD_BLINKON 0x01 45 | #define LCD_BLINKOFF 0x00 46 | 47 | // flags for display/cursor shift 48 | #define LCD_DISPLAYMOVE 0x08 49 | #define LCD_CURSORMOVE 0x00 50 | #define LCD_MOVERIGHT 0x04 51 | #define LCD_MOVELEFT 0x00 52 | 53 | // flags for function set 54 | #define LCD_8BITMODE 0x10 55 | #define LCD_4BITMODE 0x00 56 | #define LCD_2LINE 0x08 57 | #define LCD_1LINE 0x00 58 | #define LCD_5x10DOTS 0x04 59 | #define LCD_5x8DOTS 0x00 60 | 61 | // pin/port bit 62 | #define RS B00000001 // P0 : RS bit 63 | #define RW B00000010 // P1 : R/W bit 64 | #define EN B00000100 // P2 : Enable bit 65 | #define BL B00001000 // P3 : BACKLIGHT bit 66 | #define DB4 B00010000 // P4 : DB4 bit 67 | #define DB5 B00100000 // P5 : DB5 bit 68 | #define DB6 B01000000 // P6 : DB6 bit 69 | #define DB7 B10000000 // P7 : DB7 bit 70 | 71 | /** 72 | @class FaBoLCDmini_AQM0802A 73 | @brief FaBo LCD I2C Controll class 74 | */ 75 | class FaBoLCD_PCF8574 : public Print { 76 | public: 77 | FaBoLCD_PCF8574(uint8_t addr = PCF8574_SLAVE_ADDRESS); 78 | void init(void); 79 | void begin(uint8_t cols, uint8_t rows, uint8_t charsize = LCD_5x8DOTS); 80 | 81 | void clear(); 82 | void home(); 83 | 84 | void noDisplay(); 85 | void display(); 86 | void noBlink(); 87 | void blink(); 88 | void noCursor(); 89 | void cursor(); 90 | void scrollDisplayLeft(); 91 | void scrollDisplayRight(); 92 | void leftToRight(); 93 | void rightToLeft(); 94 | void autoscroll(); 95 | void noAutoscroll(); 96 | 97 | void setRowOffsets(int row1, int row2, int row3, int row4); 98 | void createChar(uint8_t, uint8_t[]); 99 | void setCursor(uint8_t, uint8_t); 100 | virtual size_t write(uint8_t); 101 | void command(uint8_t); 102 | 103 | private: 104 | void send(uint8_t, uint8_t); 105 | void write4bits(uint8_t); 106 | void write8bits(uint8_t); 107 | void pulseEnable(uint8_t); 108 | void writeI2c(uint8_t); 109 | 110 | uint8_t _displayfunction; 111 | uint8_t _displaycontrol; 112 | uint8_t _displaymode; 113 | 114 | uint8_t _numlines; 115 | uint8_t _row_offsets[4]; 116 | 117 | uint8_t _i2caddr; 118 | uint8_t _backlight; 119 | }; 120 | 121 | #endif // FABOLCD_PCF8574_H 122 | -------------------------------------------------------------------------------- /libraries/HMC5883L/HMC5883L.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | HMC5883L.cpp - Class file for the HMC5883L Triple Axis Magnetometer Arduino Library. 3 | Copyright (C) 2011 Love Electronics (loveelectronics.co.uk)/ 2012 bildr.org (Arduino 1.0 compatible) 4 | 5 | This program is free software: you can redistribute it and/or modify 6 | it under the terms of the version 3 GNU General Public License as 7 | published by the Free Software Foundation. 8 | 9 | This program is distributed in the hope that it will be useful, 10 | but WITHOUT ANY WARRANTY; without even the implied warranty of 11 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 12 | GNU General Public License for more details. 13 | 14 | You should have received a copy of the GNU General Public License 15 | along with this program. If not, see . 16 | 17 | WARNING: THE HMC5883L IS NOT IDENTICAL TO THE HMC5883! 18 | Datasheet for HMC5883L: 19 | http://www51.honeywell.com/aero/common/documents/myaerospacecatalog-documents/Defense_Brochures-documents/HMC5883L_3-Axis_Digital_Compass_IC.pdf 20 | 21 | */ 22 | 23 | #include 24 | #include "HMC5883L.h" 25 | 26 | HMC5883L::HMC5883L() 27 | { 28 | m_Scale = 1; 29 | } 30 | 31 | MagnetometerRaw HMC5883L::ReadRawAxis() 32 | { 33 | uint8_t* buffer = Read(DataRegisterBegin, 6); 34 | MagnetometerRaw raw = MagnetometerRaw(); 35 | raw.XAxis = (buffer[0] << 8) | buffer[1]; 36 | raw.ZAxis = (buffer[2] << 8) | buffer[3]; 37 | raw.YAxis = (buffer[4] << 8) | buffer[5]; 38 | return raw; 39 | } 40 | 41 | MagnetometerScaled HMC5883L::ReadScaledAxis() 42 | { 43 | MagnetometerRaw raw = ReadRawAxis(); 44 | MagnetometerScaled scaled = MagnetometerScaled(); 45 | scaled.XAxis = raw.XAxis * m_Scale; 46 | scaled.ZAxis = raw.ZAxis * m_Scale; 47 | scaled.YAxis = raw.YAxis * m_Scale; 48 | return scaled; 49 | } 50 | 51 | int HMC5883L::SetScale(float gauss) 52 | { 53 | uint8_t regValue = 0x00; 54 | if(gauss == 0.88) 55 | { 56 | regValue = 0x00; 57 | m_Scale = 0.73; 58 | } 59 | else if(gauss == 1.3) 60 | { 61 | regValue = 0x01; 62 | m_Scale = 0.92; 63 | } 64 | else if(gauss == 1.9) 65 | { 66 | regValue = 0x02; 67 | m_Scale = 1.22; 68 | } 69 | else if(gauss == 2.5) 70 | { 71 | regValue = 0x03; 72 | m_Scale = 1.52; 73 | } 74 | else if(gauss == 4.0) 75 | { 76 | regValue = 0x04; 77 | m_Scale = 2.27; 78 | } 79 | else if(gauss == 4.7) 80 | { 81 | regValue = 0x05; 82 | m_Scale = 2.56; 83 | } 84 | else if(gauss == 5.6) 85 | { 86 | regValue = 0x06; 87 | m_Scale = 3.03; 88 | } 89 | else if(gauss == 8.1) 90 | { 91 | regValue = 0x07; 92 | m_Scale = 4.35; 93 | } 94 | else 95 | return ErrorCode_1_Num; 96 | 97 | // Setting is in the top 3 bits of the register. 98 | regValue = regValue << 5; 99 | Write(ConfigurationRegisterB, regValue); 100 | } 101 | 102 | int HMC5883L::SetMeasurementMode(uint8_t mode) 103 | { 104 | Write(ModeRegister, mode); 105 | } 106 | 107 | void HMC5883L::Write(int address, int data) 108 | { 109 | Wire.beginTransmission(HMC5883L_Address); 110 | Wire.write(address); 111 | Wire.write(data); 112 | Wire.endTransmission(); 113 | } 114 | 115 | uint8_t* HMC5883L::Read(int address, int length) 116 | { 117 | Wire.beginTransmission(HMC5883L_Address); 118 | Wire.write(address); 119 | Wire.endTransmission(); 120 | 121 | Wire.beginTransmission(HMC5883L_Address); 122 | Wire.requestFrom(HMC5883L_Address, length); 123 | 124 | uint8_t buffer[length]; 125 | if(Wire.available() == length) 126 | { 127 | for(uint8_t i = 0; i < length; i++) 128 | { 129 | buffer[i] = Wire.read(); 130 | } 131 | } 132 | Wire.endTransmission(); 133 | 134 | return buffer; 135 | } 136 | 137 | char* HMC5883L::GetErrorText(int errorCode) 138 | { 139 | if(ErrorCode_1_Num == 1) 140 | return ErrorCode_1; 141 | 142 | return "Error not defined."; 143 | } -------------------------------------------------------------------------------- /k3ng_rotator_controller/rotator_features_ea4tx_ars_usb.h: -------------------------------------------------------------------------------- 1 | /* ---------------------- EA4TX ARS USB Features and Options - you must configure this if using HARDWARE_EA4TX_ARS_USB !! ------------------------------------------------*/ 2 | 3 | /* main features */ 4 | //#define FEATURE_ELEVATION_CONTROL // uncomment this for AZ/EL rotators 5 | #define FEATURE_YAESU_EMULATION // uncomment this for Yaesu GS-232 emulation on control port 6 | //#define FEATURE_EASYCOM_EMULATION // Easycom protocol emulation on control port 7 | //#define FEATURE_DCU_1_EMULATION // DCU-1 protocol emulation on control port 8 | 9 | #define LANGUAGE_ENGLISH // all languages customized in rotator_language.h 10 | //#define LANGUAGE_SPANISH 11 | //#define LANGUAGE_CZECH 12 | //#define LANGUAGE_ITALIAN 13 | //#define LANGUAGE_PORTUGUESE_BRASIL 14 | //#define LANGUAGE_GERMAN 15 | //#define LANGUAGE_FRENCH 16 | //#define LANGUAGE_DUTCH 17 | 18 | //#define FEATURE_TEST_DISPLAY_AT_STARTUP 19 | 20 | //#define FEATURE_SATELLITE_TRACKING // https://github.com/k3ng/k3ng_rotator_controller/wiki/707-Satellite-Tracking 21 | 22 | #define FEATURE_AZ_POSITION_POTENTIOMETER //this is used for both a voltage from a rotator control or a homebrew rotator with a potentiometer 23 | 24 | #define FEATURE_EL_POSITION_POTENTIOMETER 25 | 26 | #define FEATURE_4_BIT_LCD_DISPLAY //Uncomment for classic 4 bit LCD display (most common) 27 | 28 | // #define FEATURE_AUDIBLE_ALERT 29 | 30 | 31 | /* less often used features and options */ 32 | #define OPTION_GS_232B_EMULATION // comment this out to default to Yaesu GS-232A emulation when using FEATURE_YAESU_EMULATION above 33 | //#define FEATURE_ROTATION_INDICATOR_PIN // activate rotation_indication_pin to indicate rotation 34 | //#define FEATURE_LIMIT_SENSE 35 | //#define FEATURE_TIMED_BUFFER // Support for Yaesu timed buffer commands 36 | //#define OPTION_SERIAL_HELP_TEXT // Yaesu help command prints help 37 | //#define FEATURE_PARK 38 | //#define FEATURE_AUTOPARK // Requires FEATURE_PARK 39 | //#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) 40 | //#define OPTION_EL_MANUAL_ROTATE_LIMITS 41 | //#define OPTION_C_COMMAND_SENDS_AZ_AND_EL // uncomment this when using Yaesu emulation with Ham Radio Deluxe 42 | //#define OPTION_DELAY_C_CMD_OUTPUT // uncomment this when using Yaesu emulation with Ham Radio Deluxe 43 | //#define FEATURE_ONE_DECIMAL_PLACE_HEADINGS 44 | //#define FEATURE_AZIMUTH_CORRECTION // correct the azimuth using a calibration table below 45 | //#define FEATURE_ELEVATION_CORRECTION // correct the elevation using a calibration table below 46 | //#define FEATURE_ANCILLARY_PIN_CONTROL // control I/O pins with serial commands \F, \N, \P 47 | //#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 48 | //#define OPTION_BUTTON_RELEASE_NO_SLOWDOWN // disables slowdown when CW or CCW button is released, or stop button is depressed 49 | //#define FEATURE_POWER_SWITCH 50 | //#define OPTION_EXTERNAL_ANALOG_REFERENCE //Activate external analog voltage reference (needed for RemoteQTH.com unit) 51 | #define OPTION_DISPLAY_DIRECTION_STATUS 52 | #define OPTION_SAVE_MEMORY_EXCLUDE_EXTENDED_COMMANDS 53 | //#define OPTION_SAVE_MEMORY_EXCLUDE_BACKSLASH_CMDS 54 | //#define OPTION_GPS_DO_PORT_FLUSHES 55 | //#define OPTION_DONT_READ_GPS_PORT_AS_OFTEN 56 | //#define OPTION_SEND_STRING_OUT_CONTROL_PORT_WHEN_INITIALIZING // change OPTION_SEND_STRING_OUT_CONTROL_PORT_WHEN_INITIALIZING_STRING in settings file 57 | //#define OPTION_GPS_EXCLUDE_MISSING_LF_CR_HANDLING 58 | //#define OPTION_MORE_SERIAL_CHECKS 59 | //#define OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE 60 | //#define OPTION_ALLOW_ROTATIONAL_AND_CONFIGURATION_CMDS_AT_BOOT_UP // if disabled, rotational and configuration commands will be ignored on the serial port for the first 10 second after boot up 61 | -------------------------------------------------------------------------------- /libraries/TimerOne/examples/ReadReciver/ReadReciver.pde: -------------------------------------------------------------------------------- 1 | /* 2 | Copyright 2011 Lex Talionis (Lex.V.Talionis at gmail) 3 | This program is free software: you can redistribute it 4 | and/or modify it under the terms of the GNU General Public 5 | License as published by the Free Software Foundation, 6 | either version 3 of the License, or (at your option) any 7 | later version. 8 | 9 | This uses pin change interrupts and timer 1 to mesure the 10 | time between the rise and fall of 3 channels of PPM 11 | (Though often called PWM, see http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1253149521/all) 12 | on a typical RC car reciver. It could be extended to as 13 | many channels as you like. 14 | 15 | */ 16 | #include // http://www.arduino.cc/playground/Main/PinChangeInt 17 | #include 18 | #include // http://www.arduino.cc/playground/Code/Timer1 19 | 20 | #define NO_PORTB_PINCHANGES //PinChangeInt setup 21 | #define NO_PORTC_PINCHANGES //only port D pinchanges (see: http://www.arduino.cc/playground/Learning/Pins) 22 | #define PIN_COUNT 3 //number of channels attached to the reciver 23 | #define MAX_PIN_CHANGE_PINS PIN_COUNT 24 | 25 | #define RC_TURN 3 //arduino pins attached to the reciver 26 | #define RC_FWD 2 27 | #define RC_FIRE 4 28 | byte pin[] = {RC_FWD, RC_TURN, RC_FIRE}; //for maximum efficency thise pins should be attached 29 | unsigned int time[] = {0,0,0}; // to the reciver's channels in the order listed here 30 | 31 | byte state=0; 32 | byte burp=0; // a counter to see how many times the int has executed 33 | byte cmd=0; // a place to put our serial data 34 | byte i=0; // global counter for tracking what pin we are on 35 | 36 | void setup() { 37 | Serial.begin(115200); 38 | Serial.print("PinChangeInt ReciverReading test"); 39 | Serial.println(); //warm up the serial port 40 | 41 | Timer1.initialize(2200); //longest pulse in PPM is usally 2.1 milliseconds, 42 | //pick a period that gives you a little headroom. 43 | Timer1.stop(); //stop the counter 44 | Timer1.restart(); //set the clock to zero 45 | 46 | for (byte i=0; i<3; i++) 47 | { 48 | pinMode(pin[i], INPUT); //set the pin to input 49 | digitalWrite(pin[i], HIGH); //use the internal pullup resistor 50 | } 51 | PCintPort::attachInterrupt(pin[i], rise,RISING); // attach a PinChange Interrupt to our first pin 52 | } 53 | 54 | void loop() { 55 | 56 | cmd=Serial.read(); //while you got some time gimme a systems report 57 | if (cmd=='p') 58 | { 59 | Serial.print("time:\t"); 60 | for (byte i=0; i // http://www.arduino.cc/playground/Main/PinChangeInt 17 | #include 18 | #include // http://www.arduino.cc/playground/Code/Timer1 19 | 20 | #define NO_PORTB_PINCHANGES //PinChangeInt setup 21 | #define NO_PORTC_PINCHANGES //only port D pinchanges (see: http://www.arduino.cc/playground/Learning/Pins) 22 | #define PIN_COUNT 3 //number of channels attached to the reciver 23 | #define MAX_PIN_CHANGE_PINS PIN_COUNT 24 | 25 | #define RC_TURN 3 //arduino pins attached to the reciver 26 | #define RC_FWD 2 27 | #define RC_FIRE 4 28 | byte pin[] = {RC_FWD, RC_TURN, RC_FIRE}; //for maximum efficency thise pins should be attached 29 | unsigned int time[] = {0,0,0}; // to the reciver's channels in the order listed here 30 | 31 | byte state=0; 32 | byte burp=0; // a counter to see how many times the int has executed 33 | byte cmd=0; // a place to put our serial data 34 | byte i=0; // global counter for tracking what pin we are on 35 | 36 | void setup() { 37 | Serial.begin(115200); 38 | Serial.print("PinChangeInt ReciverReading test"); 39 | Serial.println(); //warm up the serial port 40 | 41 | Timer1.initialize(2200); //longest pulse in PPM is usally 2.1 milliseconds, 42 | //pick a period that gives you a little headroom. 43 | Timer1.stop(); //stop the counter 44 | Timer1.restart(); //set the clock to zero 45 | 46 | for (byte i=0; i<3; i++) 47 | { 48 | pinMode(pin[i], INPUT); //set the pin to input 49 | digitalWrite(pin[i], HIGH); //use the internal pullup resistor 50 | } 51 | PCintPort::attachInterrupt(pin[i], rise,RISING); // attach a PinChange Interrupt to our first pin 52 | } 53 | 54 | void loop() { 55 | 56 | cmd=Serial.read(); //while you got some time gimme a systems report 57 | if (cmd=='p') 58 | { 59 | Serial.print("time:\t"); 60 | for (byte i=0; i 2 | #include 3 | #include "ST7036.h" 4 | #include "LCD_C0220BiZ.h" 5 | 6 | // ???:fmalpartida:20110821 7 | 8 | /*! 9 | @defined CHAR_WIDTH 10 | @abstract Character witdth of the display, expressed in pixeles per character. 11 | */ 12 | #define CHAR_WIDTH 5 13 | 14 | /*! 15 | @defined LDR_PIN 16 | @abstract Light Detection Resistor Analog pin. 17 | @discussion Define the Analog channel that will be used to read a LDR. 18 | */ 19 | #define LDR_PIN 7 20 | 21 | 22 | extern unsigned int __bss_end; 23 | extern unsigned int __heap_start; 24 | extern void *__brkval; 25 | 26 | 27 | //LCD_C0220BIZ lcd = LCD_C0220BIZ ( ); 28 | ST7036 lcd = ST7036 ( 2, 20, 0x78 ); 29 | 30 | 31 | /*! 32 | @const charBitmap 33 | @abstract Define Character bitmap for the bargraph. 34 | @discussion Defines a character bitmap to represent a bargraph on a text 35 | display. The bitmap goes from a blank character to full black. 36 | */ 37 | const uint8_t charBitmap[][8] = { 38 | { 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0 }, 39 | { 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x0 }, 40 | { 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x0 }, 41 | { 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x0 }, 42 | { 0x1E, 0x1E, 0x1E, 0x1E, 0x1E, 0x1E, 0x1E, 0x0 }, 43 | { 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x0 } 44 | }; 45 | 46 | /*! 47 | @function 48 | @abstract Return available RAM memory 49 | @discussion This routine returns the ammount of RAM memory available after 50 | initialising the C runtime. 51 | @param 52 | @result Free RAM available. 53 | */ 54 | 55 | static int freeMemory() 56 | { 57 | int free_memory; 58 | 59 | if((int)__brkval == 0) 60 | free_memory = ((int)&free_memory) - ((int)&__bss_end); 61 | else 62 | free_memory = ((int)&free_memory) - ((int)__brkval); 63 | 64 | return free_memory; 65 | } 66 | 67 | 68 | /*! 69 | @function 70 | @abstract Braws a bargraph onto the display representing the value passed. 71 | @discussion Draws a bargraph on the specified row using barLength characters. 72 | @param value[in] Value to represent in the bargraph 73 | @param row[in] Row of the LCD where to display the bargraph. Range (0, 1) 74 | for this display. 75 | @param barlength[in] Length of the bar, expressed in display characters. 76 | @param start[in] Start bar character 77 | @param end [in] End bar character 78 | 79 | @result None 80 | */ 81 | static void drawBars ( int value, uint8_t row, uint8_t barLength, char start, 82 | char end ) 83 | { 84 | int numBars; 85 | 86 | // Set initial titles on the display 87 | lcd.setCursor (row, 0); 88 | lcd.print (start); 89 | 90 | // Calculate the size of the bar 91 | value = map ( value, 0, 1024, 0, ( barLength - 1) * CHAR_WIDTH ); 92 | numBars = value / CHAR_WIDTH; 93 | 94 | lcd.setCursor ( row,2 ); 95 | 96 | // Draw the bars 97 | while ( numBars-- ) 98 | { 99 | lcd.print ( char( (sizeof(charBitmap ) / sizeof(charBitmap[0])) - 1 ) ); 100 | } 101 | 102 | // Draw the fractions 103 | numBars = value % CHAR_WIDTH; 104 | lcd.print ( char(numBars) ); 105 | lcd.setCursor (row, barLength + 1); 106 | lcd.print ( " " ); 107 | lcd.print (end); 108 | 109 | } 110 | 111 | void setup () 112 | { 113 | int i; 114 | int charBitmapSize = (sizeof(charBitmap ) / sizeof (charBitmap[0])); 115 | 116 | Serial.begin ( 57600 ); 117 | analogReference ( DEFAULT ); 118 | pinMode ( LDR_PIN, INPUT ); 119 | lcd.init (); 120 | lcd.setContrast(10); 121 | 122 | // Load custom character set into CGRAM 123 | for ( i = 0; i < charBitmapSize; i++ ) 124 | { 125 | lcd.load_custom_character ( i, (uint8_t *)charBitmap[i] ); 126 | } 127 | Serial.println ( freeMemory () ); 128 | } 129 | 130 | 131 | void loop () 132 | { 133 | int lightLevel; 134 | 135 | lcd.clear (); 136 | lcd.print ("Light Level:"); 137 | lightLevel = analogRead (LDR_PIN); 138 | lcd.setCursor ( 1, 16 ); 139 | lcd.print ( lightLevel ); 140 | lcd.setCursor (1,0); 141 | drawBars ( lightLevel, 1, 12, '-', '+' ); 142 | delay (100); 143 | } 144 | -------------------------------------------------------------------------------- /libraries/TimerFive/TimerFive.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Interrupt and PWM utilities for 16 bit Timer5 on ATmega640/1280/2560 3 | * Original code by Jesse Tane for http://labs.ideo.com August 2008 4 | * Modified March 2009 by Jérôme Despatis and Jesse Tane for ATmega328 support 5 | * Modified June 2009 by Michael Polli and Jesse Tane to fix a bug in setPeriod() which caused the timer to stop 6 | * Modified Oct 2009 by Dan Clemens to work with timer3 of the ATMega1280 or Arduino Mega 7 | * Modified Aug 2011 by RobotFreak to work with timer5 of the ATMega640/1280/2560 or Arduino Mega/ADK 8 | * 9 | * This is free software. You can redistribute it and/or modify it under 10 | * the terms of Creative Commons Attribution 3.0 United States License. 11 | * To view a copy of this license, visit http://creativecommons.org/licenses/by/3.0/us/ 12 | * or send a letter to Creative Commons, 171 Second Street, Suite 300, San Francisco, California, 94105, USA. 13 | * 14 | */ 15 | 16 | #include "TimerFive.h" 17 | 18 | TimerFive Timer5; // preinstatiate 19 | 20 | ISR(TIMER5_OVF_vect) // interrupt service routine that wraps a user defined function supplied by attachInterrupt 21 | { 22 | Timer5.isrCallback(); 23 | } 24 | 25 | void TimerFive::initialize(long microseconds) 26 | { 27 | TCCR5A = 0; // clear control register A 28 | TCCR5B = _BV(WGM53); // set mode as phase and frequency correct pwm, stop the timer 29 | setPeriod(microseconds); 30 | } 31 | 32 | void TimerFive::setPeriod(long microseconds) 33 | { 34 | long cycles = (F_CPU * microseconds) / 2000000; // the counter runs backwards after TOP, interrupt is at BOTTOM so divide microseconds by 2 35 | if(cycles < RESOLUTION) clockSelectBits = _BV(CS50); // no prescale, full xtal 36 | else if((cycles >>= 3) < RESOLUTION) clockSelectBits = _BV(CS51); // prescale by /8 37 | else if((cycles >>= 3) < RESOLUTION) clockSelectBits = _BV(CS51) | _BV(CS50); // prescale by /64 38 | else if((cycles >>= 2) < RESOLUTION) clockSelectBits = _BV(CS52); // prescale by /256 39 | else if((cycles >>= 2) < RESOLUTION) clockSelectBits = _BV(CS52) | _BV(CS50); // prescale by /1024 40 | else cycles = RESOLUTION - 1, clockSelectBits = _BV(CS52) | _BV(CS50); // request was out of bounds, set as maximum 41 | ICR5 = pwmPeriod = cycles; // ICR1 is TOP in p & f correct pwm mode 42 | TCCR5B &= ~(_BV(CS50) | _BV(CS51) | _BV(CS52)); 43 | TCCR5B |= clockSelectBits; // reset clock select register 44 | } 45 | 46 | void TimerFive::setPwmDuty(char pin, int duty) 47 | { 48 | unsigned long dutyCycle = pwmPeriod; 49 | dutyCycle *= duty; 50 | dutyCycle >>= 10; 51 | if(pin == 46) OCR5A = dutyCycle; 52 | if(pin == 45) OCR5B = dutyCycle; 53 | if(pin == 44) OCR5C = dutyCycle; 54 | } 55 | 56 | void TimerFive::pwm(char pin, int duty, long microseconds) // expects duty cycle to be 10 bit (1024) 57 | { 58 | if(microseconds > 0) setPeriod(microseconds); 59 | 60 | // sets data direction register for pwm output pin 61 | // activates the output pin 62 | if(pin == 46) { DDRE |= _BV(PORTL3); TCCR5A |= _BV(COM5A1); } 63 | if(pin == 45) { DDRE |= _BV(PORTL4); TCCR5A |= _BV(COM5B1); } 64 | if(pin == 44) { DDRE |= _BV(PORTL5); TCCR5A |= _BV(COM5C1); } 65 | setPwmDuty(pin, duty); 66 | start(); 67 | } 68 | 69 | void TimerFive::disablePwm(char pin) 70 | { 71 | if(pin == 46) TCCR5A &= ~_BV(COM5A1); // clear the bit that enables pwm on PE3 72 | if(pin == 45) TCCR5A &= ~_BV(COM5B1); // clear the bit that enables pwm on PE4 73 | if(pin == 44) TCCR5A &= ~_BV(COM5C1); // clear the bit that enables pwm on PE5 74 | } 75 | 76 | void TimerFive::attachInterrupt(void (*isr)(), long microseconds) 77 | { 78 | if(microseconds > 0) setPeriod(microseconds); 79 | isrCallback = isr; // register the user's callback with the real ISR 80 | TIMSK5 = _BV(TOIE5); // sets the timer overflow interrupt enable bit 81 | sei(); // ensures that interrupts are globally enabled 82 | start(); 83 | } 84 | 85 | void TimerFive::detachInterrupt() 86 | { 87 | TIMSK5 &= ~_BV(TOIE5); // clears the timer overflow interrupt enable bit 88 | } 89 | 90 | void TimerFive::start() 91 | { 92 | TCCR5B |= clockSelectBits; 93 | } 94 | 95 | void TimerFive::stop() 96 | { 97 | TCCR5B &= ~(_BV(CS50) | _BV(CS51) | _BV(CS52)); // clears all clock selects bits 98 | } 99 | 100 | void TimerFive::restart() 101 | { 102 | TCNT5 = 0; 103 | } 104 | -------------------------------------------------------------------------------- /libraries/P13/README: -------------------------------------------------------------------------------- 1 | _ The Arduino n' Gameduino 2 | __ _ _ _ __ _ __| |_ Satellite Tracker 3 | / _` | ' \/ _` (_-< _| 4 | \__,_|_||_\__, /__/\__| Written by Mark VandeWettering, K6HX, 2011 5 | |___/ brainwagon@gmail.com 6 | 7 | 8 | Angst is an application that I wrote for the Arduino and Gameduino. It 9 | is being distributed under the so-called "2-class BSD License", which I 10 | think grants potential users the greatest possible freedom to integrate 11 | this code into their own projects. I would, however, consider it a great 12 | courtesy if you could email me and tell me about your project and how 13 | this code was used, just for my own continued personal gratification. 14 | 15 | Angst includes P13, a port of the Plan 13 algorithm, originally written 16 | by James Miller, G3RUH and documented here: 17 | 18 | http://www.amsat.org/amsat/articles/g3ruh/111.html 19 | 20 | Other implementations exist, even for embedded platforms, such as 21 | the qrpTracker library of Bruce Robertson, VE9QRP and G6LVB's PIC 22 | implementation that is part of his embedded satellite tracker. My own 23 | code was ported from a quick and dirty Python implementation of my own, 24 | and retains a bit of the object orientation that I imposed in that code. 25 | 26 | While the P13 library is reasonably independent and can be used in 27 | other applications, the remainder of the code is fairly specific to the 28 | particular hardware I had on hand: 29 | 30 | 1. The Gameduino 31 | 32 | James Bowman developed the Gameduino as an Arduino shield to 33 | generate sound and graphics which might have been typical of 34 | 8 bit computers of the 1980s. It consists of a Xilinx FPGA, 35 | programmed with a version of his J1 Forth processor, and 36 | generates video and sound. It is programmed from the Arduino 37 | using a simple set of commands sent over the I2C bus. 38 | 39 | You can find more information here: 40 | 41 | http://excamera.com/sphinx/gameduino/ 42 | 43 | 2. A DS1307 RTC 44 | 45 | Sparkfun has a Dallas Semiconductor DS1307 chip mounted on a 46 | handly little breakout board. I used this chip to keep track 47 | of time. It's not particularly great: it drifts by a couple 48 | of minutes a week in my prototype: a better and more accurate 49 | timepiece would enhance the usability of this prototype. I've 50 | considered using a GPS to keep track of time, that extension is 51 | left as an exercise for the motivated reader. 52 | 53 | 3. An AT24C1024 Serial EEPROM 54 | 55 | The ATMEGA328 used in the Arduino contains a mere 512 bytes of 56 | EEPROM. This is enough space to store a few satellites, but I 57 | wanted to have greater capacitity. So, I got some 128K byte 58 | EEPROMS for about $4 from digikey. Each one of these can store 59 | the data for about 750 satellites. My prototype just uses one, 60 | but it's possible to chain up to four of them together. 61 | 62 | 4. A Rotary Encoder 63 | 64 | The entire interface is driven from a single rotary encoder w/ 65 | a built in switch, similar to this one: 66 | 67 | http://www.sparkfun.com/products/9117 68 | 69 | The code turns on the necessary internal pullup resistors to 70 | allow it to be directly wired to the Arduino input pins. 71 | 72 | Currently the encoder is read in the polling main event loop. 73 | This means that quick motion of the encoder is not adequately 74 | tracked: consider this another exercise for the motivated 75 | reader. 76 | 77 | 78 | I hope you enjoy the code, and find it useful and/or informative! 79 | 80 | Copyright 2011, Mark VandeWettering. All rights reserved. 81 | 82 | Redistribution and use in source and binary forms, with or without 83 | modification, are permitted provided that the following conditions are 84 | met: 85 | 86 | 1. Redistributions of source code must retain the above copyright 87 | notice, this list of conditions and the following disclaimer. 88 | 89 | 2. Redistributions in binary form must reproduce the above copyright 90 | notice, this list of conditions and the following disclaimer 91 | in the documentation and/or other materials provided with the 92 | distribution. 93 | 94 | THIS SOFTWARE IS PROVIDED BY MARK VANDEWETTERING ''AS IS'' AND ANY 95 | EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 96 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 97 | PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL OR 98 | CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, 99 | EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, 100 | PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 101 | PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 102 | LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 103 | NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 104 | SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 105 | 106 | The views and conclusions contained in the software and documentation 107 | are those of the authors and should not be interpreted as representing 108 | official policies, either expressed or implied, of Mark VandeWettering 109 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # K3NG Rotator Controller 2 | 3 | ## Modify version for RemoteQTH USB rotator interface rev.4 4 | 5 | More in [wiki](https://remoteqth.com/w/doku.php?id=usb_rotator_interface_4) 6 | ![OI3](https://remoteqth.com/img/wiki-rot4-29.jpg) 7 | 8 | ## Introduction 9 | 10 | This is an Arduino-based rotator interface that interfaces a computer to a rotator or rotator controller, emulating the Yaesu GS-232A/B and Easycom protocols which are supported by a myriad of logging, contest, and control programs. It can be easily interfaced with commercial rotator control units. With the addition of a proper capacity power supply and several interface components such as relays, this unit could also serve as a total replacement for a rotator control unit or serve as the basis for a 100% homebrew rotation system. Several azimuth and elevation position sensors including potentiometers, rotary encoders, and I2C devices are supported. The code is very flexible, modular, and easy to read allowing intermediate and advanced experimenters and builders to customize it. 11 | 12 | ## Documentation 13 | 14 | Full documentation is located [here](https://github.com/k3ng/k3ng_rotator_controller/wiki). Please read it! Volunteers for maintaining documentation are needed. 15 | 16 | ## Features 17 | 18 | * Azimuth only and azimuth / elevation rotator support 19 | * Serial interface using the standard Arduino USB port 20 | * Control Port Protocol Support: 21 | * Yaesu GS-232A & GS-232B 22 | * Easycom 23 | * Support for position sensors: 24 | * Potentiometers / Analog Voltage 25 | * Rotary Encoders 26 | * Incremental Encoders 27 | * Pulse Output 28 | * HMC5883L digital compass 29 | * ADXL345 accelerometer 30 | * LSM303 digital compass and accelerometer 31 | * HH-12 / AS5045 32 | * A2 Absolute Encoder (under development) 33 | * LCD display (2 or 4 rows, at least 16 columns) 34 | * Can be interfaced with non-Yaesu rotators, including homebrew systems 35 | * Directional indication on LCD display (North, South, North Northwest, etc.) along with degrees 36 | * Intelligent automatic rotation (utilizes overlap on 450 degree rotators) 37 | * Support for both 360 degree and 450 degree azimuth rotators or any rotation capability up to 719 degrees 38 | * North Center and South Center support 39 | * Support for any starting point (fully clockwise) 40 | * Optional automatic azimuthal rotation slowdown feature when reaching target azimuth 41 | * Optional rotation smooth ramp up 42 | * Optional brake engage/disengage lines for azimuth and elevation 43 | * Buttons for manual rotation 44 | * Command timeout 45 | * Timed interval rotation 46 | * Overlap LED Indicator 47 | * Help screen 48 | * Speed Control, both single PWM output (compatible with Yaesu controllers) and dual PWM rotate CW and rotate CCW outputs and dual elevate up and elevate down outputs 49 | * Variable frequency outputs 50 | * Preset Control using either potentiometers or rotary encoders with optional preset start button 51 | * Speed Potentiometer 52 | * Manual Rotation Limits 53 | * Classic 4 bit, Adafruit I2C LCD, and Yourduino.com Display Support 54 | * Optional tenth of a degree support with Easycom protocol (i.e. 123.4 degrees) 55 | * Park button 56 | * Azimuth and elevation calibration tables 57 | * Host unit and Remote unit operation for remotely located sensors using two Arduinos or ATMega chips 58 | * Works with hamlib rotctl/rotcltd, HRD, N1MM, PST Rotator, and many more programs 59 | * Moon and Sun Tracking 60 | * GPS Interfacing 61 | * Realtime Clock Interfacing 62 | 63 | ## Acknowledgements 64 | 65 | John, W3SA, has tested on a Yaesu Az/El unit, contributed several updates to the elevation code, and tweaked the code for a 16 column LCD display. 66 | 67 | Anthony, M0UPU, [wrote about](http://ava.upuaut.net/?p=372) his rotator controller construction and is offering PC boards. 68 | 69 | Bent, OZ1CT, has contributed several ideas and feature requests, and performed testing. 70 | 71 | G4HSK has a [nice page documenting](http://radio.g4hsk.co.uk/2m-eme/rotator-controller/) his project using this code, the PstRotator control software, and a Yaesu G-5500 rotator. 72 | 73 | All trademarks mentioned on this page and in the code are property of their respective owners. 74 | 75 | ## DXpeditions 76 | 77 | I will donate parts, units, or specially customized software for DXpeditions. Email me at anthony dot good at gmail dot com. DX IS! 78 | 79 | ## Support and Feature Requests 80 | 81 | Please consult [this page](https://blog.radioartisan.com/support-for-k3ng-projects/) for support information. Feature requests and bugs are documented and tracked on [GitHub](https://github.com/k3ng/k3ng_rotator_controller/issues). 82 | 83 | Please note that I do this work in my spare time as I can and I am not a professional developer, however I play one on TV. I do my best to answer support requests, however I don’t like having to answer questions for items that are explained in the [documentation](https://github.com/k3ng/k3ng_rotator_controller/wiki). I do maintain a list of [feature requests](https://github.com/k3ng/k3ng_rotator_controller/issues). Development items are prioritized by me based on the level of difficulty and what I’m interested in. I welcome code contributions, code testing, bug reports, and any help you can provide. This can even be helping with [documentation](https://github.com/k3ng/k3ng_rotator_controller/wiki) or providing support to others on the [Radio Artisan discussion group](https://groups.yahoo.com/neo/groups/radioartisan/info). 84 | -------------------------------------------------------------------------------- /libraries/sunpos/sunpos.cpp: -------------------------------------------------------------------------------- 1 | // This file is available in electronic form at http://www.psa.es/sdg/sunpos.htm 2 | 3 | #include "sunpos.h" 4 | #include 5 | 6 | void sunpos(cTime udtTime,cLocation udtLocation, cSunCoordinates *udtSunCoordinates) 7 | { 8 | // Main variables 9 | double dElapsedJulianDays; 10 | double dDecimalHours; 11 | double dEclipticLongitude; 12 | double dEclipticObliquity; 13 | double dRightAscension; 14 | double dDeclination; 15 | 16 | // Auxiliary variables 17 | double dY; 18 | double dX; 19 | 20 | 21 | 22 | // Calculate difference in days between the current Julian Day 23 | // and JD 2451545.0, which is noon 1 January 2000 Universal Time 24 | { 25 | double dJulianDate; 26 | long int liAux1; 27 | long int liAux2; 28 | // Calculate time of the day in UT decimal hours 29 | dDecimalHours = udtTime.dHours + (udtTime.dMinutes 30 | + udtTime.dSeconds / 60.0 ) / 60.0; 31 | // Calculate current Julian Day 32 | liAux1 =(udtTime.iMonth-14)/12; 33 | liAux2=(1461*(udtTime.iYear + 4800 + liAux1))/4 + (367*(udtTime.iMonth 34 | - 2-12*liAux1))/12- (3*((udtTime.iYear + 4900 35 | + liAux1)/100))/4+udtTime.iDay-32075; 36 | 37 | // dJulianDate=(double)(liAux2)-0.5+dDecimalHours/24.0; 38 | // Calculate difference between current Julian Day and JD 2451545.0 39 | // dElapsedJulianDays = dJulianDate-2451545.0; 40 | 41 | // 140113 VE5VA 42 | // The original way of calculating elapsed Julian days required 43 | // more precision than is possible in a 32-bit float, so change 44 | // the order of the calculation to preserve the significant digits. 45 | liAux2 -= 2451545L; 46 | dElapsedJulianDays = (double)liAux2-0.5+dDecimalHours/24.0; 47 | } 48 | 49 | /* old Julian day calculation 50 | 51 | // Calculate difference in days between the current Julian Day 52 | // and JD 2451545.0, which is noon 1 January 2000 Universal Time 53 | { 54 | double dJulianDate; 55 | long int liAux1; 56 | long int liAux2; 57 | // Calculate time of the day in UT decimal hours 58 | dDecimalHours = udtTime.dHours + (udtTime.dMinutes 59 | + udtTime.dSeconds / 60.0 ) / 60.0; 60 | // Calculate current Julian Day 61 | liAux1 =(udtTime.iMonth-14)/12; 62 | liAux2=(1461*(udtTime.iYear + 4800 + liAux1))/4 + (367*(udtTime.iMonth 63 | - 2-12*liAux1))/12- (3*((udtTime.iYear + 4900 64 | + liAux1)/100))/4+udtTime.iDay-32075; 65 | dJulianDate=(double)(liAux2)-0.5+dDecimalHours/24.0; 66 | // Calculate difference between current Julian Day and JD 2451545.0 67 | dElapsedJulianDays = dJulianDate-2451545.0; 68 | } 69 | 70 | */ 71 | 72 | // Calculate ecliptic coordinates (ecliptic longitude and obliquity of the 73 | // ecliptic in radians but without limiting the angle to be less than 2*Pi 74 | // (i.e., the result may be greater than 2*Pi) 75 | { 76 | double dMeanLongitude; 77 | double dMeanAnomaly; 78 | double dOmega; 79 | dOmega=2.1429-0.0010394594*dElapsedJulianDays; 80 | dMeanLongitude = 4.8950630+ 0.017202791698*dElapsedJulianDays; // Radians 81 | dMeanAnomaly = 6.2400600+ 0.0172019699*dElapsedJulianDays; 82 | dEclipticLongitude = dMeanLongitude + 0.03341607*sin( dMeanAnomaly ) 83 | + 0.00034894*sin( 2*dMeanAnomaly )-0.0001134 84 | -0.0000203*sin(dOmega); 85 | dEclipticObliquity = 0.4090928 - 6.2140e-9*dElapsedJulianDays 86 | +0.0000396*cos(dOmega); 87 | } 88 | 89 | // Calculate celestial coordinates ( right ascension and declination ) in radians 90 | // but without limiting the angle to be less than 2*Pi (i.e., the result may be 91 | // greater than 2*Pi) 92 | { 93 | double dSin_EclipticLongitude; 94 | dSin_EclipticLongitude= sin( dEclipticLongitude ); 95 | dY = cos( dEclipticObliquity ) * dSin_EclipticLongitude; 96 | dX = cos( dEclipticLongitude ); 97 | dRightAscension = atan2( dY,dX ); 98 | if( dRightAscension < 0.0 ) dRightAscension = dRightAscension + TWOPI_SUNPOS; 99 | dDeclination = asin( sin( dEclipticObliquity )*dSin_EclipticLongitude ); 100 | } 101 | 102 | // Calculate local coordinates ( azimuth and zenith angle ) in degrees 103 | { 104 | double dGreenwichMeanSiderealTime; 105 | double dLocalMeanSiderealTime; 106 | double dLatitudeInRadians; 107 | double dHourAngle; 108 | double dCos_Latitude; 109 | double dSin_Latitude; 110 | double dCos_HourAngle; 111 | double dParallax; 112 | dGreenwichMeanSiderealTime = 6.6974243242 + 113 | 0.0657098283*dElapsedJulianDays 114 | + dDecimalHours; 115 | dLocalMeanSiderealTime = (dGreenwichMeanSiderealTime*15 116 | + udtLocation.dLongitude)*RAD_SUNPOS; 117 | dHourAngle = dLocalMeanSiderealTime - dRightAscension; 118 | dLatitudeInRadians = udtLocation.dLatitude*RAD_SUNPOS; 119 | dCos_Latitude = cos( dLatitudeInRadians ); 120 | dSin_Latitude = sin( dLatitudeInRadians ); 121 | dCos_HourAngle= cos( dHourAngle ); 122 | udtSunCoordinates->dZenithAngle = (acos( dCos_Latitude*dCos_HourAngle 123 | *cos(dDeclination) + sin( dDeclination )*dSin_Latitude)); 124 | dY = -sin( dHourAngle ); 125 | dX = tan( dDeclination )*dCos_Latitude - dSin_Latitude*dCos_HourAngle; 126 | udtSunCoordinates->dAzimuth = atan2( dY, dX ); 127 | if ( udtSunCoordinates->dAzimuth < 0.0 ) 128 | udtSunCoordinates->dAzimuth = udtSunCoordinates->dAzimuth + TWOPI_SUNPOS; 129 | udtSunCoordinates->dAzimuth = udtSunCoordinates->dAzimuth/RAD_SUNPOS; 130 | // Parallax Correction 131 | dParallax=(dEarthMeanRadius/dAstronomicalUnit) 132 | *sin(udtSunCoordinates->dZenithAngle); 133 | udtSunCoordinates->dZenithAngle=(udtSunCoordinates->dZenithAngle 134 | + dParallax)/RAD_SUNPOS; 135 | } 136 | } 137 | 138 | -------------------------------------------------------------------------------- /libraries/TinyGPS/TinyGPS.h: -------------------------------------------------------------------------------- 1 | /* 2 | TinyGPS - a small GPS library for Arduino providing basic NMEA parsing 3 | Based on work by and "distance_to" and "course_to" courtesy of Maarten Lamers. 4 | Suggestion to add satellites(), course_to(), and cardinal(), by Matt Monson. 5 | Precision improvements suggested by Wayne Holder. 6 | Copyright (C) 2008-2013 Mikal Hart 7 | All rights reserved. 8 | 9 | This library is free software; you can redistribute it and/or 10 | modify it under the terms of the GNU Lesser General Public 11 | License as published by the Free Software Foundation; either 12 | version 2.1 of the License, or (at your option) any later version. 13 | 14 | This library is distributed in the hope that it will be useful, 15 | but WITHOUT ANY WARRANTY; without even the implied warranty of 16 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 17 | Lesser General Public License for more details. 18 | 19 | You should have received a copy of the GNU Lesser General Public 20 | License along with this library; if not, write to the Free Software 21 | Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA 22 | */ 23 | 24 | #ifndef TinyGPS_h 25 | #define TinyGPS_h 26 | 27 | #if defined(ARDUINO) && ARDUINO >= 100 28 | #include "Arduino.h" 29 | #else 30 | #include "WProgram.h" 31 | #endif 32 | 33 | #include 34 | 35 | #define _GPS_VERSION 13 // software version of this library 36 | #define _GPS_MPH_PER_KNOT 1.15077945 37 | #define _GPS_MPS_PER_KNOT 0.51444444 38 | #define _GPS_KMPH_PER_KNOT 1.852 39 | #define _GPS_MILES_PER_METER 0.00062137112 40 | #define _GPS_KM_PER_METER 0.001 41 | // #define _GPS_NO_STATS 42 | 43 | class TinyGPS 44 | { 45 | public: 46 | enum { 47 | GPS_INVALID_AGE = 0xFFFFFFFF, GPS_INVALID_ANGLE = 999999999, 48 | GPS_INVALID_ALTITUDE = 999999999, GPS_INVALID_DATE = 0, 49 | GPS_INVALID_TIME = 0xFFFFFFFF, GPS_INVALID_SPEED = 999999999, 50 | GPS_INVALID_FIX_TIME = 0xFFFFFFFF, GPS_INVALID_SATELLITES = 0xFF, 51 | GPS_INVALID_HDOP = 0xFFFFFFFF 52 | }; 53 | 54 | static const float GPS_INVALID_F_ANGLE, GPS_INVALID_F_ALTITUDE, GPS_INVALID_F_SPEED; 55 | 56 | TinyGPS(); 57 | bool encode(char c); // process one character received from GPS 58 | TinyGPS &operator << (char c) {encode(c); return *this;} 59 | 60 | // lat/long in MILLIONTHs of a degree and age of fix in milliseconds 61 | // (note: versions 12 and earlier gave lat/long in 100,000ths of a degree. 62 | void get_position(long *latitude, long *longitude, unsigned long *fix_age = 0); 63 | 64 | // date as ddmmyy, time as hhmmsscc, and age in milliseconds 65 | void get_datetime(unsigned long *date, unsigned long *time, unsigned long *age = 0); 66 | 67 | // signed altitude in centimeters (from GPGGA sentence) 68 | inline long altitude() { return _altitude; } 69 | 70 | // course in last full GPRMC sentence in 100th of a degree 71 | inline unsigned long course() { return _course; } 72 | 73 | // speed in last full GPRMC sentence in 100ths of a knot 74 | inline unsigned long speed() { return _speed; } 75 | 76 | // satellites used in last full GPGGA sentence 77 | inline unsigned short satellites() { return _numsats; } 78 | 79 | // horizontal dilution of precision in 100ths 80 | inline unsigned long hdop() { return _hdop; } 81 | 82 | void f_get_position(float *latitude, float *longitude, unsigned long *fix_age = 0); 83 | void crack_datetime(int *year, byte *month, byte *day, 84 | byte *hour, byte *minute, byte *second, byte *hundredths = 0, unsigned long *fix_age = 0); 85 | float f_altitude(); 86 | float f_course(); 87 | float f_speed_knots(); 88 | float f_speed_mph(); 89 | float f_speed_mps(); 90 | float f_speed_kmph(); 91 | 92 | static int library_version() { return _GPS_VERSION; } 93 | 94 | static float distance_between (float lat1, float long1, float lat2, float long2); 95 | static float course_to (float lat1, float long1, float lat2, float long2); 96 | static const char *cardinal(float course); 97 | 98 | #ifndef _GPS_NO_STATS 99 | void stats(unsigned long *chars, unsigned short *good_sentences, unsigned short *failed_cs); 100 | #endif 101 | 102 | private: 103 | enum {_GPS_SENTENCE_GPGGA, _GPS_SENTENCE_GPRMC, _GPS_SENTENCE_OTHER}; 104 | 105 | // properties 106 | unsigned long _time, _new_time; 107 | unsigned long _date, _new_date; 108 | long _latitude, _new_latitude; 109 | long _longitude, _new_longitude; 110 | long _altitude, _new_altitude; 111 | unsigned long _speed, _new_speed; 112 | unsigned long _course, _new_course; 113 | unsigned long _hdop, _new_hdop; 114 | unsigned short _numsats, _new_numsats; 115 | 116 | unsigned long _last_time_fix, _new_time_fix; 117 | unsigned long _last_position_fix, _new_position_fix; 118 | 119 | // parsing state variables 120 | byte _parity; 121 | bool _is_checksum_term; 122 | char _term[15]; 123 | byte _sentence_type; 124 | byte _term_number; 125 | byte _term_offset; 126 | bool _gps_data_good; 127 | 128 | #ifndef _GPS_NO_STATS 129 | // statistics 130 | unsigned long _encoded_characters; 131 | unsigned short _good_sentences; 132 | unsigned short _failed_checksum; 133 | unsigned short _passed_checksum; 134 | #endif 135 | 136 | // internal utilities 137 | int from_hex(char a); 138 | unsigned long parse_decimal(); 139 | unsigned long parse_degrees(); 140 | bool term_complete(); 141 | bool gpsisdigit(char c) { return c >= '0' && c <= '9'; } 142 | long gpsatol(const char *str); 143 | int gpsstrcmp(const char *str1, const char *str2); 144 | }; 145 | 146 | #if !defined(ARDUINO) 147 | // Arduino 0012 workaround 148 | #undef int 149 | #undef char 150 | #undef long 151 | #undef byte 152 | #undef float 153 | #undef abs 154 | #undef round 155 | #endif 156 | 157 | #endif 158 | -------------------------------------------------------------------------------- /k3ng_rotator_controller/rotator_pins_ea4tx_ars_usb.h: -------------------------------------------------------------------------------- 1 | /* 2 | 3 | 4 | EA4TX ARS-USB Pin Definitions 5 | 6 | */ 7 | 8 | /* azimuth pins --------------------- (use just the azimuth pins for an azimuth-only rotator) */ 9 | 10 | #define rotate_cw 6 // goes high to activate rotator R (CW) rotation - pin 1 on Yaesu connector 11 | #define rotate_ccw 7 // goes high to activate rotator L (CCW) rotation - pin 2 on Yaesu connector 12 | #define button_cw A2 // normally open button to ground for manual CW rotation (schematic pin: A2) 13 | #define button_ccw A3 // normally open button to ground for manual CCW rotation (schematic pin: A3) 14 | #define serial_led 0 // LED blinks when command is received on serial port (set to 0 to disable) 15 | #define rotator_analog_az A0 // reads analog azimuth voltage from rotator - pin 4 on Yaesu connector 16 | #define brake_az 0 // goes high to disengage azimuth brake (set to 0 to disable) 17 | #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) 18 | 19 | 20 | /*----------- elevation pins --------------*/ 21 | #ifdef FEATURE_ELEVATION_CONTROL 22 | #define rotate_up 8 // goes high to activate rotator elevation up 23 | #define rotate_down 9 // goes high to activate rotator elevation down 24 | #define rotator_analog_el A1 // reads analog elevation voltage from rotator 25 | #define button_up A4 // normally open button to ground for manual up elevation 26 | #define button_down A5 // normally open button to ground for manual down rotation 27 | #define brake_el 0 // goes high to disengage elevation brake (set to 0 to disable) 28 | #endif //FEATURE_ELEVATION_CONTROL 29 | 30 | //classic 4 bit LCD pins 31 | #define lcd_4_bit_rs_pin 12 32 | #define lcd_4_bit_enable_pin 11 33 | #define lcd_4_bit_d4_pin 5 34 | #define lcd_4_bit_d5_pin 4 35 | #define lcd_4_bit_d6_pin 3 36 | #define lcd_4_bit_d7_pin 2 37 | 38 | 39 | // everything below this line is unused 40 | 41 | 42 | #ifdef FEATURE_PARK 43 | #define button_park 0 44 | #endif 45 | 46 | #ifdef FEATURE_PARK 47 | #define park_in_progress_pin 0 // goes high when a park has been initiated and rotation is in progress 48 | #define parked_pin 0 // goes high when in a parked position 49 | #endif //FEATURE_PARK 50 | 51 | #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 52 | 53 | #ifdef FEATURE_LIMIT_SENSE 54 | #define az_limit_sense_pin 0 // input - low stops azimuthal rotation 55 | #define el_limit_sense_pin 0 // input - low stops elevation rotation 56 | #endif //FEATURE_LIMIT_SENSE 57 | 58 | 59 | #ifdef FEATURE_POWER_SWITCH 60 | #define power_switch 0 // use with FEATURE_POWER_SWITCH 61 | #endif //FEATURE_POWER_SWITCH 62 | 63 | #define rotate_cw_ccw 0 // goes high for both CW and CCW rotation 64 | #define rotate_cw_pwm 0 // optional - PWM CW output - set to 0 to disable (must be PWM capable pin) 65 | #define rotate_ccw_pwm 0 // optional - PWM CCW output - set to 0 to disable (must be PWM capable pin) 66 | #define rotate_cw_ccw_pwm 0 // optional - PWM on CW and CCW output - set to 0 to disable (must be PWM capable pin) 67 | #define rotate_cw_freq 0 // optional - CW variable frequency output 68 | #define rotate_ccw_freq 0 // optional - CCW variable frequency output 69 | #define az_speed_pot 0 // connect to wiper of 1K to 10K potentiometer for speed control (set to 0 to disable) 70 | #define az_preset_pot 0 // connect to wiper of 1K to 10K potentiometer for preset control (set to 0 to disable) 71 | #define rotate_up_or_down 0 // goes high when elevation up or down is activated 72 | #define rotate_up_pwm 0 // optional - PWM UP output - set to 0 to disable (must be PWM capable pin) 73 | #define rotate_down_pwm 0 // optional - PWM DOWN output - set to 0 to disable (must be PWM capable pin) 74 | #define rotate_up_down_pwm 0 // optional - PWM on both UP and DOWN (must be PWM capable pin) 75 | #define rotate_up_freq 0 // optional - UP variable frequency output 76 | #define rotate_down_freq 0 // optional - UP variable frequency output 77 | #define az_stepper_motor_pulse 0 78 | #define az_stepper_motor_direction 0 79 | #define rotation_indication_pin 0 80 | #define blink_led 0 81 | #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) 82 | #define el_stepper_motor_pulse 0 83 | #define el_stepper_motor_direction 0 84 | #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) 85 | #define overlap_led 0 // line goes high when azimuth rotator is in overlap (> 360 rotators) 86 | #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) 87 | 88 | 89 | // #define pin_led_cw 0 90 | // #define pin_led_ccw 0 91 | // #define pin_led_up 0 92 | // #define pin_led_down 0 93 | 94 | #ifdef FEATURE_AUTOPARK 95 | #define pin_autopark_disable 0 // Pull low to disable autopark 96 | #define pin_autopark_timer_reset 0 // Pull low to reset the autopark timer (tie in with rig PTT) 97 | #endif 98 | 99 | #ifdef FEATURE_AUDIBLE_ALERT 100 | #define pin_audible_alert 0 101 | #endif 102 | 103 | //#define pin_status_led 0 // Status LED - blinks when there is rotation in progress 104 | 105 | // Added 2020.07.24.01 106 | #define satellite_tracking_active_pin 0 107 | #define satellite_tracking_activate_line 0 108 | #define satellite_tracking_button 0 // use with a normally open momentary switch to ground -------------------------------------------------------------------------------- /libraries/hh12/hh12.cpp: -------------------------------------------------------------------------------- 1 | #if defined(ARDUINO) && ARDUINO >= 100 2 | #include "Arduino.h" 3 | #else 4 | #include "WProgram.h" 5 | #endif 6 | #include "hh12.h" 7 | 8 | /* 9 | 10 | Code adapted from here: http://www.madscientisthut.com/forum_php/viewtopic.php?f=11&t=7 11 | 12 | Updated 2015-02-07 for 12 bit readings - Thanks Johan PA3FPQ 13 | Updated 2016-09-28 Created OPTION_HH12_DONT_GO_HI_END_OF_CYCLE 14 | 15 | 16 | */ 17 | 18 | //#define OPTION_HH12_DONT_GO_HI_END_OF_CYCLE // normally this should be commented out (disabled). Uncomment if you have problems with your HH12 19 | 20 | int hh12_clock_pin = 0; 21 | int hh12_cs_pin = 0; 22 | int hh12_data_pin = 0; 23 | 24 | int inputstream = 0; //one bit read from pin 25 | long packeddata = 0; //two bytes concatenated from inputstream 26 | long angle = 0; //holds processed angle value 27 | float floatangle = 0; 28 | #ifdef OPTION_HH12_10_BIT_READINGS 29 | long anglemask = 65472; //0x1111111111000000: mask to obtain first 10 digits with position info 30 | #else 31 | long anglemask = 262080; // 0x111111111111000000: mask to obtain first 12 digits with position info 32 | #endif //OPTION_HH12_10_BIT_READINGS 33 | long statusmask = 63; //0x000000000111111; mask to obtain last 6 digits containing status info 34 | long statusbits; //holds status/error information 35 | int DECn; //bit holding decreasing magnet field error data 36 | int INCn; //bit holding increasing magnet field error data 37 | int OCF; //bit holding startup-valid bit 38 | int COF; //bit holding cordic DSP processing error data 39 | int LIN; //bit holding magnet field displacement error data 40 | 41 | //----------------------------------------------------------------------------------------------------- 42 | hh12::hh12(){ 43 | 44 | 45 | } 46 | //----------------------------------------------------------------------------------------------------- 47 | void hh12::initialize(int _hh12_clock_pin, int _hh12_cs_pin, int _hh12_data_pin){ 48 | 49 | hh12_clock_pin = _hh12_clock_pin; 50 | hh12_cs_pin = _hh12_cs_pin; 51 | hh12_data_pin = _hh12_data_pin; 52 | 53 | pinMode(hh12_clock_pin, OUTPUT); 54 | pinMode(hh12_cs_pin, OUTPUT); 55 | pinMode(hh12_data_pin, INPUT); 56 | 57 | } 58 | 59 | //----------------------------------------------------------------------------------------------------- 60 | float hh12::heading(){ 61 | 62 | digitalWrite(hh12_cs_pin, HIGH); // CSn high 63 | digitalWrite(hh12_clock_pin, HIGH); // CLK high 64 | digitalWrite(hh12_cs_pin, LOW); // CSn low: start of transfer 65 | delayMicroseconds(HH12_DELAY); // delay for chip initialization 66 | digitalWrite(hh12_clock_pin, LOW); // CLK goes low: start clocking 67 | delayMicroseconds(HH12_DELAY); // hold low 68 | #ifdef OPTION_HH12_10_BIT_READINGS 69 | for (int x=0; x <16; x++) // clock signal, 16 transitions, output to clock pin 70 | #else 71 | for (int x=0; x <18; x++) // clock signal, 18 transitions, output to clock pin 72 | #endif //OPTION_HH12_10_BIT_READINGS 73 | { 74 | digitalWrite(hh12_clock_pin, HIGH); //clock goes high 75 | delayMicroseconds(HH12_DELAY); // 76 | inputstream =digitalRead(hh12_data_pin); // read one bit of data from pin 77 | #ifdef DEBUG_HH12 78 | Serial.print(inputstream, DEC); 79 | #endif 80 | packeddata = ((packeddata << 1) + inputstream);// left-shift summing variable, add pin value 81 | digitalWrite(hh12_clock_pin, LOW); 82 | delayMicroseconds(HH12_DELAY); // end of one clock cycle 83 | } 84 | // end of entire clock cycle 85 | 86 | #if !defined(OPTION_HH12_DONT_GO_HI_END_OF_CYCLE) 87 | digitalWrite(hh12_cs_pin, HIGH); // CSn high 88 | digitalWrite(hh12_clock_pin, HIGH); // CLK high 89 | #endif 90 | 91 | #ifdef DEBUG_HH12 92 | Serial.print("hh12: packed:"); 93 | Serial.println(packeddata,DEC); 94 | Serial.print("hh12: pack bin: "); 95 | Serial.println(packeddata,BIN); 96 | #endif 97 | 98 | angle = packeddata & anglemask; // mask rightmost 6 digits of packeddata to zero, into angle 99 | 100 | #ifdef DEBUG_HH12 101 | Serial.print("hh12: mask: "); 102 | Serial.println(anglemask, BIN); 103 | Serial.print("hh12: bin angle:"); 104 | Serial.println(angle, BIN); 105 | Serial.print("hh12: angle: "); 106 | Serial.println(angle, DEC); 107 | #endif 108 | 109 | angle = (angle >> 6); // shift 16-digit angle right 6 digits to form 10-digit value 110 | 111 | #ifdef DEBUG_HH12 112 | Serial.print("hh12: angleshft:"); 113 | Serial.println(angle, BIN); 114 | Serial.print("hh12: angledec: "); 115 | Serial.println(angle, DEC); 116 | #endif 117 | 118 | #ifdef OPTION_HH12_10_BIT_READINGS 119 | floatangle = angle * 0.3515; // angle * (360/1024) == actual degrees 120 | #else 121 | floatangle = angle * 0.08789; // angle * (360/4096) == actual degrees 122 | #endif //OPTION_HH12_10_BIT_READINGS 123 | 124 | #ifdef DEBUG_HH12 125 | statusbits = packeddata & statusmask; 126 | DECn = statusbits & 2; // goes high if magnet moved away from IC 127 | INCn = statusbits & 4; // goes high if magnet moved towards IC 128 | LIN = statusbits & 8; // goes high for linearity alarm 129 | COF = statusbits & 16; // goes high for cordic overflow: data invalid 130 | OCF = statusbits & 32; // this is 1 when the chip startup is finished 131 | if (DECn && INCn) { 132 | Serial.println("hh12: magnet moved out of range"); 133 | } else { 134 | if (DECn) { 135 | Serial.println("hh12: magnet moved away from chip"); 136 | } 137 | if (INCn) { 138 | Serial.println("hh12: magnet moved towards chip"); 139 | } 140 | } 141 | if (LIN) { 142 | Serial.println("hh12: linearity alarm: magnet misaligned? data questionable"); 143 | } 144 | if (COF) { 145 | Serial.println("hh12: cordic overflow: magnet misaligned? data invalid"); 146 | } 147 | #endif //DEBUG_HH12 148 | 149 | 150 | return(floatangle); 151 | 152 | 153 | } 154 | 155 | -------------------------------------------------------------------------------- /libraries/LCD_C0220BIZ/examples/lcd_c0220Biz_test/lcd_c0220Biz_test.ino: -------------------------------------------------------------------------------- 1 | #include 2 | #include "ST7036.h" 3 | #include "LCD_C0220BiZ.h" 4 | #include 5 | 6 | // ???:fmalpartida:20110821 7 | 8 | /*! 9 | @defined CHAR_WIDTH 10 | @abstract Character witdth of the display, expressed in pixeles per character. 11 | */ 12 | #define CHAR_WIDTH 5 13 | 14 | /*! 15 | @defined LDR_PIN 16 | @abstract Light Detection Resistor Analog pin. 17 | @discussion Define the Analog channel that will be used to read a LDR. 18 | */ 19 | #define LDR_PIN 7 20 | 21 | /*! 22 | @defined TEMP_CAL_OFFSET 23 | @abstract Temperature calibration offset. 24 | @discussion This is the offset value that has to be modified to get a 25 | correct temperature reading from the internal temperature sensor 26 | of your AVR. 27 | */ 28 | #define TEMP_CAL_OFFSET 335 29 | 30 | /*! 31 | @defined FILTER_ALP 32 | @abstract Low pass filter alpha value 33 | @discussion This value defines how much does the current reading, influences 34 | the over all value. The smaller, the less influence the current 35 | reading has over the overall result. 36 | */ 37 | #define FILTER_ALP 0.1 38 | 39 | extern unsigned int __bss_end; 40 | extern unsigned int __heap_start; 41 | extern void *__brkval; 42 | 43 | 44 | //LCD_C0220BIZ lcd = LCD_C0220BIZ ( ); 45 | ST7036 lcd = ST7036 ( 2, 20, 0x78 ); 46 | 47 | static double tempFilter; 48 | 49 | 50 | /*! 51 | @const charBitmap 52 | @abstract Define Character bitmap for the bargraph. 53 | @discussion Defines a character bitmap to represent a bargraph on a text 54 | display. The bitmap goes from a blank character to full black. 55 | */ 56 | const uint8_t charBitmap[][8] = { 57 | { 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0 }, 58 | { 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x0 }, 59 | { 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x0 }, 60 | { 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x0 }, 61 | { 0x1E, 0x1E, 0x1E, 0x1E, 0x1E, 0x1E, 0x1E, 0x0 }, 62 | { 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x0 } 63 | }; 64 | 65 | /*! 66 | @function 67 | @abstract Return available RAM memory 68 | @discussion This routine returns the ammount of RAM memory available after 69 | initialising the C runtime. 70 | @param 71 | @result Free RAM available. 72 | */ 73 | 74 | static int freeMemory() 75 | { 76 | int free_memory; 77 | 78 | if((int)__brkval == 0) 79 | free_memory = ((int)&free_memory) - ((int)&__bss_end); 80 | else 81 | free_memory = ((int)&free_memory) - ((int)__brkval); 82 | 83 | return free_memory; 84 | } 85 | 86 | /*! 87 | @function 88 | @abstract Returns AVR328p internal temperature 89 | @discussion Configures the ADC MUX for the temperature ADC channel and 90 | waits for conversion and returns the value of the ADC module 91 | @result The internal temperature reading - in degrees C 92 | */ 93 | 94 | static int readTemperature() 95 | { 96 | ADMUX = 0xC8; // activate interal temperature sensor, 97 | // using 1.1V ref. voltage 98 | ADCSRA |= _BV(ADSC); // start the conversion 99 | while (bit_is_set(ADCSRA, ADSC)); // ADSC is cleared when the conversion 100 | // finishes 101 | 102 | // combine bytes & correct for temperature offset (approximate) 103 | return ( (ADCL | (ADCH << 8)) - TEMP_CAL_OFFSET); 104 | } 105 | 106 | /*! 107 | @function 108 | @abstract Braws a bargraph onto the display representing the value passed. 109 | @discussion Draws a bargraph on the specified row using barLength characters. 110 | @param value[in] Value to represent in the bargraph 111 | @param row[in] Row of the LCD where to display the bargraph. Range (0, 1) 112 | for this display. 113 | @param barlength[in] Length of the bar, expressed in display characters. 114 | @param start[in] Start bar character 115 | @param end [in] End bar character 116 | 117 | @result None 118 | */ 119 | static void drawBars ( int value, uint8_t row, uint8_t barLength, char start, 120 | char end ) 121 | { 122 | int numBars; 123 | 124 | // Set initial titles on the display 125 | lcd.setCursor (row, 0); 126 | lcd.print (start); 127 | 128 | // Calculate the size of the bar 129 | value = map ( value, -20, 50, 0, ( barLength - 1) * CHAR_WIDTH ); 130 | numBars = value / CHAR_WIDTH; 131 | 132 | // Limit the size of the bargraph to barLength 133 | if ( numBars > barLength ) 134 | { 135 | numBars = barLength; 136 | } 137 | 138 | lcd.setCursor ( row,2 ); 139 | 140 | // Draw the bars 141 | while ( numBars-- ) 142 | { 143 | lcd.print ( char( (sizeof(charBitmap ) / sizeof(charBitmap[0])) - 1 ) ); 144 | } 145 | 146 | // Draw the fractions 147 | numBars = value % CHAR_WIDTH; 148 | lcd.print ( char(numBars) ); 149 | lcd.setCursor (row, barLength + 1); 150 | lcd.print ( " " ); 151 | lcd.print (end); 152 | 153 | } 154 | 155 | void setup () 156 | { 157 | int i; 158 | int charBitmapSize = (sizeof(charBitmap ) / sizeof (charBitmap[0])); 159 | 160 | Serial.begin ( 57600 ); 161 | analogReference ( INTERNAL ); 162 | pinMode ( LDR_PIN, INPUT ); 163 | lcd.init (); 164 | lcd.setContrast(10); 165 | 166 | // Load custom character set into CGRAM 167 | for ( i = 0; i < charBitmapSize; i++ ) 168 | { 169 | lcd.load_custom_character ( i, (uint8_t *)charBitmap[i] ); 170 | } 171 | Serial.println ( freeMemory () ); 172 | tempFilter = readTemperature(); // Initialise the temperature Filter 173 | } 174 | 175 | 176 | void loop () 177 | { 178 | int temp; 179 | 180 | temp = readTemperature(); 181 | tempFilter = ( FILTER_ALP * temp) + (( 1.0 - FILTER_ALP ) * tempFilter); 182 | 183 | lcd.clear (); 184 | lcd.setCursor ( 0, 0 ); 185 | lcd.print ("Temperature:"); 186 | lcd.setCursor ( 1, 15 ); 187 | lcd.print ( tempFilter, 1 ); 188 | lcd.setCursor (1,0); 189 | drawBars ( tempFilter, 1, 11, '-', '+' ); 190 | delay (100); 191 | } 192 | -------------------------------------------------------------------------------- /k3ng_rotator_controller/rotator_k3ngdisplay.h: -------------------------------------------------------------------------------- 1 | 2 | #ifndef _K3NGDISPLAY_H 3 | #define _K3NGDISPLAY_H 4 | 5 | #if defined(ARDUINO) && ARDUINO >= 100 6 | #include "Arduino.h" 7 | #else 8 | #include "WProgram.h" 9 | #endif 10 | 11 | /* 12 | 13 | 14 | Set the display type here !!!!!!!!! 15 | 16 | 17 | */ 18 | 19 | #define FEATURE_4_BIT_LCD_DISPLAY 20 | // #define FEATURE_ADAFRUIT_I2C_LCD 21 | // #define FEATURE_YOURDUINO_I2C_LCD 22 | // #define FEATURE_RFROBOT_I2C_DISPLAY 23 | // #define FEATURE_YWROBOT_I2C_DISPLAY 24 | // #define FEATURE_SAINSMART_I2C_LCD 25 | // #define FEATURE_ADAFRUIT_BUTTONS 26 | // #define FEATURE_MIDAS_I2C_DISPLAY 27 | // #define FEATURE_FABO_LCD_PCF8574_DISPLAY 28 | // #define FEATURE_HD44780_I2C_DISPLAY 29 | 30 | // #define OPTION_RFROBOT_I2C_DISPLAY_BACKLIGHT_OFF 31 | 32 | #include "rotator_hardware.h" 33 | 34 | #ifdef HARDWARE_EA4TX_ARS_USB 35 | #include "rotator_features_ea4tx_ars_usb.h" 36 | #endif 37 | #ifdef HARDWARE_WB6KCN 38 | #include "rotator_features_wb6kcn.h" 39 | #endif 40 | #ifdef HARDWARE_M0UPU 41 | #include "rotator_features_m0upu.h" 42 | #endif 43 | #ifdef HARDWARE_TEST 44 | #include "rotator_features_test.h" 45 | #endif 46 | #if !defined(HARDWARE_CUSTOM) 47 | #include "rotator_features.h" 48 | #endif 49 | 50 | #ifdef HARDWARE_EA4TX_ARS_USB 51 | #include "rotator_pins_ea4tx_ars_usb.h" 52 | #endif 53 | #ifdef HARDWARE_M0UPU 54 | #include "rotator_pins_m0upu.h" 55 | #endif 56 | #ifdef HARDWARE_WB6KCN 57 | #include "rotator_pins_wb6kcn.h" 58 | #endif 59 | #ifdef HARDWARE_TEST 60 | #include "rotator_pins_test.h" 61 | #endif 62 | #if !defined(HARDWARE_CUSTOM) 63 | #include "rotator_pins.h" 64 | #endif 65 | 66 | #if defined(FEATURE_ADAFRUIT_I2C_LCD) 67 | #include "rotator.h" 68 | #endif 69 | 70 | #define K3NG_DISPLAY_LIBRARY_VERSION "2020.03.16.01" 71 | #define MAX_SCREEN_BUFFER_COLUMNS 20 72 | #define MAX_SCREEN_BUFFER_ROWS 4 73 | 74 | #define ATTRIBUTE_BLINK B00000001 75 | 76 | #define TEXT_BLINK_MS 500 77 | #define WORK_STRING_SIZE 32 78 | 79 | #define I2C_LCD_COLOR WHITE // default color of I2C LCD display, including Adafruit and Yourduino; some Yourduino units may want this as LED_ON 80 | // #define I2C_LCD_COLOR GREEN 81 | // #define I2C_LCD_COLOR LED_ON 82 | 83 | class K3NGdisplay { 84 | 85 | public: 86 | 87 | K3NGdisplay(int display_columns, int display_rows, int _update_time); 88 | void initialize(); 89 | void service(uint8_t force_update_flag); // write pending changes to the screen periodically and blink text that has the blink attribute 90 | void clear(); // clear the display immediately 91 | void clear_pending_buffer(); 92 | void update(); // update pending changes to the screen 93 | void print(char * print_string); 94 | void print(char * print_string,int x,int y); 95 | void print(char * print_string,int x,int y, uint8_t text_attribute); 96 | void print_attribute(char * print_string, uint8_t text_attribute); 97 | void print_attribute(char * print_string,int x,int y, uint8_t text_attribute); 98 | void print_center(char * print_string,int y); 99 | void print_center_padded(char * print_string,int y,int padding); 100 | void print_center_fixed_field_size(char * print_string,int y,int field_size); 101 | void print_center_entire_row(char * print_string,int y,uint8_t text_attribute); 102 | void print_center(char * print_string,int y,uint8_t text_attribute); 103 | void print_center_screen(char * print_string); 104 | void print_center_screen(char * print_string,uint8_t text_attribute); 105 | void print_center_screen(char * print_string,char * print_string2); 106 | void print_center_screen(char * print_string,char * print_string2,char * print_string3); 107 | void print_center_screen(char * print_string,char * print_string2,char * print_string3,char * print_string4); 108 | void print_right(char * print_string,int y); 109 | void print_right_padded(char * print_string,int y,int padding); 110 | void print_right_fixed_field_size(char * print_string,int y,int field_size); 111 | void print_left(char * print_string,int y); 112 | void print_left_padded(char * print_string,int y,int padding); 113 | void print_left_fixed_field_size(char * print_string,int y,int field_size); 114 | void print_top_left(char * print_string); 115 | void print_top_right(char * print_string); 116 | void print_bottom_left(char * print_string); 117 | void print_bottom_right(char * print_string); 118 | 119 | /* print a timed message in the center of the screen; this can be multiline */ 120 | 121 | void print_center_timed_message(char * print_string,int ms_to_display); 122 | void print_center_timed_message(char * print_string,int ms_to_display,uint8_t text_attribute); // TODO - add multiline timed attribute prints 123 | void print_center_timed_message(char * print_string,char * print_string2,int ms_to_display); 124 | void print_center_timed_message(char * print_string,char * print_string2,char * print_string3,int ms_to_display); 125 | void print_center_timed_message(char * print_string,char * print_string2,char * print_string3,char * print_string4,int ms_to_display); 126 | 127 | void redraw(); // redraw the entire screen 128 | void row_scroll(); 129 | void println(char * print_string); 130 | int length(char * print_string); 131 | void clear_row(uint8_t row_number); // clear one entire row 132 | 133 | #if defined(FEATURE_ADAFRUIT_BUTTONS) 134 | uint8_t readButtons(); 135 | #endif 136 | 137 | private: 138 | 139 | void save_current_screen_to_revert_screen_buffer(); // used by the timed message functionality to push the current screen to a buffer for saving 140 | //void push_revert_screen_buffer_to_live_buffer(); // used by the timed message functionality to pull a saved screen and push to the live display 141 | void push_revert_screen_buffer_to_pending_buffer(); 142 | void revert_back_screen(); // used by the timed message functionality to pull a saved screen and push to the live display 143 | void prepare_for_timed_screen(int ms_to_display); 144 | int Xposition(int screen_buffer_index); 145 | int Yposition(int screen_buffer_index); 146 | int buffer_index_position(int x,int y); 147 | 148 | }; 149 | 150 | #endif //_K3NGDISPLAY_H 151 | 152 | -------------------------------------------------------------------------------- /libraries/PCF8583/PCF8583.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Implements a simple interface to the time function of the PCF8583 RTC chip 3 | 4 | Works around the device's limited year storage by keeping the year in the 5 | first two bytes of user accessible storage 6 | 7 | Assumes device is attached in the standard location - Analog pins 4 and 5 8 | Device address is the 8 bit address (as in the device datasheet - normally A0) 9 | 10 | Copyright (c) 2009, Erik DeBill 11 | 12 | 13 | This library is free software; you can redistribute it and/or 14 | modify it under the terms of the GNU Lesser General Public 15 | License as published by the Free Software Foundation; either 16 | version 2.1 of the License, or (at your option) any later version. 17 | 18 | This library is distributed in the hope that it will be useful, 19 | but WITHOUT ANY WARRANTY; without even the implied warranty of 20 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 21 | Lesser General Public License for more details. 22 | 23 | You should have received a copy of the GNU Lesser General Public 24 | License along with this library; if not, write to the Free Software 25 | Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA 26 | */ 27 | 28 | 29 | #include 30 | #include 31 | #include "PCF8583.h" 32 | 33 | namespace { 34 | bool IsLeapYear(int year) { 35 | return !(year % 400) || ((year % 100) && !(year % 4)); 36 | } 37 | 38 | byte DayOfWeek(const PCF8583 &now) { 39 | //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}; 40 | const 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}; // modified by Anthony Good 2015-03-23 for compilation under Arduino 1.6.1 41 | byte y = now.year % 100, c = 6 - 2 * ((now.year / 100) % 4); 42 | return (now.day + pgm_read_byte_near(MonthTable + IsLeapYear(now.year) * 12 + now.month - 1) + y + (y / 4) + c) % 7; 43 | } 44 | } 45 | 46 | // provide device address as a full 8 bit address (like the datasheet) 47 | PCF8583::PCF8583(int device_address) { 48 | address = device_address >> 1; // convert to 7 bit so Wire doesn't choke 49 | Wire.begin(); 50 | } 51 | 52 | // initialization 53 | void PCF8583::init() 54 | { 55 | 56 | Wire.beginTransmission(address); 57 | Wire.write(0x00); 58 | Wire.write(0x04); // Set alarm on int\ will turn to vcc 59 | Wire.endTransmission(); 60 | 61 | } 62 | 63 | void PCF8583::get_time(){ 64 | 65 | Wire.beginTransmission(address); 66 | Wire.write(0xC0); // stop counting, don't mask 67 | Wire.endTransmission(); 68 | 69 | Wire.beginTransmission(address); 70 | Wire.write(0x02); 71 | Wire.endTransmission(); 72 | Wire.requestFrom(address, 5); 73 | 74 | second = bcd_to_byte(Wire.read()); 75 | minute = bcd_to_byte(Wire.read()); 76 | hour = bcd_to_byte(Wire.read()); 77 | byte incoming = Wire.read(); // year/date counter 78 | day = bcd_to_byte(incoming & 0x3f); 79 | year = (int)((incoming >> 6) & 0x03); // it will only hold 4 years... 80 | incoming = Wire.read(); 81 | month = bcd_to_byte(incoming & 0x1f); 82 | dow = incoming >> 5; 83 | 84 | // but that's not all - we need to find out what the base year is 85 | // so we can add the 2 bits we got above and find the real year 86 | Wire.beginTransmission(address); 87 | Wire.write(0x10); 88 | Wire.endTransmission(); 89 | Wire.requestFrom(address, 2); 90 | year_base = 0; 91 | year_base = Wire.read(); 92 | year_base = year_base << 8; 93 | year_base = year_base | Wire.read(); 94 | year = year + year_base; 95 | } 96 | 97 | 98 | void PCF8583::set_time() 99 | { 100 | 101 | if (!IsLeapYear(year) && 2 == month && 29 == day) { 102 | month = 3; 103 | day = 1; 104 | } 105 | 106 | // Attempt to find the previous leap year 107 | year_base = year - year % 4; 108 | if (!IsLeapYear(year_base)) { 109 | // Not a leap year (new century), make sure the calendar won't use a 29 days February. 110 | year_base = year - 1; 111 | } 112 | 113 | dow = DayOfWeek(*this); 114 | 115 | Wire.beginTransmission(address); 116 | Wire.write(0xC0); // stop counting, don't mask 117 | Wire.endTransmission(); 118 | 119 | Wire.beginTransmission(address); 120 | Wire.write(0x02); 121 | Wire.write(int_to_bcd(second)); 122 | Wire.write(int_to_bcd(minute)); 123 | Wire.write(int_to_bcd(hour)); 124 | Wire.write(((byte)(year - year_base) << 6) | int_to_bcd(day)); 125 | Wire.write((dow << 5) | (int_to_bcd(month) & 0x1f)); 126 | Wire.endTransmission(); 127 | 128 | Wire.beginTransmission(address); 129 | Wire.write(0x10); 130 | Wire.write(year_base >> 8); 131 | Wire.write(year_base & 0x00ff); 132 | Wire.endTransmission(); 133 | 134 | init(); // re set the control/status register to 0x04 135 | 136 | } 137 | 138 | //Get the alarm at 0x09 adress 139 | void PCF8583::get_alarm() 140 | { 141 | Wire.beginTransmission(address); 142 | Wire.write(0x0A); // Set the register pointer to (0x0A) 143 | Wire.endTransmission(); 144 | 145 | Wire.requestFrom(address, 4); // Read 4 values 146 | 147 | alarm_second = bcd_to_byte(Wire.read()); 148 | alarm_minute = bcd_to_byte(Wire.read()); 149 | alarm_hour = bcd_to_byte(Wire.read()); 150 | 151 | Wire.beginTransmission(address); 152 | Wire.write(0x0E); 153 | Wire.endTransmission(); 154 | 155 | Wire.requestFrom(address, 1); // Read weekday value 156 | 157 | alarm_day = bcd_to_byte(Wire.read()); 158 | } 159 | 160 | //Set a daily alarm 161 | void PCF8583::set_daily_alarm() 162 | { 163 | Wire.beginTransmission(address); 164 | Wire.write(0x08); 165 | Wire.write(0x90); // daily alarm set 166 | Wire.endTransmission(); 167 | 168 | Wire.beginTransmission(address); 169 | Wire.write(0x09); // Set the register pointer to (0x09) 170 | Wire.write(0x00); // Set 00 at milisec 171 | Wire.write(int_to_bcd(alarm_second)); 172 | Wire.write(int_to_bcd(alarm_minute)); 173 | Wire.write(int_to_bcd(alarm_hour)); 174 | Wire.write(0x00); // Set 00 at day 175 | Wire.endTransmission(); 176 | } 177 | 178 | int PCF8583::bcd_to_byte(byte bcd){ 179 | return ((bcd >> 4) * 10) + (bcd & 0x0f); 180 | } 181 | 182 | byte PCF8583::int_to_bcd(int in){ 183 | return ((in / 10) << 4) + (in % 10); 184 | } 185 | 186 | -------------------------------------------------------------------------------- /libraries/P13/P13.h: -------------------------------------------------------------------------------- 1 | // 2 | // Plan13.cpp 3 | // 4 | // An implementation of Plan13 in C++ by Mark VandeWettering 5 | // 6 | // Plan13 is an algorithm for satellite orbit prediction first formulated 7 | // by James Miller G3RUH. I learned about it when I saw it was the basis 8 | // of the PIC based antenna rotator project designed by G6LVB. 9 | // 10 | // http://www.g6lvb.com/Articles/LVBTracker2/index.htm 11 | // 12 | // I ported the algorithm to Python, and it was my primary means of orbit 13 | // prediction for a couple of years while I operated the "Easy Sats" with 14 | // a dual band hand held and an Arrow antenna. 15 | // 16 | // I've long wanted to redo the work in C++ so that I could port the code 17 | // to smaller processors including the Atmel AVR chips. Bruce Robertson, 18 | // VE9QRP started the qrpTracker project to fufill many of the same goals, 19 | // but I thought that the code could be made more compact and more modular, 20 | // and could serve not just the embedded targets but could be of more 21 | // use for more general applications. And, I like the BSD License a bit 22 | // better too. 23 | // 24 | // So, here it is! 25 | // 26 | 27 | /* 28 | 29 | Copyright 2011, Mark VandeWettering. All rights reserved. 30 | 31 | Redistribution and use in source and binary forms, with or without 32 | modification, are permitted provided that the following conditions are 33 | met: 34 | 35 | 1. Redistributions of source code must retain the above copyright 36 | notice, this list of conditions and the following disclaimer. 37 | 38 | 2. Redistributions in binary form must reproduce the above copyright 39 | notice, this list of conditions and the following disclaimer 40 | in the documentation and/or other materials provided with the 41 | distribution. 42 | 43 | THIS SOFTWARE IS PROVIDED BY MARK VANDEWETTERING ''AS IS'' AND ANY 44 | EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 45 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 46 | PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL OR 47 | CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, 48 | EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, 49 | PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 50 | PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 51 | LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 52 | NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 53 | SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 54 | 55 | The views and conclusions contained in the software and documentation 56 | are those of the authors and should not be interpreted as representing 57 | official policies, either expressed or implied, of Mark VandeWettering 58 | 59 | */ 60 | 61 | // Modification by Anthony Good, K3NG 2020-07-24: Change DateTime to SatDateTime to avoid a conflict with an RTC library I'm using 62 | 63 | //---------------------------------------------------------------------- 64 | 65 | #if defined(ARDUINO) && ARDUINO >= 100 66 | #include "Arduino.h" 67 | #else 68 | #include "WProgram.h" 69 | #endif 70 | 71 | // here are a bunch of constants that will be used throughout the 72 | // code, but which will probably not be helpful outside. 73 | 74 | static const double RE = 6378.137f ; 75 | static const double FL = 1.f/298.257224f ; 76 | static const double GM = 3.986E5f ; 77 | static const double J2 = 1.08263E-3f ; 78 | static const double YM = 365.25f ; 79 | static const double YT = 365.2421874f ; 80 | static const double WW = 2.f*M_PI/YT ; 81 | static const double WE = 2.f*M_PI+ WW ; 82 | static const double W0 = WE/86400.f ; 83 | 84 | 85 | static const double YG = 2014.f; 86 | static const double G0 = 99.5828f; 87 | static const double MAS0 = 356.4105f; 88 | static const double MASD = 0.98560028f; 89 | static const double EQC1 = 0.03340; 90 | static const double EQC2 = 0.00035; 91 | static const double INS = radians(23.4375f); 92 | 93 | // static const double YG = 2000.f ; 94 | // static const double G0 = 98.9821f ; 95 | // static const double MAS0 = 356.0507f ; 96 | // static const double MASD = 0.98560028f ; 97 | // static const double EQC1 = 0.03342 ; 98 | // static const double EQC2 = 0.00035 ; 99 | // static const double INS = radians(23.4393f) ; 100 | 101 | static const double CNS = cos(INS) ; 102 | static const double SNS = sin(INS) ; 103 | 104 | //---------------------------------------------------------------------- 105 | 106 | // the original BASIC code used three variables (e.g. Ox, Oy, Oz) to 107 | // represent a vector quantity. I think that makes for slightly more 108 | // obtuse code, so I going to collapse them into a single variable 109 | // which is an array of three elements 110 | 111 | typedef double Vec3[3] ; 112 | 113 | //---------------------------------------------------------------------- 114 | 115 | class SatDateTime { 116 | public: 117 | long DN ; 118 | double TN ; 119 | SatDateTime(int year, int month, int day, int h, int m, int s) ; 120 | SatDateTime(const SatDateTime &) ; 121 | SatDateTime() ; 122 | ~SatDateTime() { } 123 | void add(double) ; 124 | void settime(int year, int month, int day, int h, int m, int s) ; 125 | void gettime(int& year, int& mon, int& day, int& h, int& m, int& s) ; 126 | void ascii(char *) ; 127 | void roundup(double) ; 128 | } ; 129 | 130 | //---------------------------------------------------------------------- 131 | 132 | class Observer { 133 | public: 134 | const char *name ; 135 | double LA ; 136 | double LO ; 137 | double HT ; 138 | Vec3 U, E, N, O, V ; 139 | 140 | Observer(const char *, double, double, double) ; 141 | ~Observer() { } ; 142 | } ; 143 | 144 | //---------------------------------------------------------------------- 145 | 146 | 147 | class Satellite { 148 | long N ; 149 | long YE ; 150 | long DE ; 151 | double TE ; 152 | double IN ; 153 | double RA ; 154 | double EC ; 155 | double WP ; 156 | double MA ; 157 | double MM ; 158 | double M2 ; 159 | double RV ; 160 | double ALON ; 161 | double ALAT ; 162 | 163 | 164 | // these values are stored, but could be calculated on the fly 165 | // during calls to predict() 166 | // classic space/time tradeoff 167 | 168 | double N0, A_0, B_0 ; 169 | double PC ; 170 | double QD, WD, DC ; 171 | double RS ; 172 | 173 | public: 174 | const char *name ; 175 | Vec3 SAT, VEL ; // celestial coordinates 176 | Vec3 S, V ; // geocentric coordinates 177 | 178 | Satellite() { } ; 179 | Satellite(const char *name, const char *l1, const char *l2) ; 180 | ~Satellite() ; 181 | void tle(const char *name, const char *l1, const char *l2) ; 182 | void predict(const SatDateTime &dt) ; 183 | void LL(double &lat, double &lng) ; 184 | void altaz(const Observer &obs, double &alt, double &az) ; 185 | } ; 186 | 187 | class Sun { 188 | public: 189 | Vec3 SUN, H ; 190 | Sun() ; 191 | ~Sun() { } ; 192 | void predict(const SatDateTime &dt) ; 193 | void LL(double &lat, double &lng) ; 194 | void altaz(const Observer &obs, double &alt, double &az) ; 195 | } ; 196 | -------------------------------------------------------------------------------- /libraries/LCD_C0220BIZ/lcd.h: -------------------------------------------------------------------------------- 1 | // --------------------------------------------------------------------------- 2 | // Created by Francisco Malpartida on 20/08/11. 3 | // Copyright 2011 - Under creative commons license 3.0: 4 | // Attribution-ShareAlike CC BY-SA 5 | // 6 | // This software is furnished "as is", without technical support, and with no 7 | // warranty, express or implied, as to its usefulness for any purpose. 8 | // 9 | // Thread Safe: No 10 | // Extendable: No 11 | // 12 | // @file lcd.h 13 | // LCD API 1.0 interface declaration class. 14 | // 15 | // @brief Based on the LCD API 1.0 by dale@wentztech.com 16 | // This class implements the LCD API abstract library class from 17 | // which all LCDs inherite. 18 | // 19 | // @author F. Malpartida - fmalpartida@gmail.com 20 | // --------------------------------------------------------------------------- 21 | 22 | #ifndef LCD_h 23 | #define LCD_h 24 | #include "Arduino.h" 25 | #include "Print.h" 26 | 27 | 28 | #define _LCDEXPANDED // If defined turn on advanced functions 29 | 30 | #define _LCD_API_VERSION "1.0" 31 | 32 | class LCD : public Print 33 | { 34 | 35 | public: 36 | 37 | /** 38 | Send a command to the display 39 | 40 | @param value[in] Command to be sent to the display 41 | 42 | @return None 43 | 44 | void command(uint8_t value); 45 | */ 46 | virtual void command(uint8_t value) = 0; 47 | 48 | /** 49 | Initialise the display. Once created the object, this is the next operation 50 | that has to be called to initialise the display into a known state. It 51 | assumes that the I2C bus is not initialised and hence initialise the Wire 52 | interface. 53 | 54 | Clear the display 55 | Set contrast levels 56 | Set the cursor at origens (0,0) 57 | Turn on the entire display 58 | 59 | void init(); 60 | */ 61 | virtual void init() = 0; 62 | 63 | /** 64 | Set a different delay to that in the library. It may be needed to delay 65 | sending commands or characters one after the other. 66 | 67 | @param cmdDelay[in] Delay after issuing a command 68 | @param charDelay[in] Delay after issuing a character to the LCD 69 | 70 | @return None 71 | 72 | void setDelay(int,int); 73 | */ 74 | virtual void setDelay(int,int) = 0; 75 | 76 | /** 77 | This is the write method used by the Print library. It allows printing 78 | characters to the display and new lines: print, println. It will write the 79 | value to the display and increase the cursor. 80 | 81 | @param value[in] character to write to the current LCD write position 82 | 83 | @return None 84 | 85 | virtual void write(uint8_t); 86 | */ 87 | virtual size_t write(uint8_t) = 0; 88 | 89 | /** 90 | This is the write method used by the Print library. It allows printing 91 | characters to the display and new lines: print, println. It will write the 92 | value to the display and increase the cursor. 93 | 94 | @param buffer[in] buffer to write to the current LCD write position 95 | @param size[in] size of the buffer 96 | 97 | @return None 98 | 99 | virtual void write(uint8_t, size_t); 100 | */ 101 | virtual size_t write(const uint8_t *buffer, size_t size) = 0; 102 | 103 | /** 104 | Clear the display and set the cursor to 0,0 105 | 106 | void clear(); 107 | */ 108 | virtual void clear() = 0; 109 | 110 | /** 111 | Set the cursor to 0,0 112 | 113 | void home(); 114 | */ 115 | virtual void home() = 0; 116 | 117 | /** 118 | Switch the display on. This is the default state when the display is 119 | initialised. See. init() method 120 | 121 | void on(); 122 | */ 123 | virtual void on() = 0; 124 | 125 | /** 126 | Switch the display off. 127 | 128 | void off(); 129 | */ 130 | virtual void off() = 0; 131 | 132 | /** 133 | Turn on the cursor "_". 134 | 135 | void cursor_on(); 136 | */ 137 | virtual void cursor_on() = 0; 138 | 139 | /** 140 | Turn off the cursor. This is the default state when the display is 141 | initialised. 142 | 143 | void cursor_off(); 144 | */ 145 | virtual void cursor_off() = 0; 146 | 147 | /** 148 | Activate cursor blink. 149 | 150 | void blink_on(); 151 | */ 152 | virtual void blink_on() = 0; 153 | 154 | /** 155 | Deactivate cursor blinking. This is the default state when the display is 156 | initialised. 157 | 158 | void blink_off (); 159 | */ 160 | virtual void blink_off() = 0; 161 | 162 | /** 163 | Set the cursor at the following coordinates (Line, Col). Initial value after 164 | initialization is (0,0). 165 | 166 | @param Line[in] Line where to put the cursor, range (0, max display lines-1) 167 | This display only take (0, 1) 168 | @param Col[in] Colum where to put the cursor, range (0, max width+1) 169 | 170 | @return None 171 | 172 | void setCursor(uint8_t Line, uint8_t Col ); 173 | */ 174 | virtual void setCursor(uint8_t Line, uint8_t Col ) = 0; 175 | 176 | // 177 | // EXPANDED FUNCTIONALITY METHODS 178 | // -------------------------------------------------------------------------- 179 | 180 | #ifdef _LCDEXPANDED 181 | 182 | /** 183 | Provides the state of the LCD. This value is updated every command is sent 184 | to the LCD or a character or a buffer is writen to the display. 185 | 186 | @return 0 OK, 1 if data was too big to be transmitted, 2 NACK on address 187 | transmission, 3 NACK on data transmission, 4 other error. 188 | 189 | uint8_t status(); 190 | */ 191 | virtual uint8_t status() = 0; 192 | 193 | /** 194 | Load a custom character on the display. After adding a new character to 195 | the character set, the coordinates are set to (0, 0). This method should 196 | be called during initialization. 197 | 198 | @param char_num[in] Character to load onto the display, this display supports 199 | upto 16 user defined characters. 200 | @param rows[in] Bitmap defining the character, the display assumes an array 201 | of 8 bytes per character. 202 | 203 | @return None. 204 | 205 | uint8_t load_custom_character(uint8_t char_num, uint8_t *rows); 206 | */ 207 | virtual void load_custom_character(uint8_t char_num, uint8_t *rows) = 0; 208 | 209 | /** 210 | NOT SUPPORTED 211 | 212 | uint8_t keypad(); 213 | */ 214 | virtual uint8_t keypad() = 0; 215 | 216 | void printstr(const char[]); 217 | 218 | /** 219 | Sets the backlight level. If the backlight level is connected to a PWM pin, 220 | new_val will set a light level range between 0 and 255. If it is connected 221 | to a normal GPIO, from 0 to 127 it will be off and from 128 to 255 the 222 | backlight will be on. Backlight pin allocation on constructor. 223 | 224 | @param new_val[in] Backlight level of the display. Full range will only be 225 | available on pins with PWM support. 226 | 227 | @return None. 228 | 229 | uint8_t setBacklight(); 230 | */ 231 | virtual void setBacklight(uint8_t new_val) = 0; 232 | 233 | /** 234 | Sets the LCD contrast level. 235 | 236 | @param new_val[in] The contrast range (0 to 255) has been mapped to 16 237 | contrast levels on the display. 238 | 239 | @return None. 240 | 241 | uint8_t setContrast(); 242 | */ 243 | virtual void setContrast(uint8_t new_val) = 0; 244 | 245 | 246 | #endif 247 | 248 | private: 249 | 250 | }; 251 | 252 | #endif 253 | 254 | -------------------------------------------------------------------------------- /libraries/LSM303/LSM303.h: -------------------------------------------------------------------------------- 1 | #ifndef LSM303_h 2 | #define LSM303_h 3 | 4 | #include // for byte data type 5 | 6 | class LSM303 7 | { 8 | public: 9 | template struct vector 10 | { 11 | T x, y, z; 12 | }; 13 | 14 | enum deviceType { device_DLH, device_DLM, device_DLHC, device_D, device_auto }; 15 | enum sa0State { sa0_low, sa0_high, sa0_auto }; 16 | 17 | // register addresses 18 | enum regAddr 19 | { 20 | TEMP_OUT_L = 0x05, // D 21 | TEMP_OUT_H = 0x06, // D 22 | 23 | STATUS_M = 0x07, // D 24 | 25 | INT_CTRL_M = 0x12, // D 26 | INT_SRC_M = 0x13, // D 27 | INT_THS_L_M = 0x14, // D 28 | INT_THS_H_M = 0x15, // D 29 | 30 | OFFSET_X_L_M = 0x16, // D 31 | OFFSET_X_H_M = 0x17, // D 32 | OFFSET_Y_L_M = 0x18, // D 33 | OFFSET_Y_H_M = 0x19, // D 34 | OFFSET_Z_L_M = 0x1A, // D 35 | OFFSET_Z_H_M = 0x1B, // D 36 | REFERENCE_X = 0x1C, // D 37 | REFERENCE_Y = 0x1D, // D 38 | REFERENCE_Z = 0x1E, // D 39 | 40 | CTRL0 = 0x1F, // D 41 | CTRL1 = 0x20, // D 42 | CTRL_REG1_A = 0x20, // DLH, DLM, DLHC 43 | CTRL2 = 0x21, // D 44 | CTRL_REG2_A = 0x21, // DLH, DLM, DLHC 45 | CTRL3 = 0x22, // D 46 | CTRL_REG3_A = 0x22, // DLH, DLM, DLHC 47 | CTRL4 = 0x23, // D 48 | CTRL_REG4_A = 0x23, // DLH, DLM, DLHC 49 | CTRL5 = 0x24, // D 50 | CTRL_REG5_A = 0x24, // DLH, DLM, DLHC 51 | CTRL6 = 0x25, // D 52 | CTRL_REG6_A = 0x25, // DLHC 53 | HP_FILTER_RESET_A = 0x25, // DLH, DLM 54 | CTRL7 = 0x26, // D 55 | REFERENCE_A = 0x26, // DLH, DLM, DLHC 56 | STATUS_A = 0x27, // D 57 | STATUS_REG_A = 0x27, // DLH, DLM, DLHC 58 | 59 | OUT_X_L_A = 0x28, 60 | OUT_X_H_A = 0x29, 61 | OUT_Y_L_A = 0x2A, 62 | OUT_Y_H_A = 0x2B, 63 | OUT_Z_L_A = 0x2C, 64 | OUT_Z_H_A = 0x2D, 65 | 66 | FIFO_CTRL = 0x2E, // D 67 | FIFO_CTRL_REG_A = 0x2E, // DLHC 68 | FIFO_SRC = 0x2F, // D 69 | FIFO_SRC_REG_A = 0x2F, // DLHC 70 | 71 | IG_CFG1 = 0x30, // D 72 | INT1_CFG_A = 0x30, // DLH, DLM, DLHC 73 | IG_SRC1 = 0x31, // D 74 | INT1_SRC_A = 0x31, // DLH, DLM, DLHC 75 | IG_THS1 = 0x32, // D 76 | INT1_THS_A = 0x32, // DLH, DLM, DLHC 77 | IG_DUR1 = 0x33, // D 78 | INT1_DURATION_A = 0x33, // DLH, DLM, DLHC 79 | IG_CFG2 = 0x34, // D 80 | INT2_CFG_A = 0x34, // DLH, DLM, DLHC 81 | IG_SRC2 = 0x35, // D 82 | INT2_SRC_A = 0x35, // DLH, DLM, DLHC 83 | IG_THS2 = 0x36, // D 84 | INT2_THS_A = 0x36, // DLH, DLM, DLHC 85 | IG_DUR2 = 0x37, // D 86 | INT2_DURATION_A = 0x37, // DLH, DLM, DLHC 87 | 88 | CLICK_CFG = 0x38, // D 89 | CLICK_CFG_A = 0x38, // DLHC 90 | CLICK_SRC = 0x39, // D 91 | CLICK_SRC_A = 0x39, // DLHC 92 | CLICK_THS = 0x3A, // D 93 | CLICK_THS_A = 0x3A, // DLHC 94 | TIME_LIMIT = 0x3B, // D 95 | TIME_LIMIT_A = 0x3B, // DLHC 96 | TIME_LATENCY = 0x3C, // D 97 | TIME_LATENCY_A = 0x3C, // DLHC 98 | TIME_WINDOW = 0x3D, // D 99 | TIME_WINDOW_A = 0x3D, // DLHC 100 | 101 | Act_THS = 0x3E, // D 102 | Act_DUR = 0x3F, // D 103 | 104 | CRA_REG_M = 0x00, // DLH, DLM, DLHC 105 | CRB_REG_M = 0x01, // DLH, DLM, DLHC 106 | MR_REG_M = 0x02, // DLH, DLM, DLHC 107 | 108 | SR_REG_M = 0x09, // DLH, DLM, DLHC 109 | IRA_REG_M = 0x0A, // DLH, DLM, DLHC 110 | IRB_REG_M = 0x0B, // DLH, DLM, DLHC 111 | IRC_REG_M = 0x0C, // DLH, DLM, DLHC 112 | 113 | WHO_AM_I_M = 0x0F, // DLM 114 | WHO_AM_I = 0x0F, // D 115 | 116 | TEMP_OUT_H_M = 0x31, // DLHC 117 | TEMP_OUT_L_M = 0x32, // DLHC 118 | 119 | 120 | // dummy addresses for registers in different locations on different devices; 121 | // the library translates these based on device type 122 | // value with sign flipped is used as index into translated_regs array 123 | 124 | OUT_X_H_M = -1, 125 | OUT_X_L_M = -2, 126 | OUT_Y_H_M = -3, 127 | OUT_Y_L_M = -4, 128 | OUT_Z_H_M = -5, 129 | OUT_Z_L_M = -6, 130 | // update dummy_reg_count if registers are added here! 131 | 132 | // device-specific register addresses 133 | 134 | DLH_OUT_X_H_M = 0x03, 135 | DLH_OUT_X_L_M = 0x04, 136 | DLH_OUT_Y_H_M = 0x05, 137 | DLH_OUT_Y_L_M = 0x06, 138 | DLH_OUT_Z_H_M = 0x07, 139 | DLH_OUT_Z_L_M = 0x08, 140 | 141 | DLM_OUT_X_H_M = 0x03, 142 | DLM_OUT_X_L_M = 0x04, 143 | DLM_OUT_Z_H_M = 0x05, 144 | DLM_OUT_Z_L_M = 0x06, 145 | DLM_OUT_Y_H_M = 0x07, 146 | DLM_OUT_Y_L_M = 0x08, 147 | 148 | DLHC_OUT_X_H_M = 0x03, 149 | DLHC_OUT_X_L_M = 0x04, 150 | DLHC_OUT_Z_H_M = 0x05, 151 | DLHC_OUT_Z_L_M = 0x06, 152 | DLHC_OUT_Y_H_M = 0x07, 153 | DLHC_OUT_Y_L_M = 0x08, 154 | 155 | D_OUT_X_L_M = 0x08, 156 | D_OUT_X_H_M = 0x09, 157 | D_OUT_Y_L_M = 0x0A, 158 | D_OUT_Y_H_M = 0x0B, 159 | D_OUT_Z_L_M = 0x0C, 160 | D_OUT_Z_H_M = 0x0D 161 | }; 162 | 163 | vector a; // accelerometer readings 164 | vector m; // magnetometer readings 165 | vector m_max; // maximum magnetometer values, used for calibration 166 | vector m_min; // minimum magnetometer values, used for calibration 167 | 168 | byte last_status; // status of last I2C transmission 169 | 170 | LSM303(void); 171 | 172 | bool init(deviceType device = device_auto, sa0State sa0 = sa0_auto); 173 | byte getDeviceType(void) { return _device; } 174 | 175 | void enableDefault(void); 176 | 177 | void writeAccReg(regAddr reg, byte value); 178 | byte readAccReg(regAddr reg); 179 | void writeMagReg(regAddr reg, byte value); 180 | byte readMagReg(regAddr reg); 181 | 182 | void writeReg(regAddr reg, byte value); 183 | byte readReg(regAddr reg); 184 | 185 | void readAcc(void); 186 | void readMag(void); 187 | void read(void); 188 | 189 | void setTimeout(unsigned int timeout); 190 | unsigned int getTimeout(void); 191 | bool timeoutOccurred(void); 192 | 193 | float heading(void); 194 | template float heading(vector from); 195 | 196 | // vector functions 197 | template static void vector_cross(const vector *a, const vector *b, vector *out); 198 | template static float vector_dot(const vector *a,const vector *b); 199 | static void vector_normalize(vector *a); 200 | 201 | private: 202 | deviceType _device; // chip type (DLH, DLM, or DLHC) 203 | byte acc_address; 204 | byte mag_address; 205 | 206 | static const int dummy_reg_count = 6; 207 | regAddr translated_regs[dummy_reg_count + 1]; // index 0 not used 208 | 209 | unsigned int io_timeout; 210 | bool did_timeout; 211 | 212 | int testReg(byte address, regAddr reg); 213 | }; 214 | 215 | #endif 216 | 217 | 218 | 219 | -------------------------------------------------------------------------------- /libraries/RTClib/RTClib.cpp: -------------------------------------------------------------------------------- 1 | // Code by JeeLabs http://news.jeelabs.org/code/ 2 | // Released to the public domain! Enjoy! 3 | 4 | #include 5 | #include "RTClib.h" 6 | #ifdef __AVR__ 7 | #include 8 | #define WIRE Wire 9 | #else 10 | #define PROGMEM 11 | #define pgm_read_byte(addr) (*(const unsigned char *)(addr)) 12 | #define WIRE Wire1 13 | #endif 14 | 15 | #define DS1307_ADDRESS 0x68 16 | #define SECONDS_PER_DAY 86400L 17 | 18 | #define SECONDS_FROM_1970_TO_2000 946684800 19 | 20 | #if (ARDUINO >= 100) 21 | #include // capital A so it is error prone on case-sensitive filesystems 22 | #else 23 | #include 24 | #endif 25 | 26 | //////////////////////////////////////////////////////////////////////////////// 27 | // utility code, some of this could be exposed in the DateTime API if needed 28 | 29 | const uint8_t daysInMonth [] PROGMEM = { 31,28,31,30,31,30,31,31,30,31,30,31 }; 30 | 31 | // number of days since 2000/01/01, valid for 2001..2099 32 | static uint16_t date2days(uint16_t y, uint8_t m, uint8_t d) { 33 | if (y >= 2000) 34 | y -= 2000; 35 | uint16_t days = d; 36 | for (uint8_t i = 1; i < m; ++i) 37 | days += pgm_read_byte(daysInMonth + i - 1); 38 | if (m > 2 && y % 4 == 0) 39 | ++days; 40 | return days + 365 * y + (y + 3) / 4 - 1; 41 | } 42 | 43 | static long time2long(uint16_t days, uint8_t h, uint8_t m, uint8_t s) { 44 | return ((days * 24L + h) * 60 + m) * 60 + s; 45 | } 46 | 47 | //////////////////////////////////////////////////////////////////////////////// 48 | // DateTime implementation - ignores time zones and DST changes 49 | // NOTE: also ignores leap seconds, see http://en.wikipedia.org/wiki/Leap_second 50 | 51 | DateTime::DateTime (uint32_t t) { 52 | t -= SECONDS_FROM_1970_TO_2000; // bring to 2000 timestamp from 1970 53 | 54 | ss = t % 60; 55 | t /= 60; 56 | mm = t % 60; 57 | t /= 60; 58 | hh = t % 24; 59 | uint16_t days = t / 24; 60 | uint8_t leap; 61 | for (yOff = 0; ; ++yOff) { 62 | leap = yOff % 4 == 0; 63 | if (days < 365 + leap) 64 | break; 65 | days -= 365 + leap; 66 | } 67 | for (m = 1; ; ++m) { 68 | uint8_t daysPerMonth = pgm_read_byte(daysInMonth + m - 1); 69 | if (leap && m == 2) 70 | ++daysPerMonth; 71 | if (days < daysPerMonth) 72 | break; 73 | days -= daysPerMonth; 74 | } 75 | d = days + 1; 76 | } 77 | 78 | DateTime::DateTime (uint16_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec) { 79 | if (year >= 2000) 80 | year -= 2000; 81 | yOff = year; 82 | m = month; 83 | d = day; 84 | hh = hour; 85 | mm = min; 86 | ss = sec; 87 | } 88 | 89 | static uint8_t conv2d(const char* p) { 90 | uint8_t v = 0; 91 | if ('0' <= *p && *p <= '9') 92 | v = *p - '0'; 93 | return 10 * v + *++p - '0'; 94 | } 95 | 96 | // A convenient constructor for using "the compiler's time": 97 | // DateTime now (__DATE__, __TIME__); 98 | // NOTE: using PSTR would further reduce the RAM footprint 99 | DateTime::DateTime (const char* date, const char* time) { 100 | // sample input: date = "Dec 26 2009", time = "12:34:56" 101 | yOff = conv2d(date + 9); 102 | // Jan Feb Mar Apr May Jun Jul Aug Sep Oct Nov Dec 103 | switch (date[0]) { 104 | case 'J': m = date[1] == 'a' ? 1 : m = date[2] == 'n' ? 6 : 7; break; 105 | case 'F': m = 2; break; 106 | case 'A': m = date[2] == 'r' ? 4 : 8; break; 107 | case 'M': m = date[2] == 'r' ? 3 : 5; break; 108 | case 'S': m = 9; break; 109 | case 'O': m = 10; break; 110 | case 'N': m = 11; break; 111 | case 'D': m = 12; break; 112 | } 113 | d = conv2d(date + 4); 114 | hh = conv2d(time); 115 | mm = conv2d(time + 3); 116 | ss = conv2d(time + 6); 117 | } 118 | 119 | uint8_t DateTime::dayOfWeek() const { 120 | uint16_t day = date2days(yOff, m, d); 121 | return (day + 6) % 7; // Jan 1, 2000 is a Saturday, i.e. returns 6 122 | } 123 | 124 | uint32_t DateTime::unixtime(void) const { 125 | uint32_t t; 126 | uint16_t days = date2days(yOff, m, d); 127 | t = time2long(days, hh, mm, ss); 128 | t += SECONDS_FROM_1970_TO_2000; // seconds from 1970 to 2000 129 | 130 | return t; 131 | } 132 | 133 | //////////////////////////////////////////////////////////////////////////////// 134 | // RTC_DS1307 implementation 135 | 136 | static uint8_t bcd2bin (uint8_t val) { return val - 6 * (val >> 4); } 137 | static uint8_t bin2bcd (uint8_t val) { return val + 6 * (val / 10); } 138 | 139 | uint8_t RTC_DS1307::begin(void) { 140 | return 1; 141 | } 142 | 143 | 144 | #if (ARDUINO >= 100) 145 | 146 | uint8_t RTC_DS1307::isrunning(void) { 147 | WIRE.beginTransmission(DS1307_ADDRESS); 148 | WIRE.write(0); 149 | WIRE.endTransmission(); 150 | 151 | WIRE.requestFrom(DS1307_ADDRESS, 1); 152 | uint8_t ss = WIRE.read(); 153 | return !(ss>>7); 154 | } 155 | 156 | void RTC_DS1307::adjust(const DateTime& dt) { 157 | WIRE.beginTransmission(DS1307_ADDRESS); 158 | WIRE.write(0); 159 | WIRE.write(bin2bcd(dt.second())); 160 | WIRE.write(bin2bcd(dt.minute())); 161 | WIRE.write(bin2bcd(dt.hour())); 162 | WIRE.write(bin2bcd(0)); 163 | WIRE.write(bin2bcd(dt.day())); 164 | WIRE.write(bin2bcd(dt.month())); 165 | WIRE.write(bin2bcd(dt.year() - 2000)); 166 | WIRE.write(0); 167 | WIRE.endTransmission(); 168 | } 169 | 170 | DateTime RTC_DS1307::now() { 171 | WIRE.beginTransmission(DS1307_ADDRESS); 172 | WIRE.write(0); 173 | WIRE.endTransmission(); 174 | 175 | WIRE.requestFrom(DS1307_ADDRESS, 7); 176 | uint8_t ss = bcd2bin(WIRE.read() & 0x7F); 177 | uint8_t mm = bcd2bin(WIRE.read()); 178 | uint8_t hh = bcd2bin(WIRE.read()); 179 | WIRE.read(); 180 | uint8_t d = bcd2bin(WIRE.read()); 181 | uint8_t m = bcd2bin(WIRE.read()); 182 | uint16_t y = bcd2bin(WIRE.read()) + 2000; 183 | 184 | return DateTime (y, m, d, hh, mm, ss); 185 | } 186 | 187 | #else 188 | 189 | uint8_t RTC_DS1307::isrunning(void) { 190 | WIRE.beginTransmission(DS1307_ADDRESS); 191 | WIRE.send(0); 192 | WIRE.endTransmission(); 193 | 194 | WIRE.requestFrom(DS1307_ADDRESS, 1); 195 | uint8_t ss = WIRE.receive(); 196 | return !(ss>>7); 197 | } 198 | 199 | void RTC_DS1307::adjust(const DateTime& dt) { 200 | WIRE.beginTransmission(DS1307_ADDRESS); 201 | WIRE.send(0); 202 | WIRE.send(bin2bcd(dt.second())); 203 | WIRE.send(bin2bcd(dt.minute())); 204 | WIRE.send(bin2bcd(dt.hour())); 205 | WIRE.send(bin2bcd(0)); 206 | WIRE.send(bin2bcd(dt.day())); 207 | WIRE.send(bin2bcd(dt.month())); 208 | WIRE.send(bin2bcd(dt.year() - 2000)); 209 | WIRE.send(0); 210 | WIRE.endTransmission(); 211 | } 212 | 213 | DateTime RTC_DS1307::now() { 214 | WIRE.beginTransmission(DS1307_ADDRESS); 215 | WIRE.send(0); 216 | WIRE.endTransmission(); 217 | 218 | WIRE.requestFrom(DS1307_ADDRESS, 7); 219 | uint8_t ss = bcd2bin(WIRE.receive() & 0x7F); 220 | uint8_t mm = bcd2bin(WIRE.receive()); 221 | uint8_t hh = bcd2bin(WIRE.receive()); 222 | WIRE.receive(); 223 | uint8_t d = bcd2bin(WIRE.receive()); 224 | uint8_t m = bcd2bin(WIRE.receive()); 225 | uint16_t y = bcd2bin(WIRE.receive()) + 2000; 226 | 227 | return DateTime (y, m, d, hh, mm, ss); 228 | } 229 | 230 | #endif 231 | 232 | 233 | //////////////////////////////////////////////////////////////////////////////// 234 | // RTC_Millis implementation 235 | 236 | long RTC_Millis::offset = 0; 237 | 238 | void RTC_Millis::adjust(const DateTime& dt) { 239 | offset = dt.unixtime() - millis() / 1000; 240 | } 241 | 242 | DateTime RTC_Millis::now() { 243 | return (uint32_t)(offset + millis() / 1000); 244 | } 245 | 246 | //////////////////////////////////////////////////////////////////////////////// 247 | -------------------------------------------------------------------------------- /libraries/FaBoLCD_PCF8574/FaBoLCD_PCF8574.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | @file FaBoLCD_PCF8574.cpp 3 | @brief This is a library for the FaBo LCD I2C Brick. 4 | 5 | http://fabo.io/212.html 6 | 7 | Released under APACHE LICENSE, VERSION 2.0 8 | 9 | http://www.apache.org/licenses/ 10 | 11 | @author FaBo 12 | */ 13 | 14 | #include "FaBoLCD_PCF8574.h" 15 | 16 | // When the display powers up, it is configured as follows: 17 | // 18 | // 1. Display clear 19 | // 2. Function set: 20 | // DL = 1; 8-bit interface data 21 | // N = 0; 1-line display 22 | // F = 0; 5x8 dot character font 23 | // 3. Display on/off control: 24 | // D = 0; Display off 25 | // C = 0; Cursor off 26 | // B = 0; Blinking off 27 | // 4. Entry mode set: 28 | // I/D = 1; Increment by 1 29 | // S = 0; No shift 30 | // 31 | // Note, however, that resetting the Arduino doesn't reset the LCD, so we 32 | // can't assume that its in that state when a sketch starts (and the 33 | // LiquidCrystal constructor is called). 34 | 35 | /** 36 | @brief Constructor 37 | */ 38 | FaBoLCD_PCF8574::FaBoLCD_PCF8574(uint8_t addr) 39 | { 40 | _i2caddr = addr; 41 | _backlight = BL; 42 | Wire.begin(); 43 | init(); 44 | } 45 | 46 | /** 47 | @brief init 48 | */ 49 | void FaBoLCD_PCF8574::init() 50 | { 51 | _displayfunction = LCD_4BITMODE | LCD_1LINE | LCD_5x8DOTS; 52 | } 53 | 54 | /** 55 | @brief brgin 56 | */ 57 | void FaBoLCD_PCF8574::begin(uint8_t cols, uint8_t lines, uint8_t dotsize) { 58 | if (lines > 1) { 59 | _displayfunction |= LCD_2LINE; 60 | } 61 | _numlines = lines; 62 | 63 | setRowOffsets(0x00, 0x40, 0x00 + cols, 0x40 + cols); 64 | 65 | // for some 1 line displays you can select a 10 pixel high font 66 | if ((dotsize != LCD_5x8DOTS) && (lines == 1)) { 67 | _displayfunction |= LCD_5x10DOTS; 68 | } 69 | 70 | // SEE PAGE 45/46 FOR INITIALIZATION SPECIFICATION! 71 | // according to datasheet, we need at least 40ms after power rises above 2.7V 72 | // before sending commands. Arduino can turn on way before 4.5V so we'll wait 50 73 | delayMicroseconds(50000); 74 | // Now we pull both RS and R/W low to begin commands 75 | writeI2c(0x00); 76 | 77 | // this is according to the hitachi HD44780 datasheet 78 | // figure 24, pg 46 79 | 80 | // we start in 8bit mode, try to set 4 bit mode 81 | write4bits(DB4|DB5); 82 | delayMicroseconds(4500); // wait min 4.1ms 83 | 84 | // second try 85 | write4bits(DB4|DB5); 86 | delayMicroseconds(4500); // wait min 4.1ms 87 | 88 | // third go! 89 | write4bits(DB4|DB5); 90 | delayMicroseconds(150); 91 | 92 | // finally, set to 4-bit interface 93 | write4bits(DB5); 94 | 95 | // finally, set # lines, font size, etc. 96 | command(LCD_FUNCTIONSET | _displayfunction); 97 | 98 | // turn the display on with no cursor or blinking default 99 | _displaycontrol = LCD_DISPLAYON | LCD_CURSOROFF | LCD_BLINKOFF; 100 | display(); 101 | 102 | // clear it off 103 | clear(); 104 | 105 | // Initialize to default text direction (for romance languages) 106 | _displaymode = LCD_ENTRYLEFT | LCD_ENTRYSHIFTDECREMENT; 107 | // set the entry mode 108 | command(LCD_ENTRYMODESET | _displaymode); 109 | 110 | } 111 | 112 | /** 113 | @brief setRowOffsets 114 | */ 115 | void FaBoLCD_PCF8574::setRowOffsets(int row0, int row1, int row2, int row3) 116 | { 117 | _row_offsets[0] = row0; 118 | _row_offsets[1] = row1; 119 | _row_offsets[2] = row2; 120 | _row_offsets[3] = row3; 121 | } 122 | 123 | /********** high level commands, for the user! */ 124 | 125 | /** 126 | @brief clear 127 | */ 128 | void FaBoLCD_PCF8574::clear() 129 | { 130 | command(LCD_CLEARDISPLAY); // clear display, set cursor position to zero 131 | delayMicroseconds(2000); // this command takes a long time! 132 | } 133 | 134 | /** 135 | @brief home 136 | */ 137 | void FaBoLCD_PCF8574::home() 138 | { 139 | command(LCD_RETURNHOME); // set cursor position to zero 140 | delayMicroseconds(2000); // this command takes a long time! 141 | } 142 | 143 | /** 144 | @brief setCursor 145 | */ 146 | void FaBoLCD_PCF8574::setCursor(uint8_t col, uint8_t row) 147 | { 148 | const size_t max_lines = sizeof(_row_offsets) / sizeof(*_row_offsets); 149 | if ( row >= max_lines ) { 150 | row = max_lines - 1; // we count rows starting w/0 151 | } 152 | if ( row >= _numlines ) { 153 | row = _numlines - 1; // we count rows starting w/0 154 | } 155 | 156 | command(LCD_SETDDRAMADDR | (col + _row_offsets[row])); 157 | } 158 | 159 | /** 160 | @brief Turn the display off (quickly) 161 | */ 162 | void FaBoLCD_PCF8574::noDisplay() { 163 | _displaycontrol &= ~LCD_DISPLAYON; 164 | command(LCD_DISPLAYCONTROL | _displaycontrol); 165 | } 166 | 167 | /** 168 | @brief Turn the display on (quickly) 169 | */ 170 | void FaBoLCD_PCF8574::display() { 171 | _displaycontrol |= LCD_DISPLAYON; 172 | command(LCD_DISPLAYCONTROL | _displaycontrol); 173 | } 174 | 175 | /** 176 | @brief Turns the underline cursor off 177 | */ 178 | void FaBoLCD_PCF8574::noCursor() { 179 | _displaycontrol &= ~LCD_CURSORON; 180 | command(LCD_DISPLAYCONTROL | _displaycontrol); 181 | } 182 | 183 | /** 184 | @brief Turns the underline cursor on 185 | */ 186 | void FaBoLCD_PCF8574::cursor() { 187 | _displaycontrol |= LCD_CURSORON; 188 | command(LCD_DISPLAYCONTROL | _displaycontrol); 189 | } 190 | 191 | /** 192 | @brief Turn off the blinking cursor 193 | */ 194 | void FaBoLCD_PCF8574::noBlink() { 195 | _displaycontrol &= ~LCD_BLINKON; 196 | command(LCD_DISPLAYCONTROL | _displaycontrol); 197 | } 198 | 199 | /** 200 | @brief Turn on the blinking cursor 201 | */ 202 | void FaBoLCD_PCF8574::blink() { 203 | _displaycontrol |= LCD_BLINKON; 204 | command(LCD_DISPLAYCONTROL | _displaycontrol); 205 | } 206 | 207 | /** 208 | @brief These commands scroll the display without changing the RAM 209 | */ 210 | void FaBoLCD_PCF8574::scrollDisplayLeft(void) { 211 | command(LCD_CURSORSHIFT | LCD_DISPLAYMOVE | LCD_MOVELEFT); 212 | } 213 | 214 | /** 215 | @brief These commands scroll the display without changing the RAM 216 | */ 217 | void FaBoLCD_PCF8574::scrollDisplayRight(void) { 218 | command(LCD_CURSORSHIFT | LCD_DISPLAYMOVE | LCD_MOVERIGHT); 219 | } 220 | 221 | /** 222 | @brief This is for text that flows Left to Right 223 | */ 224 | void FaBoLCD_PCF8574::leftToRight(void) { 225 | _displaymode |= LCD_ENTRYLEFT; 226 | command(LCD_ENTRYMODESET | _displaymode); 227 | } 228 | 229 | /** 230 | @brief This is for text that flows Right to Left 231 | */ 232 | void FaBoLCD_PCF8574::rightToLeft(void) { 233 | _displaymode &= ~LCD_ENTRYLEFT; 234 | command(LCD_ENTRYMODESET | _displaymode); 235 | } 236 | 237 | /** 238 | @brief This will 'right justify' text from the cursor 239 | */ 240 | void FaBoLCD_PCF8574::autoscroll(void) { 241 | _displaymode |= LCD_ENTRYSHIFTINCREMENT; 242 | command(LCD_ENTRYMODESET | _displaymode); 243 | } 244 | 245 | /** 246 | @brief This will 'left justify' text from the cursor 247 | */ 248 | void FaBoLCD_PCF8574::noAutoscroll(void) { 249 | _displaymode &= ~LCD_ENTRYSHIFTINCREMENT; 250 | command(LCD_ENTRYMODESET | _displaymode); 251 | } 252 | 253 | /** 254 | @brief Allows us to fill the first 8 CGRAM locations with custom characters 255 | */ 256 | void FaBoLCD_PCF8574::createChar(uint8_t location, uint8_t charmap[]) { 257 | location &= 0x7; // we only have 8 locations 0-7 258 | command(LCD_SETCGRAMADDR | (location << 3)); 259 | for (int i=0; i<8; i++) { 260 | write(charmap[i]); 261 | } 262 | } 263 | 264 | /*********** mid level commands, for sending data/cmds */ 265 | 266 | /** 267 | @brief command 268 | */ 269 | inline void FaBoLCD_PCF8574::command(uint8_t value) { 270 | send(value, 0); 271 | } 272 | 273 | /** 274 | @brief write 275 | */ 276 | inline size_t FaBoLCD_PCF8574::write(uint8_t value) { 277 | send(value, RS); 278 | return 1; // assume sucess 279 | } 280 | 281 | /************ low level data pushing commands **********/ 282 | 283 | /** 284 | @brief write either command or data, 4-bit 285 | */ 286 | void FaBoLCD_PCF8574::send(uint8_t value, uint8_t mode) { 287 | uint8_t Hbit = value & 0xF0; 288 | uint8_t Lbit = (value << 4) & 0xF0; 289 | write4bits(Hbit|mode); 290 | write4bits(Lbit|mode); 291 | } 292 | 293 | /** 294 | @brief pulseEnable 295 | */ 296 | void FaBoLCD_PCF8574::pulseEnable(uint8_t value) { 297 | writeI2c(value & ~EN); // EN LOW 298 | delayMicroseconds(1); 299 | writeI2c(value|EN); // EN HIGH 300 | delayMicroseconds(1); // enable pulse must be >450ns 301 | writeI2c(value & ~EN); // EN LOW 302 | delayMicroseconds(100); // commands need > 37us to settle 303 | } 304 | 305 | /** 306 | @brief write4bits 307 | */ 308 | void FaBoLCD_PCF8574::write4bits(uint8_t value) { 309 | writeI2c(value); 310 | pulseEnable(value); 311 | } 312 | 313 | /** 314 | @brief writeI2c 315 | */ 316 | void FaBoLCD_PCF8574::writeI2c(uint8_t data) { 317 | Wire.beginTransmission(_i2caddr); 318 | Wire.write(data|_backlight); 319 | Wire.endTransmission(); 320 | } 321 | -------------------------------------------------------------------------------- /libraries/TimerOne/TimerOne.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Interrupt and PWM utilities for 16 bit Timer1 on ATmega168/328 3 | * Original code by Jesse Tane for http://labs.ideo.com August 2008 4 | * Modified March 2009 by Jérôme Despatis and Jesse Tane for ATmega328 support 5 | * Modified June 2009 by Michael Polli and Jesse Tane to fix a bug in setPeriod() which caused the timer to stop 6 | * Modified June 2011 by Lex Talionis to add a function to read the timer 7 | * Modified Oct 2011 by Andrew Richards to avoid certain problems: 8 | * - Add (long) assignments and casts to TimerOne::read() to ensure calculations involving tmp, ICR1 and TCNT1 aren't truncated 9 | * - Ensure 16 bit registers accesses are atomic - run with interrupts disabled when accessing 10 | * - Remove global enable of interrupts (sei())- could be running within an interrupt routine) 11 | * - Disable interrupts whilst TCTN1 == 0. Datasheet vague on this, but experiment shows that overflow interrupt 12 | * flag gets set whilst TCNT1 == 0, resulting in a phantom interrupt. Could just set to 1, but gets inaccurate 13 | * at very short durations 14 | * - startBottom() added to start counter at 0 and handle all interrupt enabling. 15 | * - start() amended to enable interrupts 16 | * - restart() amended to point at startBottom() 17 | * Modiied 7:26 PM Sunday, October 09, 2011 by Lex Talionis 18 | * - renamed start() to resume() to reflect it's actual role 19 | * - renamed startBottom() to start(). This breaks some old code that expects start to continue counting where it left off 20 | * 21 | * This program is free software: you can redistribute it and/or modify 22 | * it under the terms of the GNU General Public License as published by 23 | * the Free Software Foundation, either version 3 of the License, or 24 | * (at your option) any later version. 25 | * 26 | * This program is distributed in the hope that it will be useful, 27 | * but WITHOUT ANY WARRANTY; without even the implied warranty of 28 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 29 | * GNU General Public License for more details. 30 | * 31 | * You should have received a copy of the GNU General Public License 32 | * along with this program. If not, see . 33 | * 34 | * See Google Code project http://code.google.com/p/arduino-timerone/ for latest 35 | */ 36 | #ifndef TIMERONE_cpp 37 | #define TIMERONE_cpp 38 | 39 | #include "TimerOne.h" 40 | 41 | TimerOne Timer1; // preinstatiate 42 | 43 | ISR(TIMER1_OVF_vect) // interrupt service routine that wraps a user defined function supplied by attachInterrupt 44 | { 45 | Timer1.isrCallback(); 46 | } 47 | 48 | 49 | void TimerOne::initialize(long microseconds) 50 | { 51 | TCCR1A = 0; // clear control register A 52 | TCCR1B = _BV(WGM13); // set mode 8: phase and frequency correct pwm, stop the timer 53 | setPeriod(microseconds); 54 | } 55 | 56 | 57 | void TimerOne::setPeriod(long microseconds) // AR modified for atomic access 58 | { 59 | 60 | long cycles = (F_CPU / 2000000) * microseconds; // the counter runs backwards after TOP, interrupt is at BOTTOM so divide microseconds by 2 61 | if(cycles < RESOLUTION) clockSelectBits = _BV(CS10); // no prescale, full xtal 62 | else if((cycles >>= 3) < RESOLUTION) clockSelectBits = _BV(CS11); // prescale by /8 63 | else if((cycles >>= 3) < RESOLUTION) clockSelectBits = _BV(CS11) | _BV(CS10); // prescale by /64 64 | else if((cycles >>= 2) < RESOLUTION) clockSelectBits = _BV(CS12); // prescale by /256 65 | else if((cycles >>= 2) < RESOLUTION) clockSelectBits = _BV(CS12) | _BV(CS10); // prescale by /1024 66 | else cycles = RESOLUTION - 1, clockSelectBits = _BV(CS12) | _BV(CS10); // request was out of bounds, set as maximum 67 | 68 | oldSREG = SREG; 69 | cli(); // Disable interrupts for 16 bit register access 70 | ICR1 = pwmPeriod = cycles; // ICR1 is TOP in p & f correct pwm mode 71 | SREG = oldSREG; 72 | 73 | TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12)); 74 | TCCR1B |= clockSelectBits; // reset clock select register, and starts the clock 75 | } 76 | 77 | void TimerOne::setPwmDuty(char pin, int duty) 78 | { 79 | unsigned long dutyCycle = pwmPeriod; 80 | 81 | dutyCycle *= duty; 82 | dutyCycle >>= 10; 83 | 84 | oldSREG = SREG; 85 | cli(); 86 | if(pin == 1 || pin == 9) OCR1A = dutyCycle; 87 | else if(pin == 2 || pin == 10) OCR1B = dutyCycle; 88 | SREG = oldSREG; 89 | } 90 | 91 | void TimerOne::pwm(char pin, int duty, long microseconds) // expects duty cycle to be 10 bit (1024) 92 | { 93 | if(microseconds > 0) setPeriod(microseconds); 94 | if(pin == 1 || pin == 9) { 95 | DDRB |= _BV(PORTB1); // sets data direction register for pwm output pin 96 | TCCR1A |= _BV(COM1A1); // activates the output pin 97 | } 98 | else if(pin == 2 || pin == 10) { 99 | DDRB |= _BV(PORTB2); 100 | TCCR1A |= _BV(COM1B1); 101 | } 102 | setPwmDuty(pin, duty); 103 | resume(); // Lex - make sure the clock is running. We don't want to restart the count, in case we are starting the second WGM 104 | // and the first one is in the middle of a cycle 105 | } 106 | 107 | void TimerOne::disablePwm(char pin) 108 | { 109 | if(pin == 1 || pin == 9) TCCR1A &= ~_BV(COM1A1); // clear the bit that enables pwm on PB1 110 | else if(pin == 2 || pin == 10) TCCR1A &= ~_BV(COM1B1); // clear the bit that enables pwm on PB2 111 | } 112 | 113 | void TimerOne::attachInterrupt(void (*isr)(), long microseconds) 114 | { 115 | if(microseconds > 0) setPeriod(microseconds); 116 | isrCallback = isr; // register the user's callback with the real ISR 117 | TIMSK1 = _BV(TOIE1); // sets the timer overflow interrupt enable bit 118 | // might be running with interrupts disabled (eg inside an ISR), so don't touch the global state 119 | // sei(); 120 | resume(); 121 | } 122 | 123 | void TimerOne::detachInterrupt() 124 | { 125 | TIMSK1 &= ~_BV(TOIE1); // clears the timer overflow interrupt enable bit 126 | // timer continues to count without calling the isr 127 | } 128 | 129 | void TimerOne::resume() // AR suggested 130 | { 131 | TCCR1B |= clockSelectBits; 132 | } 133 | 134 | void TimerOne::restart() // Depricated - Public interface to start at zero - Lex 10/9/2011 135 | { 136 | start(); 137 | } 138 | 139 | void TimerOne::start() // AR addition, renamed by Lex to reflect it's actual role 140 | { 141 | unsigned int tcnt1; 142 | 143 | TIMSK1 &= ~_BV(TOIE1); // AR added 144 | GTCCR |= _BV(PSRSYNC); // AR added - reset prescaler (NB: shared with all 16 bit timers); 145 | 146 | oldSREG = SREG; // AR - save status register 147 | cli(); // AR - Disable interrupts 148 | TCNT1 = 0; 149 | SREG = oldSREG; // AR - Restore status register 150 | resume(); 151 | do { // Nothing -- wait until timer moved on from zero - otherwise get a phantom interrupt 152 | oldSREG = SREG; 153 | cli(); 154 | tcnt1 = TCNT1; 155 | SREG = oldSREG; 156 | } while (tcnt1==0); 157 | 158 | // TIFR1 = 0xff; // AR - Clear interrupt flags 159 | // TIMSK1 = _BV(TOIE1); // sets the timer overflow interrupt enable bit 160 | } 161 | 162 | void TimerOne::stop() 163 | { 164 | TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12)); // clears all clock selects bits 165 | } 166 | 167 | unsigned long TimerOne::read() //returns the value of the timer in microseconds 168 | { //rember! phase and freq correct mode counts up to then down again 169 | unsigned long tmp; // AR amended to hold more than 65536 (could be nearly double this) 170 | unsigned int tcnt1; // AR added 171 | 172 | oldSREG= SREG; 173 | cli(); 174 | tmp=TCNT1; 175 | SREG = oldSREG; 176 | 177 | char scale=0; 178 | switch (clockSelectBits) 179 | { 180 | case 1:// no prescalse 181 | scale=0; 182 | break; 183 | case 2:// x8 prescale 184 | scale=3; 185 | break; 186 | case 3:// x64 187 | scale=6; 188 | break; 189 | case 4:// x256 190 | scale=8; 191 | break; 192 | case 5:// x1024 193 | scale=10; 194 | break; 195 | } 196 | 197 | do { // Nothing -- max delay here is ~1023 cycles. AR modified 198 | oldSREG = SREG; 199 | cli(); 200 | tcnt1 = TCNT1; 201 | SREG = oldSREG; 202 | } while (tcnt1==tmp); //if the timer has not ticked yet 203 | 204 | //if we are counting down add the top value to how far we have counted down 205 | tmp = ( (tcnt1>tmp) ? (tmp) : (long)(ICR1-tcnt1)+(long)ICR1 ); // AR amended to add casts and reuse previous TCNT1 206 | return ((tmp*1000L)/(F_CPU /1000L))< 36 | #include 37 | #include 38 | #include "Print.h" 39 | #include "LCD.h" 40 | 41 | 42 | #define _ST7036_VERSION "1.2.0" 43 | #define _LCD_API_VERSION "1.0" 44 | 45 | class ST7036 : public Print 46 | { 47 | 48 | public: 49 | 50 | /** 51 | Constructor for the display class 52 | 53 | @param num_lines[in] Number of lines in the display 54 | @param num_col[in] Number of columns in the display 55 | @param i2cAddr[in] i2c address of the display 56 | 57 | @return None 58 | 59 | ST7036(uint8_t num_lines, uint8_t num_col, uint8_t i2cAddr ); 60 | */ 61 | ST7036(uint8_t num_lines, uint8_t num_col, uint8_t i2cAddr ); 62 | 63 | /** 64 | Constructor for the display class with backlight allowcation pin. 65 | 66 | @param num_lines[in] Number of lines in the display 67 | @param num_col[in] Number of columns in the display 68 | @param i2cAddr[in] i2c address of the display 69 | @param backlightPin initiales the backlight pin. 70 | 71 | @return None 72 | 73 | ST7036(uint8_t num_lines, uint8_t num_col, uint8_t i2cAddr ); 74 | */ 75 | ST7036(uint8_t num_lines, uint8_t num_col, uint8_t i2cAddr, 76 | int8_t backlightPin ); 77 | 78 | /** 79 | Send a command to the display 80 | 81 | @param value[in] Command to be sent to the display 82 | 83 | @return None 84 | 85 | void command(uint8_t value); 86 | */ 87 | void command(uint8_t value); 88 | 89 | /** 90 | Initialise the display. Once created the object, this is the next operation 91 | that has to be called to initialise the display into a known state. It 92 | assumes that the I2C bus is not initialised and hence initialise the Wire 93 | interface. 94 | 95 | Clear the display 96 | Set contrast levels 97 | Set the cursor at origens (0,0) 98 | Turn on the entire display 99 | 100 | void init(); 101 | */ 102 | void init(); 103 | 104 | /** 105 | Set a different delay to that in the library. It may be needed to delay 106 | sending commands or characters one after the other. 107 | 108 | @param cmdDelay[in] Delay after issuing a command 109 | @param charDelay[in] Delay after issuing a character to the LCD 110 | 111 | @return None 112 | 113 | void setDelay(int,int); 114 | */ 115 | void setDelay(int,int); 116 | 117 | /** 118 | This is the write method used by the Print library. It allows printing 119 | characters to the display and new lines: print, println. It will write the 120 | value to the display and increase the cursor. 121 | 122 | @param value[in] character to write to the current LCD write position 123 | 124 | @return None 125 | 126 | virtual void write(uint8_t); 127 | */ 128 | virtual size_t write(uint8_t); 129 | 130 | /** 131 | This is the write method used by the Print library. It allows printing 132 | characters to the display and new lines: print, println. It will write the 133 | value to the display and increase the cursor. 134 | 135 | @param buffer[in] buffer to write to the current LCD write position 136 | @param size[in] size of the buffer 137 | 138 | @return None 139 | 140 | virtual void write(uint8_t, size_t); 141 | */ 142 | virtual size_t write(const uint8_t *buffer, size_t size); 143 | 144 | /** 145 | Clear the display and set the cursor to 0,0 146 | 147 | void clear(); 148 | */ 149 | void clear(); 150 | 151 | /** 152 | Set the cursor to 0,0 153 | 154 | void home(); 155 | */ 156 | void home(); 157 | 158 | /** 159 | Switch the display on. This is the default state when the display is 160 | initialised. See. init() method 161 | 162 | void on(); 163 | */ 164 | void on(); 165 | 166 | /** 167 | Switch the display off. 168 | 169 | void off(); 170 | */ 171 | virtual void off(); 172 | 173 | /** 174 | Turn on the cursor "_". 175 | 176 | void cursor_on(); 177 | */ 178 | void cursor_on(); 179 | 180 | /** 181 | Turn off the cursor. This is the default state when the display is 182 | initialised. 183 | 184 | void cursor_off(); 185 | */ 186 | void cursor_off(); 187 | 188 | /** 189 | Activate cursor blink. 190 | 191 | void blink_on(); 192 | */ 193 | void blink_on(); 194 | 195 | /** 196 | Deactivate cursor blinking. This is the default state when the display is 197 | initialised. 198 | 199 | void blink_off (); 200 | */ 201 | void blink_off(); 202 | 203 | /** 204 | Set the cursor at the following coordinates (Line, Col). Initial value after 205 | initialization is (0,0). 206 | 207 | @param Line[in] Line where to put the cursor, range (0, max display lines-1) 208 | This display only take (0, 1) 209 | @param Col[in] Colum where to put the cursor, range (0, max width+1) 210 | 211 | @return None 212 | 213 | void setCursor(uint8_t Line, uint8_t Col ); 214 | */ 215 | void setCursor(uint8_t Line, uint8_t Col ); 216 | 217 | // 218 | // EXPANDED FUNCTIONALITY METHODS 219 | // -------------------------------------------------------------------------- 220 | 221 | #ifdef _LCDEXPANDED 222 | 223 | /** 224 | Provides the state of the LCD. This value is updated every command is sent 225 | to the LCD or a character or a buffer is writen to the display. 226 | 227 | @return 0 OK, 1 if data was too big to be transmitted, 2 NACK on address 228 | transmission, 3 NACK on data transmission, 4 other error. 229 | 230 | uint8_t status(); 231 | */ 232 | uint8_t status(); 233 | 234 | /** 235 | Load a custom character on the display. After adding a new character to 236 | the character set, the coordinates are set to (0, 0). This method should 237 | be called during initialization. 238 | 239 | @param char_num[in] Character to load onto the display, this display supports 240 | upto 16 user defined characters. 241 | @param rows[in] Bitmap defining the character, the display assumes an array 242 | of 8 bytes per character. 243 | 244 | @return None. 245 | 246 | uint8_t load_custom_character(uint8_t char_num, uint8_t *rows); 247 | */ 248 | void load_custom_character(uint8_t char_num, uint8_t *rows); 249 | 250 | /** 251 | NOT SUPPORTED 252 | 253 | uint8_t keypad(); 254 | */ 255 | uint8_t keypad(); 256 | 257 | void printstr(const char[]); 258 | 259 | /** 260 | Sets the backlight level. If the backlight level is connected to a PWM pin, 261 | new_val will set a light level range between 0 and 255. If it is connected 262 | to a normal GPIO, from 0 to 127 it will be off and from 128 to 255 the 263 | backlight will be on. Backlight pin allocation on constructor. 264 | 265 | @param new_val[in] Backlight level of the display. Full range will only be 266 | available on pins with PWM support. 267 | 268 | @return None. 269 | 270 | uint8_t setBacklight(); 271 | */ 272 | void setBacklight(uint8_t new_val); 273 | 274 | /** 275 | Sets the LCD contrast level. 276 | 277 | @param new_val[in] The contrast range (0 to 255) has been mapped to 16 278 | contrast levels on the display. 279 | 280 | @return None. 281 | 282 | uint8_t setContrast(); 283 | */ 284 | void setContrast(uint8_t new_val); 285 | 286 | 287 | #endif 288 | 289 | private: 290 | uint8_t _num_lines; 291 | uint8_t _num_col; 292 | uint8_t _i2cAddress; 293 | int _cmdDelay; 294 | int _charDelay; 295 | bool _initialised; 296 | uint8_t _status; 297 | int8_t _backlightPin; 298 | 299 | }; 300 | 301 | #endif 302 | 303 | -------------------------------------------------------------------------------- /k3ng_rotator_controller/rotator_dependencies.h: -------------------------------------------------------------------------------- 1 | 2 | /* ---------------------- dependency checking - don't touch this unless you know what you are doing ---------------------*/ 3 | 4 | #if defined(FEATURE_YAESU_EMULATION) && defined(FEATURE_EASYCOM_EMULATION) 5 | #error "You can't activate both FEATURE_YAESU_EMULATION and FEATURE_EASYCOM_EMULATION!" 6 | #endif 7 | 8 | #if defined(FEATURE_YAESU_EMULATION) && defined(FEATURE_DCU_1_EMULATION) 9 | #error "You can't activate both FEATURE_YAESU_EMULATION and FEATURE_DCU_1_EMULATION!" 10 | #endif 11 | 12 | #if defined(FEATURE_DCU_1_EMULATION) && defined(FEATURE_EASYCOM_EMULATION) 13 | #error "You can't activate both FEATURE_DCU_1_EMULATION and FEATURE_EASYCOM_EMULATION!" 14 | #endif 15 | 16 | #if defined(FEATURE_DCU_1_EMULATION) && defined(FEATURE_ELEVATION_CONTROL) 17 | #error "FEATURE_ELEVATION_CONTROL isn't supported with FEATURE_DCU_1_EMULATION" 18 | #endif 19 | 20 | #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)) 21 | #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" 22 | #endif 23 | 24 | #if defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) && defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE) 25 | #error "You cannot active both FEATURE_MASTER_WITH_SERIAL_SLAVE and FEATURE_MASTER_WITH_ETHERNET_SLAVE" 26 | #endif 27 | 28 | #if defined(FEATURE_EL_POSITION_PULSE_INPUT) && !defined(FEATURE_ELEVATION_CONTROL) 29 | #undef FEATURE_EL_POSITION_PULSE_INPUT 30 | #endif 31 | 32 | #if defined(FEATURE_REMOTE_UNIT_SLAVE) && (defined(FEATURE_MASTER_WITH_SERIAL_SLAVE) || defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE)) 33 | #error "You cannot make this unit be both a master and a slave" 34 | #endif 35 | 36 | #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)) 37 | #error "You cannot get AZ position from remote unit and have a local azimuth sensor defined" 38 | #endif 39 | 40 | #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)) 41 | #error "You cannot get EL position from remote unit and have a local elevation sensor defined" 42 | #endif 43 | 44 | #if (defined(FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB) && defined(FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB)) 45 | #error "You must select only one one library for the ADXL345" 46 | #endif 47 | 48 | #if defined(FEATURE_REMOTE_UNIT_SLAVE) && defined(FEATURE_YAESU_EMULATION) 49 | #error "You must turn off FEATURE_YAESU_EMULATION if using FEATURE_REMOTE_UNIT_SLAVE" 50 | #endif 51 | 52 | #if defined(FEATURE_REMOTE_UNIT_SLAVE) && defined(FEATURE_EASYCOM_EMULATION) 53 | #error "You must turn off FEATURE_EASYCOM_EMULATION if using FEATURE_REMOTE_UNIT_SLAVE" 54 | #endif 55 | 56 | 57 | #if !defined(FEATURE_ELEVATION_CONTROL) && defined(FEATURE_EL_PRESET_ENCODER) 58 | #undef FEATURE_EL_PRESET_ENCODER 59 | #endif 60 | 61 | #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_ADAFRUIT_LSM303) && !defined(FEATURE_AZ_POSITION_HH12_AS5045_SSI) &&!defined(FEATURE_AZ_POSITION_INCREMENTAL_ENCODER) &&!defined(FEATURE_AZ_POSITION_POLOLU_LSM303) &&!defined(FEATURE_AZ_POSITION_A2_ABSOLUTE_ENCODER) &&!defined(FEATURE_AZ_POSITION_ROTARY_ENCODER_USE_PJRC_LIBRARY) && !defined(FEATURE_AZ_POSITION_HMC5883L_USING_JARZEBSKI_LIBRARY) && !defined(FEATURE_AZ_POSITION_DFROBOT_QMC5883) && !defined(FEATURE_AZ_POSITION_MECHASOLUTION_QMC5883) 62 | #error "You must specify one AZ position sensor feature" 63 | #endif 64 | 65 | #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_ADAFRUIT_LSM303) && !defined(FEATURE_EL_POSITION_HH12_AS5045_SSI) && !defined(FEATURE_EL_POSITION_INCREMENTAL_ENCODER) && !defined(FEATURE_EL_POSITION_MEMSIC_2125) &&!defined(FEATURE_EL_POSITION_POLOLU_LSM303) && !defined(FEATURE_EL_POSITION_A2_ABSOLUTE_ENCODER) && !defined(FEATURE_EL_POSITION_ROTARY_ENCODER_USE_PJRC_LIBRARY) 66 | #error "You must specify one EL position sensor feature" 67 | #endif 68 | 69 | #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) 70 | #define FEATURE_ROTARY_ENCODER_SUPPORT 71 | #endif 72 | 73 | #if defined(FEATURE_REMOTE_UNIT_SLAVE) && !defined(FEATURE_ONE_DECIMAL_PLACE_HEADINGS) 74 | #define FEATURE_ONE_DECIMAL_PLACE_HEADINGS 75 | #endif 76 | 77 | #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) || defined(FEATURE_YWROBOT_I2C_DISPLAY) || defined(FEATURE_SAINSMART_I2C_LCD) || defined(FEATURE_MIDAS_I2C_DISPLAY) || defined(FEATURE_FABO_LCD_PCF8574_DISPLAY) 78 | #define FEATURE_LCD_DISPLAY 79 | #endif 80 | 81 | #if defined(FEATURE_ADAFRUIT_I2C_LCD) || defined(FEATURE_YOURDUINO_I2C_LCD) || defined(FEATURE_RFROBOT_I2C_DISPLAY) || defined(FEATURE_YWROBOT_I2C_DISPLAY) || defined(FEATURE_SAINSMART_I2C_LCD) || defined(FEATURE_MIDAS_I2C_DISPLAY) || defined(FEATURE_FABO_LCD_PCF8574_DISPLAY) 82 | #define FEATURE_I2C_LCD 83 | #endif 84 | 85 | #if defined(FEATURE_MOON_TRACKING) && !defined(FEATURE_ELEVATION_CONTROL) 86 | #error "FEATURE_MOON_TRACKING requires FEATURE_ELEVATION_CONTROL" 87 | #endif 88 | 89 | #if (defined(FEATURE_MOON_TRACKING) || defined(FEATURE_SUN_TRACKING)) && !defined(FEATURE_CLOCK) 90 | #error "FEATURE_MOON_TRACKING and FEATURE_SUN_TRACKING requires a clock feature to be activated" 91 | #endif 92 | 93 | #if defined(FEATURE_GPS) && !defined(FEATURE_CLOCK) 94 | #define FEATURE_CLOCK 95 | #endif 96 | 97 | #if defined(FEATURE_RTC_DS1307)|| defined(FEATURE_RTC_PCF8583) 98 | #define FEATURE_RTC 99 | #endif 100 | 101 | #if defined(FEATURE_RTC_DS1307) || defined(FEATURE_RTC_PCF8583) || defined(FEATURE_I2C_LCD) || defined(FEATURE_AZ_POSITION_HMC5883L) || defined(FEATURE_AZ_POSITION_ADAFRUIT_LSM303) || defined(FEATURE_EL_POSITION_ADAFRUIT_LSM303) || defined(FEATURE_AZ_POSITION_POLOLU_LSM303) || defined(FEATURE_EL_POSITION_POLOLU_LSM303) || defined(FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB) || defined(FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB) || defined(FEATURE_AZ_POSITION_HMC5883L_USING_JARZEBSKI_LIBRARY) || defined(FEATURE_AZ_POSITION_DFROBOT_QMC5883) || defined(FEATURE_AZ_POSITION_MECHASOLUTION_QMC5883) || defined(FEATURE_HD44780_I2C_DISPLAY) 102 | #define FEATURE_WIRE_SUPPORT 103 | #endif 104 | 105 | #if defined(FEATURE_RTC_DS1307) && defined(FEATURE_RTC_PCF8583) 106 | #error "You can't have two RTC features enabled!" 107 | #endif 108 | 109 | #if defined(FEATURE_REMOTE_UNIT_SLAVE) && defined(OPTION_SYNC_MASTER_CLOCK_TO_SLAVE) 110 | #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" 111 | #endif 112 | 113 | #if defined(FEATURE_REMOTE_UNIT_SLAVE) && defined(OPTION_SYNC_MASTER_COORDINATES_TO_SLAVE) 114 | #error "You can't define both FEATURE_REMOTE_UNIT_SLAVE and OPTION_SYNC_MASTER_COORDINATES_TO_SLAVE - use OPTION_SYNC_MASTER_COORDINATES_TO_SLAVE on the master unit" 115 | #endif 116 | 117 | #if defined(FEATURE_MASTER_WITH_ETHERNET_SLAVE) && !defined(FEATURE_ETHERNET) 118 | #error "FEATURE_MASTER_WITH_ETHERNET_SLAVE requires FEATURE_ETHERNET" 119 | #endif 120 | 121 | #if defined(HARDWARE_EA4TX_ARS_USB) && !defined(FEATURE_4_BIT_LCD_DISPLAY) 122 | #define FEATURE_4_BIT_LCD_DISPLAY 123 | #endif 124 | 125 | #if defined(HARDWARE_EA4TX_ARS_USB) && defined(FEATURE_ELEVATION_CONTROL) 126 | #define HACK_REDUCED_DEBUG 127 | #endif 128 | 129 | #if defined(FEATURE_AUTOPARK) && !defined(FEATURE_PARK) 130 | #define FEATURE_PARK 131 | #endif 132 | 133 | #if defined(FEATURE_YAESU_EMULATION) || defined(FEATURE_EASYCOM_EMULATION) || defined(FEATURE_DCU_1_EMULATION) 134 | #define CONTROL_PROTOCOL_EMULATION 135 | #endif 136 | 137 | #if (defined(OPTION_SAVE_MEMORY_EXCLUDE_EXTENDED_COMMANDS) || defined(OPTION_SAVE_MEMORY_EXCLUDE_BACKSLASH_CMDS)) && defined(FEATURE_NEXTION_DISPLAY) 138 | #error "FEATURE_NEXTION_DISPLAY requires extended commands. Disable OPTION_SAVE_MEMORY_EXCLUDE_EXTENDED_COMMANDS and OPTION_SAVE_MEMORY_EXCLUDE_BACKSLASH_CMDS." 139 | #endif 140 | 141 | #if defined(FEATURE_SATELLITE_TRACKING) && !defined(FEATURE_ELEVATION_CONTROL) 142 | #error "FEATURE_SATELLITE_TRACKING requires FEATURE_ELEVATION_CONTROL" 143 | #endif 144 | 145 | #if defined(FEATURE_SATELLITE_TRACKING) && !defined(FEATURE_CLOCK) 146 | #error "FEATURE_SATELLITE_TRACKING requires FEATURE_CLOCK" 147 | #endif 148 | 149 | 150 | -------------------------------------------------------------------------------- /k3ng_rotator_controller/rotator.h: -------------------------------------------------------------------------------- 1 | /*---------------------- macros - don't touch these unless you know what you are doing ---------------------*/ 2 | #define AZ 1 3 | #define EL 2 4 | 5 | #define DIR_CCW 0x10 // CW Encoder Code (Do not change) 6 | #define DIR_CW 0x20 // CCW Encoder Code (Do not change) 7 | 8 | #define BRAKE_RELEASE_OFF 0 9 | #define BRAKE_RELEASE_ON 1 10 | 11 | //az_state 12 | #define IDLE 0 13 | #define SLOW_START_CW 1 14 | #define SLOW_START_CCW 2 15 | #define NORMAL_CW 3 16 | #define NORMAL_CCW 4 17 | #define SLOW_DOWN_CW 5 18 | #define SLOW_DOWN_CCW 6 19 | #define INITIALIZE_SLOW_START_CW 7 20 | #define INITIALIZE_SLOW_START_CCW 8 21 | #define INITIALIZE_TIMED_SLOW_DOWN_CW 9 22 | #define INITIALIZE_TIMED_SLOW_DOWN_CCW 10 23 | #define TIMED_SLOW_DOWN_CW 11 24 | #define TIMED_SLOW_DOWN_CCW 12 25 | #define INITIALIZE_DIR_CHANGE_TO_CW 13 26 | #define INITIALIZE_DIR_CHANGE_TO_CCW 14 27 | #define INITIALIZE_NORMAL_CW 15 28 | #define INITIALIZE_NORMAL_CCW 16 29 | 30 | //el_state 31 | #define SLOW_START_UP 1 32 | #define SLOW_START_DOWN 2 33 | #define NORMAL_UP 3 34 | #define NORMAL_DOWN 4 35 | #define SLOW_DOWN_DOWN 5 36 | #define SLOW_DOWN_UP 6 37 | #define INITIALIZE_SLOW_START_UP 7 38 | #define INITIALIZE_SLOW_START_DOWN 8 39 | #define INITIALIZE_TIMED_SLOW_DOWN_UP 9 40 | #define INITIALIZE_TIMED_SLOW_DOWN_DOWN 10 41 | #define TIMED_SLOW_DOWN_UP 11 42 | #define TIMED_SLOW_DOWN_DOWN 12 43 | #define INITIALIZE_DIR_CHANGE_TO_UP 13 44 | #define INITIALIZE_DIR_CHANGE_TO_DOWN 14 45 | #define INITIALIZE_NORMAL_UP 15 46 | #define INITIALIZE_NORMAL_DOWN 16 47 | 48 | //az_request & el_request 49 | #define REQUEST_STOP 0 50 | #define REQUEST_AZIMUTH 1 51 | #define REQUEST_AZIMUTH_RAW 2 52 | #define REQUEST_CW 3 53 | #define REQUEST_CCW 4 54 | #define REQUEST_UP 5 55 | #define REQUEST_DOWN 6 56 | #define REQUEST_ELEVATION 7 57 | #define REQUEST_KILL 8 58 | 59 | #define DEACTIVATE 0 60 | #define ACTIVATE 1 61 | 62 | #define CW 1 63 | #define CCW 2 64 | #define STOP_AZ 3 65 | #define STOP_EL 4 66 | #define UP 5 67 | #define DOWN 6 68 | #define STOP 7 69 | 70 | //az_request_queue_state & el_request_queue_state 71 | #define NONE 0 72 | #define IN_QUEUE 1 73 | #define IN_PROGRESS_TIMED 2 74 | #define IN_PROGRESS_TO_TARGET 3 75 | 76 | #define EMPTY 0 77 | #define LOADED_AZIMUTHS 1 78 | #define RUNNING_AZIMUTHS 2 79 | #define LOADED_AZIMUTHS_ELEVATIONS 3 80 | #define RUNNING_AZIMUTHS_ELEVATIONS 4 81 | 82 | #define RED 0x1 83 | #define YELLOW 0x3 84 | #define GREEN 0x2 85 | #define TEAL 0x6 86 | #define BLUE 0x4 87 | #define VIOLET 0x5 88 | #define WHITE 0x7 89 | 90 | #define LCD_UNDEF 0 91 | #define LCD_HEADING 1 92 | #define LCD_IDLE_STATUS 2 93 | #define LCD_TARGET_AZ 3 94 | #define LCD_TARGET_EL 4 95 | #define LCD_TARGET_AZ_EL 5 96 | #define LCD_ROTATING_CW 6 97 | #define LCD_ROTATING_CCW 7 98 | #define LCD_ROTATING_TO 8 99 | #define LCD_ELEVATING_TO 9 100 | #define LCD_ELEVATING_UP 10 101 | #define LCD_ELEVATING_DOWN 11 102 | #define LCD_ROTATING_AZ_EL 12 103 | #define LCD_PARKED 13 104 | 105 | #define ENCODER_IDLE 0 106 | #define ENCODER_AZ_PENDING 1 107 | #define ENCODER_EL_PENDING 2 108 | #define ENCODER_AZ_EL_PENDING 3 109 | 110 | #define NOT_DOING_ANYTHING 0 111 | #define ROTATING_CW 1 112 | #define ROTATING_CCW 2 113 | #define ROTATING_UP 3 114 | #define ROTATING_DOWN 4 115 | 116 | #define REMOTE_UNIT_NO_COMMAND 0 117 | #define REMOTE_UNIT_AZ_COMMAND 1 118 | #define REMOTE_UNIT_EL_COMMAND 2 119 | #define REMOTE_UNIT_OTHER_COMMAND 3 120 | #define REMOTE_UNIT_AW_COMMAND 4 121 | #define REMOTE_UNIT_DHL_COMMAND 5 122 | #define REMOTE_UNIT_DOI_COMMAND 6 123 | #define REMOTE_UNIT_CL_COMMAND 7 124 | #define REMOTE_UNIT_RC_COMMAND 8 125 | #define REMOTE_UNIT_GS_COMMAND 9 126 | 127 | #define NOT_PARKED 0 128 | #define PARK_INITIATED 1 129 | #define PARKED 2 130 | 131 | #define COORDINATES 1 132 | #define MAIDENHEAD 2 133 | 134 | #define FREE_RUNNING 0 135 | #define GPS_SYNC 1 136 | #define RTC_SYNC 2 137 | #define SLAVE_SYNC 3 138 | #define SLAVE_SYNC_GPS 4 139 | #define NOT_PROVISIONED 255 140 | 141 | #define CONTROL_PORT0 1 142 | #define ETHERNET_PORT0 2 143 | #define ETHERNET_PORT1 4 144 | 145 | #define CLIENT_INACTIVE 0 146 | #define CLIENT_ACTIVE 1 147 | 148 | #define LEFT 1 149 | #define RIGHT 2 150 | #define CENTER 3 151 | 152 | #define STEPPER_UNDEF 0 153 | #define STEPPER_CW 1 154 | #define STEPPER_CCW 2 155 | #define STEPPER_UP 3 156 | #define STEPPER_DOWN 4 157 | 158 | #define ETHERNET_SLAVE_DISCONNECTED 0 159 | #define ETHERNET_SLAVE_CONNECTED 1 160 | 161 | #define AUTOCORRECT_INACTIVE 0 162 | #define AUTOCORRECT_WAITING_AZ 1 163 | #define AUTOCORRECT_WAITING_EL 2 164 | #define AUTOCORRECT_WATCHING_AZ 3 165 | #define AUTOCORRECT_WATCHING_EL 4 166 | 167 | #define AZ_DISPLAY_MODE_NORMAL 0 168 | #define AZ_DISPLAY_MODE_RAW 1 169 | #define AZ_DISPLAY_MODE_OVERLAP_PLUS 2 170 | 171 | #define AUDIBLE_ALERT_SERVICE 0 172 | #define AUDIBLE_ALERT_ACTIVATE 1 173 | 174 | 175 | // for debugging 176 | #define DBG_CHECK_AZ_PRESET_POT 44 177 | #define DBG_CHECK_PRESET_ENCODERS_NOT_IDLE 45 178 | 179 | #define DBG_CHECK_PRESET_ENCODERS_PENDING 47 180 | 181 | #define DBG_CHECK_AZ_MANUAL_ROTATE_LIMIT_CCW 49 182 | #define DBG_CHECK_AZ_MANUAL_ROTATE_LIMIT_CW 50 183 | #define DBG_CHECK_EL_MANUAL_ROTATE_LIMIT_DOWN 51 184 | #define DBG_CHECK_EL_MANUAL_ROTATE_LIMIT_UP 52 185 | 186 | #define DBG_CHECK_BUTTONS_BTN_CW 61 187 | #define DBG_CHECK_BUTTONS_BTN_CCW 62 188 | #define DBG_CHECK_BUTTONS_ADAFRUIT_STOP 63 189 | #define DBG_CHECK_BUTTONS_RELEASE_NO_SLOWDOWN 64 190 | #define DBG_CHECK_BUTTONS_RELEASE_KILL 65 191 | 192 | #define DBG_PROCESS_DCU_1 233 193 | 194 | #define DBG_STOP_ROTATION 238 195 | #define DBG_SERVICE_SATELLITE_CLI_CMD_PREROTATE 239 196 | #define DBG_BACKSLASH_GT_CMD 240 197 | #define DBG_BACKSLASH_GC_CMD 241 198 | #define DBG_CHECK_BUTTONS_SATELLITE 244 199 | #define DBG_SERVICE_MOON_CLI_CMD 245 200 | #define DBG_SERVICE_SUN_CLI_CMD 246 201 | #define DBG_SERVICE_SATELLITE_CLI_CMD 247 202 | #define DBG_SERVICE_SATELLITE_TRACKING 248 203 | #define DBG_NEXTION_DATA_ENT_ENTER_PUSH_CALLBK 249 204 | #define DBG_NEXTION_BUTTON 250 205 | #define DBG_CHECK_BUTTONS_SUN 251 206 | #define DBG_CHECK_BUTTONS_MOON 252 207 | #define DBG_SERVICE_SUN_TRACKING 253 208 | #define DBG_SERVICE_MOON_TRACKING 254 209 | 210 | #define NEXTION_API_SYSTEM_CAPABILITIES_GS_232A 1 211 | #define NEXTION_API_SYSTEM_CAPABILITIES_GS_232B 2 212 | #define NEXTION_API_SYSTEM_CAPABILITIES_EASYCOM 4 213 | #define NEXTION_API_SYSTEM_CAPABILITIES_DCU_1 8 214 | #define NEXTION_API_SYSTEM_CAPABILITIES_ELEVATION 16 215 | #define NEXTION_API_SYSTEM_CAPABILITIES_CLOCK 32 216 | #define NEXTION_API_SYSTEM_CAPABILITIES_GPS 64 217 | #define NEXTION_API_SYSTEM_CAPABILITIES_MOON 128 218 | #define NEXTION_API_SYSTEM_CAPABILITIES_SUN 256 219 | #define NEXTION_API_SYSTEM_CAPABILITIES_RTC 512 220 | #define NEXTION_API_SYSTEM_CAPABILITIES_SATELLITE 1024 221 | #define NEXTION_API_SYSTEM_CAPABILITIES_PARK 2048 222 | #define NEXTION_API_SYSTEM_CAPABILITIES_AUTOPARK 4096 223 | 224 | #define NEXTION_API_SYSTEM_CAPABILITIES_ENGLISH 1 225 | #define NEXTION_API_SYSTEM_CAPABILITIES_SPANISH 2 226 | #define NEXTION_API_SYSTEM_CAPABILITIES_CZECH 4 227 | #define NEXTION_API_SYSTEM_CAPABILITIES_PORTUGUESE_BRASIL 8 228 | #define NEXTION_API_SYSTEM_CAPABILITIES_GERMAN 16 229 | #define NEXTION_API_SYSTEM_CAPABILITIES_FRENCH 32 230 | 231 | #define DCU_1_SEMICOLON 1 232 | #define DCU_1_CARRIAGE_RETURN 2 233 | 234 | #define DEBUG_PROCESSES_SERVICE 1 235 | #define DEBUG_PROCESSES_PROCESS_ENTER 2 236 | #define DEBUG_PROCESSES_PROCESS_EXIT 3 237 | 238 | #define PROCESS_LOOP 0 239 | #define PROCESS_READ_HEADINGS 1 240 | #define PROCESS_CHECK_SERIAL 2 241 | #define PROCESS_SERVICE_NEXTION 3 242 | #define PROCESS_UPDATE_LCD_DISPLAY 4 243 | #define PROCESS_SERVICE_ROTATION 5 244 | #define PROCESS_UPDATE_SUN_POSITION 6 245 | #define PROCESS_UPDATE_MOON_POSITION 7 246 | #define PROCESS_UPDATE_TIME 8 247 | #define PROCESS_SERVICE_GPS 9 248 | #define PROCESS_CHECK_FOR_DIRTY_CONFIGURATION 10 249 | #define PROCESS_CHECK_BUTTONS 11 250 | #define PROCESS_MISC_ADMIN 12 251 | #define PROCESS_DEBUG 13 252 | 253 | #define PROCESS_TABLE_SIZE 14 254 | 255 | #define COORDINATE_PLANE_NORMAL 0 256 | #define COORDINATE_PLANE_UPPER_LEFT_ORIGIN 1 257 | 258 | #define DEACTIVATE_ALL 0 259 | #define DEACTIVATE_MOON_TRACKING 1 260 | #define DEACTIVATE_SUN_TRACKING 2 261 | #define DEACTIVATE_SATELLITE_TRACKING 3 262 | #define ACTIVATE_MOON_TRACKING 4 263 | #define ACTIVATE_SUN_TRACKING 5 264 | #define ACTIVATE_SATELLITE_TRACKING 6 265 | 266 | // #define UPDATE_CURRENT_SAT_AZ_EL_NEXT_AOS_AND_LOS 0 //*** 267 | #define PRINT_AOS_LOS_MULTILINE_REPORT 1 268 | #define PRINT_AOS_LOS_TABULAR_REPORT 2 269 | // #define UPDATE_CURRENT_SAT_JUST_AZ_EL 3 //**** 270 | #define UPDATE_SAT_ARRAY_SLOT_AZ_EL_NEXT_AOS_LOS 4 271 | #define UPDATE_SAT_ARRAY_SLOT_JUST_AZ_EL 5 272 | 273 | #define DO_NOT_INCLUDE_RESPONSE_CODE 0 274 | #define INCLUDE_RESPONSE_CODE 1 275 | 276 | #define SERVICE_CALC_SERVICE 0 277 | #define SERVICE_CALC_INITIALIZE 1 278 | #define SERVICE_CALC_REPORT_STATE 2 279 | 280 | #define SERVICE_CALC_DO_NOT_PRINT_DONE 0 281 | #define SERVICE_CALC_PRINT_DONE 1 282 | 283 | #define SERVICE_CALC_DO_NOT_PRINT_HEADER 0 284 | #define SERVICE_CALC_PRINT_HEADER 1 285 | 286 | #define CLOCK_DEFAULT_YEAR_AT_BOOTUP 2020 287 | #define CLOCK_DEFAULT_MONTH_AT_BOOTUP 8 288 | #define CLOCK_DEFAULT_DAY_AT_BOOTUP 15 289 | #define CLOCK_DEFAULT_HOURS_AT_BOOTUP 0 290 | #define CLOCK_DEFAULT_MINUTES_AT_BOOTUP 0 291 | #define CLOCK_DEFAULT_SECONDS_AT_BOOTUP 0 292 | 293 | #define DO_NOT_LOAD_HARDCODED_TLE 0 294 | #define LOAD_HARDCODED_TLE 1 295 | 296 | #define MAKE_IT_THE_CURRENT_SATELLITE 0 297 | #define DO_NOT_MAKE_IT_THE_CURRENT_SATELLITE 1 298 | 299 | #define NOT_VERBOSE 0 300 | #define _VERBOSE_ 1 301 | 302 | #define SERVICE_IDLE 0 303 | #define SERVICE_CALC_IN_PROGRESS 1 304 | 305 | #define VT100_CODE_CHAR_ATTR_OFF "[0m" 306 | #define VT100_CODE_BLINK "[5m" 307 | #define VT100_CLEAR_SCREEN "[2J" 308 | #define VT100_CURSOR_UPPER_LEFT_CORNER "[f" 309 | #define VT100_BOLD "[1m" 310 | 311 | 312 | /* ------end of macros ------- */ 313 | 314 | -------------------------------------------------------------------------------- /k3ng_rotator_controller/rotator_pins_k3ng_g1000.h: -------------------------------------------------------------------------------- 1 | /* ------------------------------------- Pin Definitions ------------------------------------------ 2 | 3 | You need to look at these and set them appropriately ! 4 | 5 | Most pins can be disabled by setting them to 0 (zero). If you're not using a pin or function, set it to 0. 6 | 7 | Pins > 99 = remote unit pin, for example: pin 109 = pin 9 on remote unit, pin A0+100 = pin A0 on remote unit 8 | 9 | */ 10 | 11 | /* azimuth pins --------------------- (use just the azimuth pins for an azimuth-only rotator) */ 12 | // alternate pinouts for K3NG's personal setup 13 | #define rotate_cw A2 // goes high to activate rotator R (CW) rotation - pin 1 on Yaesu connector 14 | #define rotate_ccw A1 // goes high to activate rotator L (CCW) rotation - pin 2 on Yaesu connector 15 | #define button_cw 0 16 | #define button_ccw 0 17 | #define rotate_cw_pwm 0 // optional - PWM CW output - set to 0 to disable (must be PWM capable pin) 18 | #define rotate_ccw_pwm 0 // optional - PWM CCW output - set to 0 to disable (must be PWM capable pin) 19 | #define rotate_cw_ccw_pwm 0 // optional - PWM on CW and CCW output - set to 0 to disable (must be PWM capable pin) 20 | #define rotate_cw_freq 0 // optional - CW variable frequency output 21 | #define rotate_ccw_freq 0 // optional - CCW variable frequency output 22 | #define button_cw 0 // normally open button to ground for manual CW rotation (schematic pin: A1) 23 | #define button_ccw 0 // normally open button to ground for manual CCW rotation (schematic pin: A2) 24 | #define serial_led 0 // LED blinks when command is received on serial port (set to 0 to disable) 25 | #define rotator_analog_az A0 // reads analog azimuth voltage from rotator - pin 4 on Yaesu connector 26 | #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) 27 | #define overlap_led 0 // line goes high when azimuth rotator is in overlap (> 360 rotators) 28 | #define brake_az 0 // goes high to disengage azimuth brake (set to 0 to disable) 29 | #define az_speed_pot 0 // connect to wiper of 1K to 10K potentiometer for speed control (set to 0 to disable) 30 | #define az_preset_pot 0 // connect to wiper of 1K to 10K potentiometer for preset control (set to 0 to disable) 31 | #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) 32 | #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) 33 | #define rotation_indication_pin 0 34 | #define blink_led 0 35 | 36 | /*----------- elevation pins --------------*/ 37 | #ifdef FEATURE_ELEVATION_CONTROL 38 | #define rotate_up 8 // goes high to activate rotator elevation up 39 | #define rotate_down 9 // goes high to activate rotator elevation down 40 | #define rotate_up_or_down 0 // goes high when elevation up or down is activated 41 | #define rotate_up_pwm 0 // optional - PWM UP output - set to 0 to disable (must be PWM capable pin) 42 | #define rotate_down_pwm 0 // optional - PWM DOWN output - set to 0 to disable (must be PWM capable pin) 43 | #define rotate_up_down_pwm 0 // optional - PWM on both UP and DOWN (must be PWM capable pin) 44 | #define rotate_up_freq 0 // optional - UP variable frequency output 45 | #define rotate_down_freq 0 // optional - UP variable frequency output 46 | #define rotator_analog_el 0 //A1 // reads analog elevation voltage from rotator 47 | #define button_up 0 // normally open button to ground for manual up elevation 48 | #define button_down 0 // normally open button to ground for manual down rotation 49 | #define brake_el 0 // goes high to disengage elevation brake (set to 0 to disable) 50 | #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) 51 | #endif //FEATURE_ELEVATION_CONTROL 52 | 53 | // rotary encoder pins and options 54 | #ifdef FEATURE_AZ_PRESET_ENCODER 55 | #define az_rotary_preset_pin1 0 // CW Encoder Pin 56 | #define az_rotary_preset_pin2 0 // CCW Encoder Pin 57 | #endif //FEATURE_AZ_PRESET_ENCODER 58 | 59 | #ifdef FEATURE_EL_PRESET_ENCODER 60 | #define el_rotary_preset_pin1 0 // UP Encoder Pin 61 | #define el_rotary_preset_pin2 0 // DOWN Encoder Pin 62 | #endif //FEATURE_EL_PRESET_ENCODER 63 | 64 | #ifdef FEATURE_AZ_POSITION_ROTARY_ENCODER 65 | #define az_rotary_position_pin1 0 // CW Encoder Pin 66 | #define az_rotary_position_pin2 0 // CCW Encoder Pin 67 | #endif //FEATURE_AZ_POSITION_ROTARY_ENCODER 68 | 69 | #ifdef FEATURE_EL_POSITION_ROTARY_ENCODER 70 | #define el_rotary_position_pin1 0 // CW Encoder Pin 71 | #define el_rotary_position_pin2 0 // CCW Encoder Pin 72 | #endif //FEATURE_EL_POSITION_ROTARY_ENCODER 73 | 74 | #ifdef FEATURE_AZ_POSITION_PULSE_INPUT 75 | #define az_position_pulse_pin 0 // must be an interrupt capable pin! 76 | #define AZ_POSITION_PULSE_PIN_INTERRUPT 0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 77 | #endif // read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts 78 | 79 | #ifdef FEATURE_EL_POSITION_PULSE_INPUT 80 | #define el_position_pulse_pin 1 // must be an interrupt capable pin! 81 | #define EL_POSITION_PULSE_PIN_INTERRUPT 1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 82 | #endif // read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts 83 | 84 | #ifdef FEATURE_PARK 85 | #define button_park 0 86 | #endif 87 | 88 | //classic 4 bit LCD pins 89 | #define lcd_4_bit_rs_pin 12 90 | #define lcd_4_bit_enable_pin 11 91 | #define lcd_4_bit_d4_pin 5 92 | #define lcd_4_bit_d5_pin 4 93 | #define lcd_4_bit_d6_pin 3 94 | #define lcd_4_bit_d7_pin 2 95 | 96 | 97 | #ifdef FEATURE_JOYSTICK_CONTROL 98 | #define pin_joystick_x A0 99 | #define pin_joystick_y A1 100 | #endif //FEATURE_JOYSTICK_CONTROL 101 | 102 | #ifdef FEATURE_AZ_POSITION_HH12_AS5045_SSI 103 | #define az_hh12_clock_pin 11 104 | #define az_hh12_cs_pin 12 105 | #define az_hh12_data_pin 13 106 | #endif //FEATURE_AZ_POSITION_HH_12 107 | 108 | #ifdef FEATURE_EL_POSITION_HH12_AS5045_SSI 109 | #define el_hh12_clock_pin 11 110 | #define el_hh12_cs_pin 12 111 | #define el_hh12_data_pin 13 112 | #endif //FEATURE_EL_POSITION_HH_12 113 | 114 | #ifdef FEATURE_PARK 115 | #define park_in_progress_pin 0 // goes high when a park has been initiated and rotation is in progress 116 | #define parked_pin 0 // goes high when in a parked position 117 | #endif //FEATURE_PARK 118 | 119 | #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 120 | 121 | #ifdef FEATURE_LIMIT_SENSE 122 | #define az_limit_sense_pin 0 // input - low stops azimuthal rotation 123 | #define el_limit_sense_pin 0 // input - low stops elevation rotation 124 | #endif //FEATURE_LIMIT_SENSE 125 | 126 | #ifdef FEATURE_AZ_POSITION_INCREMENTAL_ENCODER 127 | #define az_incremental_encoder_pin_phase_a 2 // must be an interrupt capable pin 128 | #define az_incremental_encoder_pin_phase_b 3 // must be an interrupt capable pin 129 | #define az_incremental_encoder_pin_phase_z 4 130 | #define AZ_POSITION_INCREMENTAL_ENCODER_A_PIN_INTERRUPT 0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 131 | #define AZ_POSITION_INCREMENTAL_ENCODER_B_PIN_INTERRUPT 1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 132 | // read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts 133 | #endif //FEATURE_AZ_POSITION_INCREMENTAL_ENCODER 134 | 135 | #ifdef FEATURE_EL_POSITION_INCREMENTAL_ENCODER 136 | #define el_incremental_encoder_pin_phase_a 2 // must be an interrupt capable pin 137 | #define el_incremental_encoder_pin_phase_b 3 // must be an interrupt capable pin 138 | #define el_incremental_encoder_pin_phase_z 4 139 | #define EL_POSITION_INCREMENTAL_ENCODER_A_PIN_INTERRUPT 0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 140 | #define EL_POSITION_INCREMENTAL_ENCODER_B_PIN_INTERRUPT 1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 141 | // read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts 142 | #endif //FEATURE_EL_POSITION_INCREMENTAL_ENCODER 143 | 144 | #ifdef FEATURE_YOURDUINO_I2C_LCD 145 | #define En_pin 2 146 | #define Rw_pin 1 147 | #define Rs_pin 0 148 | #define D4_pin 4 149 | #define D5_pin 5 150 | #define D6_pin 6 151 | #define D7_pin 7 152 | #endif //FEATURE_YOURDUINO_I2C_LCD 153 | 154 | #ifdef FEATURE_MOON_TRACKING 155 | #define moon_tracking_active_pin 0 // goes high when moon tracking is active 156 | #define moon_tracking_activate_line 0 // ground this pin to activate moon tracking (not for use with a button) 157 | #define moon_tracking_button 0 // use with a normally open momentary switch to ground 158 | #endif //FEATURE_MOON_TRACKING 159 | 160 | #ifdef FEATURE_SUN_TRACKING 161 | #define sun_tracking_active_pin 13 // goes high when sun tracking is active 162 | #define sun_tracking_activate_line 0 // ground this pin to activate sun tracking (not for use with a button) 163 | #define sun_tracking_button 30 // use with a normally open momentary switch to ground 164 | #endif //FEATURE_SUN_TRACKING 165 | 166 | #ifdef FEATURE_GPS 167 | #define gps_sync 0 168 | #endif //FEATURE_GPS 169 | 170 | 171 | // #define pin_led_cw 0 172 | // #define pin_led_ccw 0 173 | // #define pin_led_up 0 174 | // #define pin_led_down 0 175 | 176 | #ifdef FEATURE_AUTOPARK 177 | #define pin_autopark_disable 0 // Pull low to disable autopark 178 | #define pin_autopark_timer_reset 0 // Pull low to reset the autopark timer (tie in with rig PTT) 179 | #endif 180 | 181 | #ifdef FEATURE_AUDIBLE_ALERT 182 | #define pin_audible_alert 0 183 | #endif 184 | 185 | //#define pin_status_led 0 // Status LED - blinks when there is rotation in progress 186 | 187 | // Added 2020.07.24.01 188 | #define satellite_tracking_active_pin 0 189 | #define satellite_tracking_activate_line 0 190 | #define satellite_tracking_button 0 // use with a normally open momentary switch to ground -------------------------------------------------------------------------------- /k3ng_rotator_controller/rotator_pins_m0upu.h: -------------------------------------------------------------------------------- 1 | /* LEDs left to right 2 | 6 - PWM 3 | 7 - NO PWM 4 | 8 - NO PWM 5 | 9 - PWM 6 | 7 | */ 8 | 9 | 10 | #define pins_h 11 | #define rotate_cw 6 // goes high to activate rotator R (CW) rotation - pin 1 on Yaesu connector 12 | #define rotate_ccw 7 // goes high to activate rotator L (CCW) rotation - pin 2 on Yaesu connector 13 | #define rotate_cw_ccw 0 // goes high for both CW and CCW rotation 14 | #define rotate_cw_pwm 0 // optional - PWM CW output - set to 0 to disable (must be PWM capable pin) 15 | #define rotate_ccw_pwm 0 // optional - PWM CCW output - set to 0 to disable (must be PWM capable pin) 16 | #define rotate_cw_ccw_pwm 0 17 | #define rotate_cw_freq 0 18 | #define rotate_ccw_freq 0 19 | #define button_cw 0 //A1 // normally open button to ground for manual CW rotation 20 | #define button_ccw 0 //A2 // normally open button to ground for manual CCW rotation 21 | #define serial_led 13 //0 // LED blinks when command is received on serial port (set to 0 to disable) 22 | #define rotator_analog_az A0 // reads analog azimuth voltage from rotator - pin 4 on Yaesu connector 23 | #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) 24 | #define overlap_led 0 // line goes active when azimuth rotator is in overlap (> 360 rotators) 25 | #define brake_az 13 //0 // goes high to disengage azimuth brake (set to 0 to disable) 26 | #define az_speed_pot 0 //A4 // connect to wiper of 1K to 10K potentiometer for speed control (set to 0 to disable) 27 | #define az_preset_pot 0 // connect to wiper of 1K to 10K potentiometer for preset control (set to 0 to disable) 28 | #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) 29 | #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) 30 | #define rotation_indication_pin 0 31 | #define az_stepper_motor_pulse 0 32 | #define az_stepper_motor_direction 0 33 | #define az_rotation_stall_detected 0 34 | 35 | 36 | // elevation pins 37 | #ifdef FEATURE_ELEVATION_CONTROL 38 | #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) 39 | #define rotate_up 9//9 // goes high to activate rotator elevation up 40 | #define rotate_down 8 // goes high to activate rotator elevation down 41 | #define rotate_up_or_down 0 42 | #define rotate_up_pwm 0 43 | #define rotate_down_pwm 0 44 | #define rotate_up_down_pwm 0 45 | #define rotate_up_freq 0 46 | #define rotate_down_freq 0 47 | #define rotator_analog_el A1 // reads analog elevation voltage from rotator 48 | #define button_up 0 // normally open button to ground for manual up elevation 49 | #define button_down 0 // normally open button to ground for manual down rotation 50 | #define brake_el 0 // goes high to disengage elevation brake (set to 0 to disable) 51 | #define el_stepper_motor_pulse 0 52 | #define el_stepper_motor_direction 0 53 | #define el_rotation_stall_detected 0 54 | #endif //FEATURE_ELEVATION_CONTROL 55 | 56 | 57 | // rotary encoder pins and options 58 | #ifdef FEATURE_AZ_PRESET_ENCODER 59 | #define az_rotary_preset_pin1 A3 //6 // CW Encoder Pin 60 | #define az_rotary_preset_pin2 A2 //7 // CCW Encoder Pin 61 | #endif //FEATURE_AZ_PRESET_ENCODER 62 | 63 | #ifdef FEATURE_EL_PRESET_ENCODER 64 | #define el_rotary_preset_pin1 0 // A3 //6 // UP Encoder Pin 65 | #define el_rotary_preset_pin2 0 // A2 //7 // DOWN Encoder Pin 66 | #endif //FEATURE_EL_PRESET_ENCODER 67 | 68 | #if defined(FEATURE_AZ_POSITION_ROTARY_ENCODER) || defined(FEATURE_AZ_POSITION_ROTARY_ENCODER_USE_PJRC_LIBRARY) 69 | #define az_rotary_position_pin1 A3 // CW Encoder Pin 70 | #define az_rotary_position_pin2 A2 // CCW Encoder Pin 71 | #endif //FEATURE_AZ_POSITION_ROTARY_ENCODER 72 | 73 | #if defined(FEATURE_EL_POSITION_ROTARY_ENCODER) || defined(FEATURE_EL_POSITION_ROTARY_ENCODER_USE_PJRC_LIBRARY) 74 | #define el_rotary_position_pin1 0 // CW Encoder Pin 75 | #define el_rotary_position_pin2 0 // CCW Encoder Pin 76 | #endif //FEATURE_EL_POSITION_ROTARY_ENCODER 77 | 78 | #ifdef FEATURE_AZ_POSITION_PULSE_INPUT 79 | #define az_position_pulse_pin 0 // must be an interrupt capable pin! 80 | #define AZ_POSITION_PULSE_PIN_INTERRUPT 0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 81 | #endif // read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts 82 | 83 | #ifdef FEATURE_EL_POSITION_PULSE_INPUT 84 | #define el_position_pulse_pin 0 // must be an interrupt capable pin! 85 | #define EL_POSITION_PULSE_PIN_INTERRUPT 1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 86 | #endif // read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts 87 | 88 | #ifdef FEATURE_PARK 89 | #define button_park 0 90 | #endif 91 | 92 | 93 | #define lcd_4_bit_rs_pin 12 94 | #define lcd_4_bit_enable_pin 11 95 | #define lcd_4_bit_d4_pin 5 96 | #define lcd_4_bit_d5_pin 4 97 | #define lcd_4_bit_d6_pin 3 98 | #define lcd_4_bit_d7_pin 2 99 | 100 | 101 | #ifdef FEATURE_JOYSTICK_CONTROL 102 | #define pin_joystick_x A2 103 | #define pin_joystick_y A3 104 | #endif //FEATURE_JOYSTICK_CONTROL 105 | 106 | #define blink_led 0 //13 107 | 108 | #ifdef FEATURE_AZ_POSITION_HH12_AS5045_SSI 109 | #define az_hh12_clock_pin 11 110 | #define az_hh12_cs_pin 12 111 | #define az_hh12_data_pin 13 112 | #endif //FEATURE_AZ_POSITION_HH_12 113 | 114 | #ifdef FEATURE_EL_POSITION_HH12_AS5045_SSI 115 | #define el_hh12_clock_pin 11 116 | #define el_hh12_cs_pin 12 117 | #define el_hh12_data_pin 13 118 | #endif //FEATURE_EL_POSITION_HH_12 119 | 120 | #ifdef FEATURE_PARK 121 | #define park_in_progress_pin 0 // goes high when a park has been initiated and rotation is in progress 122 | #define parked_pin 0 // goes high when in a parked position 123 | #endif //FEATURE_PARK 124 | 125 | #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 126 | 127 | #ifdef FEATURE_LIMIT_SENSE 128 | #define az_limit_sense_pin 0 // input - low stops azimuthal rotation 129 | #define el_limit_sense_pin 0 // input - low stops elevation rotation 130 | #endif //FEATURE_LIMIT_SENSE 131 | 132 | #ifdef FEATURE_AZ_POSITION_INCREMENTAL_ENCODER 133 | #define az_incremental_encoder_pin_phase_a 18 //3 must be an interrupt capable pin 134 | #define az_incremental_encoder_pin_phase_b 19 //3 // must be an interrupt capable pin 135 | #define az_incremental_encoder_pin_phase_z 22 //4 136 | #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 137 | #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 138 | // read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts 139 | #endif //FEATURE_AZ_POSITION_INCREMENTAL_ENCODER 140 | 141 | #ifdef FEATURE_EL_POSITION_INCREMENTAL_ENCODER 142 | #define el_incremental_encoder_pin_phase_a 2 //18 //2 // must be an interrupt capable pin 143 | #define el_incremental_encoder_pin_phase_b 3 //19 //3 // must be an interrupt capable pin 144 | #define el_incremental_encoder_pin_phase_z 5 //22 //4 145 | #define EL_POSITION_INCREMENTAL_ENCODER_A_PIN_INTERRUPT 0 //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 146 | #define EL_POSITION_INCREMENTAL_ENCODER_B_PIN_INTERRUPT 1 //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 147 | // read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts 148 | #endif //FEATURE_EL_POSITION_INCREMENTAL_ENCODER 149 | 150 | #ifdef FEATURE_YOURDUINO_I2C_LCD 151 | #define En_pin 2 152 | #define Rw_pin 1 153 | #define Rs_pin 0 154 | #define D4_pin 4 155 | #define D5_pin 5 156 | #define D6_pin 6 157 | #define D7_pin 7 158 | #endif //FEATURE_YOURDUINO_I2C_LCD 159 | 160 | #ifdef FEATURE_MOON_TRACKING 161 | #define moon_tracking_active_pin 0 // goes high when moon tracking is active 162 | #define moon_tracking_activate_line 0 // ground this pin to activate moon tracking (not for use with a button) 163 | #define moon_tracking_button 0 // use with a normally open momentary switch to ground 164 | #endif //FEATURE_MOON_TRACKING 165 | 166 | #ifdef FEATURE_SUN_TRACKING 167 | #define sun_tracking_active_pin 0 // goes high when sun tracking is active 168 | #define sun_tracking_activate_line 0 // ground this pin to activate sun tracking (not for use with a button) 169 | #define sun_tracking_button 0 // use with a normally open momentary switch to ground 170 | #endif //FEATURE_SUN_TRACKING 171 | 172 | #ifdef FEATURE_GPS 173 | #define gps_sync 0 174 | #endif //FEATURE_GPS 175 | 176 | #ifdef FEATURE_POWER_SWITCH 177 | #define power_switch 0 // use with FEATURE_POWER_SWITCH 178 | #endif //FEATURE_POWER_SWITCH 179 | 180 | #ifdef FEATURE_EL_POSITION_MEMSIC_2125 181 | #define pin_memsic_2125_x 0 182 | #define pin_memsic_2125_y 0 183 | #endif //FEATURE_EL_POSITION_MEMSIC_2125 184 | 185 | // #define pin_led_cw 0 186 | // #define pin_led_ccw 0 187 | // #define pin_led_up 0 188 | // #define pin_led_down 0 189 | 190 | #ifdef FEATURE_AUTOPARK 191 | #define pin_autopark_disable 0 // Pull low to disable autopark 192 | #define pin_autopark_timer_reset 0 // Pull low to reset the autopark timer (tie in with rig PTT) 193 | #endif 194 | 195 | #ifdef FEATURE_AUDIBLE_ALERT 196 | #define pin_audible_alert 0 197 | #endif 198 | 199 | //#define pin_status_led 0 // Status LED - blinks when there is rotation in progress 200 | 201 | // Added 2020.07.24.01 202 | #define satellite_tracking_active_pin 0 203 | #define satellite_tracking_activate_line 0 204 | #define satellite_tracking_button 0 // use with a normally open momentary switch to ground 205 | 206 | --------------------------------------------------------------------------------