mirror of
https://github.com/k3ng/k3ng_rotator_controller.git
synced 2024-12-24 07:16:43 +00:00
2021.10.14.01
FEATURE_STEPPER_MOTOR Removed OPTION_STEPPER_MOTOR_MAX_50_KHZ. Too much overhead from interrupts. Implemented faster digital writes using digitalWriteFast library (library now included in Github) Added OPTION_STEPPER_DO_NOT_USE_DIGITALWRITEFAST_LIBRARY to disable digitalWriteFast library use
This commit is contained in:
parent
027df6c342
commit
56e6ed8233
@ -1019,6 +1019,15 @@
|
||||
2021.10.13.01
|
||||
FEATURE_STEPPER_MOTOR: Added OPTION_STEPPER_MOTOR_MAX_50_KHZ
|
||||
|
||||
2021.10.13.02
|
||||
DEBUG_STEPPER: More code
|
||||
|
||||
2021.10.14.01
|
||||
FEATURE_STEPPER_MOTOR
|
||||
Removed OPTION_STEPPER_MOTOR_MAX_50_KHZ. Too much overhead from interrupts.
|
||||
Implemented faster digital writes using digitalWriteFast library (library now included in Github)
|
||||
Added OPTION_STEPPER_DO_NOT_USE_DIGITALWRITEFAST_LIBRARY to disable digitalWriteFast library use
|
||||
|
||||
All library files should be placed in directories likes \sketchbook\libraries\library1\ , \sketchbook\libraries\library2\ , etc.
|
||||
Anything rotator_*.* should be in the ino directory!
|
||||
|
||||
@ -1032,7 +1041,7 @@
|
||||
|
||||
*/
|
||||
|
||||
#define CODE_VERSION "2021.10.13.01"
|
||||
#define CODE_VERSION "2021.10.14.01"
|
||||
|
||||
|
||||
#include <avr/pgmspace.h>
|
||||
@ -1196,6 +1205,9 @@
|
||||
#else
|
||||
#include <TimerFive.h>
|
||||
#endif
|
||||
#if !defined(OPTION_STEPPER_DO_NOT_USE_DIGITALWRITEFAST_LIBRARY)
|
||||
#include <digitalWriteFast.h>
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(DEVELOPMENT_TIMELIB)
|
||||
@ -9760,7 +9772,7 @@ void update_el_variable_outputs(byte speed_voltage){
|
||||
el_tone = map(speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH);
|
||||
|
||||
#ifdef FEATURE_STEPPER_MOTOR
|
||||
set_el_stepper_freq(el_tone);
|
||||
set_el_stepper_freq(el_tone,7);
|
||||
#endif
|
||||
|
||||
|
||||
@ -9877,11 +9889,12 @@ void update_az_variable_outputs(byte speed_voltage){
|
||||
debug.print("\taz_stepper_motor_pulse: ");
|
||||
#endif // DEBUG_VARIABLE_OUTPUTS
|
||||
az_tone = map(speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH);
|
||||
set_az_stepper_freq(az_tone);
|
||||
set_az_stepper_freq(az_tone,1);
|
||||
#ifdef DEBUG_VARIABLE_OUTPUTS
|
||||
debug.print(az_tone);
|
||||
#endif // DEBUG_VARIABLE_OUTPUTS
|
||||
}
|
||||
|
||||
#endif //FEATURE_STEPPER_MOTOR
|
||||
|
||||
if (azimuth_speed_voltage) {
|
||||
@ -9948,7 +9961,7 @@ void rotator(byte rotation_action, byte rotation_type, byte traceback) {
|
||||
}
|
||||
#ifdef FEATURE_STEPPER_MOTOR
|
||||
if (az_stepper_motor_pulse) {
|
||||
set_az_stepper_freq(0);
|
||||
set_az_stepper_freq(0,2);
|
||||
digitalWriteEnhanced(az_stepper_motor_pulse,LOW);
|
||||
}
|
||||
#endif //FEATURE_STEPPER_MOTOR
|
||||
@ -9971,7 +9984,7 @@ void rotator(byte rotation_action, byte rotation_type, byte traceback) {
|
||||
}
|
||||
#ifdef FEATURE_STEPPER_MOTOR
|
||||
if (az_stepper_motor_pulse) {
|
||||
set_az_stepper_freq(map(normal_az_speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH));
|
||||
set_az_stepper_freq(map(normal_az_speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH),3);
|
||||
}
|
||||
#endif //FEATURE_STEPPER_MOTOR
|
||||
}
|
||||
@ -10024,7 +10037,7 @@ void rotator(byte rotation_action, byte rotation_type, byte traceback) {
|
||||
|
||||
#ifdef FEATURE_STEPPER_MOTOR
|
||||
if (az_stepper_motor_pulse) {
|
||||
set_az_stepper_freq(0);
|
||||
set_az_stepper_freq(0,4);
|
||||
digitalWriteEnhanced(az_stepper_motor_pulse,HIGH);
|
||||
}
|
||||
#endif //FEATURE_STEPPER_MOTOR
|
||||
@ -10061,7 +10074,7 @@ void rotator(byte rotation_action, byte rotation_type, byte traceback) {
|
||||
}
|
||||
#ifdef FEATURE_STEPPER_MOTOR
|
||||
if (az_stepper_motor_pulse) {
|
||||
set_az_stepper_freq(0);
|
||||
set_az_stepper_freq(0,5);
|
||||
digitalWriteEnhanced(az_stepper_motor_pulse,LOW);
|
||||
}
|
||||
#endif //FEATURE_STEPPER_MOTOR
|
||||
@ -10083,7 +10096,7 @@ void rotator(byte rotation_action, byte rotation_type, byte traceback) {
|
||||
}
|
||||
#ifdef FEATURE_STEPPER_MOTOR
|
||||
if (az_stepper_motor_pulse) {
|
||||
set_az_stepper_freq(map(normal_az_speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH));
|
||||
set_az_stepper_freq(map(normal_az_speed_voltage, 0, 255, AZ_VARIABLE_FREQ_OUTPUT_LOW, AZ_VARIABLE_FREQ_OUTPUT_HIGH),6);
|
||||
}
|
||||
#endif //FEATURE_STEPPER_MOTOR
|
||||
}
|
||||
@ -10164,7 +10177,7 @@ void rotator(byte rotation_action, byte rotation_type, byte traceback) {
|
||||
}
|
||||
#ifdef FEATURE_STEPPER_MOTOR
|
||||
if (el_stepper_motor_pulse) {
|
||||
set_el_stepper_freq(0);
|
||||
set_el_stepper_freq(0,1);
|
||||
digitalWriteEnhanced(el_stepper_motor_pulse,LOW);
|
||||
}
|
||||
#endif //FEATURE_STEPPER_MOTOR
|
||||
@ -10183,7 +10196,7 @@ void rotator(byte rotation_action, byte rotation_type, byte traceback) {
|
||||
}
|
||||
#ifdef FEATURE_STEPPER_MOTOR
|
||||
if (el_stepper_motor_pulse) {
|
||||
set_el_stepper_freq(map(normal_el_speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH));
|
||||
set_el_stepper_freq(map(normal_el_speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH),2);
|
||||
}
|
||||
#endif //FEATURE_STEPPER_MOTOR
|
||||
if (rotate_down_freq) {
|
||||
@ -10231,7 +10244,7 @@ void rotator(byte rotation_action, byte rotation_type, byte traceback) {
|
||||
}
|
||||
#ifdef FEATURE_STEPPER_MOTOR
|
||||
if (el_stepper_motor_pulse) {
|
||||
set_el_stepper_freq(0);
|
||||
set_el_stepper_freq(0,3);
|
||||
digitalWriteEnhanced(el_stepper_motor_pulse,HIGH);
|
||||
}
|
||||
#endif //FEATURE_STEPPER_MOTOR
|
||||
@ -10269,7 +10282,7 @@ void rotator(byte rotation_action, byte rotation_type, byte traceback) {
|
||||
}
|
||||
#ifdef FEATURE_STEPPER_MOTOR
|
||||
if (el_stepper_motor_pulse) {
|
||||
set_el_stepper_freq(0);
|
||||
set_el_stepper_freq(0,4);
|
||||
digitalWriteEnhanced(el_stepper_motor_pulse,LOW);
|
||||
}
|
||||
#endif //FEATURE_STEPPER_MOTOR
|
||||
@ -10291,7 +10304,7 @@ void rotator(byte rotation_action, byte rotation_type, byte traceback) {
|
||||
}
|
||||
#ifdef FEATURE_STEPPER_MOTOR
|
||||
if (el_stepper_motor_pulse) {
|
||||
set_el_stepper_freq(map(normal_el_speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH));
|
||||
set_el_stepper_freq(map(normal_el_speed_voltage, 0, 255, EL_VARIABLE_FREQ_OUTPUT_LOW, EL_VARIABLE_FREQ_OUTPUT_HIGH),5);
|
||||
digitalWriteEnhanced(el_stepper_motor_pulse,LOW);
|
||||
}
|
||||
#endif //FEATURE_STEPPER_MOTOR
|
||||
@ -10337,7 +10350,7 @@ void rotator(byte rotation_action, byte rotation_type, byte traceback) {
|
||||
}
|
||||
#ifdef FEATURE_STEPPER_MOTOR
|
||||
if (el_stepper_motor_pulse) {
|
||||
set_el_stepper_freq(0);
|
||||
set_el_stepper_freq(0,6);
|
||||
digitalWriteEnhanced(el_stepper_motor_pulse,HIGH);
|
||||
}
|
||||
#endif //FEATURE_STEPPER_MOTOR
|
||||
@ -19280,7 +19293,6 @@ void check_sun_pushbutton_calibration(){
|
||||
#if defined(FEATURE_STEPPER_MOTOR)
|
||||
void service_stepper_motor_pulse_pins(){
|
||||
|
||||
|
||||
#ifdef DEBUG_LOOP
|
||||
control_port->println("service_stepper_motor_pulse_pins()");
|
||||
control_port->flush();
|
||||
@ -19295,10 +19307,18 @@ void service_stepper_motor_pulse_pins(){
|
||||
az_stepper_pin_transition_counter++;
|
||||
if (az_stepper_pin_transition_counter >= az_stepper_freq_count){
|
||||
if (az_stepper_pin_last_state == LOW){
|
||||
#if !defined(OPTION_STEPPER_DO_NOT_USE_DIGITALWRITEFAST_LIBRARY)
|
||||
digitalWriteFast(az_stepper_motor_pulse,HIGH);
|
||||
#else
|
||||
digitalWrite(az_stepper_motor_pulse,HIGH);
|
||||
#endif
|
||||
az_stepper_pin_last_state = HIGH;
|
||||
} else {
|
||||
#if !defined(OPTION_STEPPER_DO_NOT_USE_DIGITALWRITEFAST_LIBRARY)
|
||||
digitalWriteFast(az_stepper_motor_pulse,LOW);
|
||||
#else
|
||||
digitalWrite(az_stepper_motor_pulse,LOW);
|
||||
#endif
|
||||
az_stepper_pin_last_state = LOW;
|
||||
}
|
||||
az_stepper_pin_transition_counter = 0;
|
||||
@ -19315,10 +19335,18 @@ void service_stepper_motor_pulse_pins(){
|
||||
el_stepper_pin_transition_counter++;
|
||||
if (el_stepper_pin_transition_counter >= el_stepper_freq_count){
|
||||
if (el_stepper_pin_last_state == LOW){
|
||||
#if !defined(OPTION_STEPPER_DO_NOT_USE_DIGITALWRITEFAST_LIBRARY)
|
||||
digitalWriteFast(el_stepper_motor_pulse,HIGH);
|
||||
#else
|
||||
digitalWrite(el_stepper_motor_pulse,HIGH);
|
||||
#endif
|
||||
el_stepper_pin_last_state = HIGH;
|
||||
} else {
|
||||
#if !defined(OPTION_STEPPER_DO_NOT_USE_DIGITALWRITEFAST_LIBRARY)
|
||||
digitalWriteFast(el_stepper_motor_pulse,LOW);
|
||||
#else
|
||||
digitalWrite(el_stepper_motor_pulse,LOW);
|
||||
#endif
|
||||
el_stepper_pin_last_state = LOW;
|
||||
}
|
||||
el_stepper_pin_transition_counter = 0;
|
||||
@ -19334,7 +19362,7 @@ void service_stepper_motor_pulse_pins(){
|
||||
|
||||
//------------------------------------------------------
|
||||
#ifdef FEATURE_STEPPER_MOTOR
|
||||
void set_az_stepper_freq(unsigned int frequency){
|
||||
void set_az_stepper_freq(unsigned int frequency, byte traceback){
|
||||
|
||||
if (frequency > STEPPER_MOTOR_MAX_FREQ) {frequency = STEPPER_MOTOR_MAX_FREQ;}
|
||||
|
||||
@ -19349,6 +19377,8 @@ void set_az_stepper_freq(unsigned int frequency){
|
||||
debug.print(frequency);
|
||||
debug.print(F(" az_stepper_freq_count:"));
|
||||
debug.print(az_stepper_freq_count);
|
||||
debug.print(F(" traceback:"));
|
||||
debug.print(traceback);
|
||||
debug.println("");
|
||||
#endif //DEBUG_STEPPER
|
||||
|
||||
@ -19357,7 +19387,7 @@ void set_az_stepper_freq(unsigned int frequency){
|
||||
#endif //FEATURE_STEPPER_MOTOR
|
||||
//------------------------------------------------------
|
||||
#if defined(FEATURE_ELEVATION_CONTROL) && defined(FEATURE_STEPPER_MOTOR)
|
||||
void set_el_stepper_freq(unsigned int frequency){
|
||||
void set_el_stepper_freq(unsigned int frequency, byte traceback){
|
||||
|
||||
if (frequency > STEPPER_MOTOR_MAX_FREQ) {frequency = STEPPER_MOTOR_MAX_FREQ;}
|
||||
|
||||
@ -19372,6 +19402,8 @@ void set_el_stepper_freq(unsigned int frequency){
|
||||
debug.print(frequency);
|
||||
debug.print(" el_stepper_freq_count:");
|
||||
debug.print(el_stepper_freq_count);
|
||||
debug.print(F(" traceback:"));
|
||||
debug.print(traceback);
|
||||
debug.println("");
|
||||
#endif //DEBUG_STEPPER
|
||||
|
||||
|
@ -179,8 +179,9 @@
|
||||
// #define OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE
|
||||
// #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
|
||||
|
||||
#define OPTION_STEPPER_MOTOR_MAX_2_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_2_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_5_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_10_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_20_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_50_KHZ
|
||||
#define OPTION_STEPPER_MOTOR_MAX_20_KHZ
|
||||
|
||||
//#define OPTION_STEPPER_DO_NOT_USE_DIGITALWRITEFAST_LIBRARY
|
@ -165,8 +165,9 @@
|
||||
//#define OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE
|
||||
//#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
|
||||
|
||||
#define OPTION_STEPPER_MOTOR_MAX_2_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_2_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_5_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_10_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_20_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_50_KHZ
|
||||
#define OPTION_STEPPER_MOTOR_MAX_20_KHZ
|
||||
|
||||
//#define OPTION_STEPPER_DO_NOT_USE_DIGITALWRITEFAST_LIBRARY
|
||||
|
@ -191,12 +191,13 @@
|
||||
#define OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE
|
||||
// #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
|
||||
|
||||
#define OPTION_STEPPER_MOTOR_MAX_2_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_2_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_5_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_10_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_20_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_50_KHZ
|
||||
#define OPTION_STEPPER_MOTOR_MAX_20_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_50_KHZ // DO NOT USE ! Too much interrupt overhead
|
||||
|
||||
//#define OPTION_STEPPER_DO_NOT_USE_DIGITALWRITEFAST_LIBRARY
|
||||
|
||||
#define OPTION_CLI_VT100
|
||||
|
||||
|
@ -1,78 +1,80 @@
|
||||
/* ---------------------- Features and Options - you must configure this !! ------------------------------------------------
|
||||
|
||||
|
||||
If you are using EA4TX ARS USB, edit rotator_features_ea4tx_ars_usb.h, not this file.
|
||||
(If you have enabled one of the hardware profiles in rotator_hardware.h, do not edit this file, edit the appropriate files indicated in rotator_hardware.h)
|
||||
|
||||
*/
|
||||
|
||||
/* main features */
|
||||
|
||||
#define FEATURE_ELEVATION_CONTROL // uncomment this for AZ/EL rotators
|
||||
//#define FEATURE_YAESU_EMULATION // uncomment this for Yaesu GS-232 emulation on control port
|
||||
#define FEATURE_EASYCOM_EMULATION // Easycom protocol emulation on control port (undefine FEATURE_YAESU_EMULATION above)
|
||||
#define FEATURE_YAESU_EMULATION // uncomment this for Yaesu GS-232 emulation on control port
|
||||
// #define FEATURE_EASYCOM_EMULATION // Easycom protocol emulation on control port
|
||||
// #define FEATURE_DCU_1_EMULATION // DCU-1 protocol emulation on control port (only supports azimuth only systems)
|
||||
|
||||
//#define FEATURE_MOON_TRACKING
|
||||
//#define FEATURE_SUN_TRACKING
|
||||
//#define FEATURE_CLOCK
|
||||
//#define FEATURE_GPS
|
||||
//#define FEATURE_RTC_DS1307
|
||||
//#define FEATURE_RTC_PCF8583
|
||||
//#define FEATURE_ETHERNET
|
||||
// #define FEATURE_MOON_TRACKING
|
||||
// #define FEATURE_SUN_TRACKING
|
||||
// #define FEATURE_CLOCK
|
||||
// #define FEATURE_GPS
|
||||
// #define FEATURE_RTC_DS1307
|
||||
// #define FEATURE_RTC_PCF8583
|
||||
// #define FEATURE_ETHERNET
|
||||
#define FEATURE_STEPPER_MOTOR // Requires TimerFive library to be copied to the Arduino libraries directory (If using OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE below, copy the TimeOne library)
|
||||
//#define FEATURE_AUTOCORRECT
|
||||
//#define FEATURE_TEST_DISPLAY_AT_STARTUP
|
||||
// #define FEATURE_AUTOCORRECT
|
||||
// #define FEATURE_TEST_DISPLAY_AT_STARTUP
|
||||
|
||||
//#define FEATURE_SATELLITE_TRACKING // https://github.com/k3ng/k3ng_rotator_controller/wiki/707-Satellite-Tracking
|
||||
// #define FEATURE_SATELLITE_TRACKING // https://github.com/k3ng/k3ng_rotator_controller/wiki/707-Satellite-Tracking
|
||||
|
||||
#define LANGUAGE_ENGLISH // all languages customized in rotator_language.h
|
||||
//#define LANGUAGE_SPANISH
|
||||
//#define LANGUAGE_CZECH
|
||||
//#define LANGUAGE_ITALIAN
|
||||
//#define LANGUAGE_PORTUGUESE_BRASIL
|
||||
//#define LANGUAGE_GERMAN
|
||||
//#define LANGUAGE_FRENCH
|
||||
//#define LANGUAGE_DUTCH
|
||||
//#define LANGUAGE_NORWEGIAN_BOKMAAL
|
||||
|
||||
// #define LANGUAGE_SPANISH
|
||||
// #define LANGUAGE_CZECH
|
||||
// #define LANGUAGE_ITALIAN
|
||||
// #define LANGUAGE_PORTUGUESE_BRASIL
|
||||
// #define LANGUAGE_GERMAN
|
||||
// #define LANGUAGE_FRENCH
|
||||
// #define LANGUAGE_DUTCH
|
||||
// #define LANGUAGE_NORWEGIAN_BOKMAAL
|
||||
|
||||
/* master and remote slave unit functionality */
|
||||
//#define FEATURE_REMOTE_UNIT_SLAVE // uncomment this to make this unit a remote unit controlled by a host unit
|
||||
// #define FEATURE_REMOTE_UNIT_SLAVE // uncomment this to make this unit a remote unit controlled by a host unit
|
||||
|
||||
// #define FEATURE_MASTER_WITH_SERIAL_SLAVE // [master]{remote_port}<-------serial-------->{control_port}[slave]
|
||||
// #define FEATURE_MASTER_WITH_ETHERNET_SLAVE // [master]<-------------------ethernet--------------------->[slave]
|
||||
|
||||
//#define FEATURE_MASTER_WITH_SERIAL_SLAVE // [master]{remote_port}<-------serial-------->{control_port}[slave]
|
||||
//#define FEATURE_MASTER_WITH_ETHERNET_SLAVE // [master]<-------------------ethernet--------------------->[slave]
|
||||
|
||||
//#define FEATURE_ADC_RESOLUTION12 // 12 bit ADC resolution for Teensy 3.x, Arduino Due Zero MKR families
|
||||
|
||||
/* position sensors - pick one for azimuth and one for elevation if using an az/el rotator */
|
||||
//#define FEATURE_AZ_POSITION_POTENTIOMETER //this is used for both a voltage from a rotator control or a homebrew rotator with a potentiometer
|
||||
//#define FEATURE_AZ_POSITION_ROTARY_ENCODER
|
||||
// #define FEATURE_AZ_POSITION_POTENTIOMETER //this is used for both a voltage from a rotator control or a homebrew rotator with a potentiometer
|
||||
// #define FEATURE_AZ_POSITION_ROTARY_ENCODER
|
||||
// #define FEATURE_AZ_POSITION_ROTARY_ENCODER_USE_PJRC_LIBRARY // library @ http://www.pjrc.com/teensy/td_libs_Encoder.html
|
||||
//#define FEATURE_AZ_POSITION_PULSE_INPUT
|
||||
//#define FEATURE_AZ_POSITION_HMC5883L // HMC5883L digital compass support
|
||||
//#define FEATURE_AZ_POSITION_HMC5883L_USING_JARZEBSKI_LIBRARY // HMC5883L digital compass support using Jarzebski library at https://github.com/jarzebski/Arduino-HMC5883L
|
||||
//#define FEATURE_AZ_POSITION_DFROBOT_QMC5883 // QMC5883 digital compass support using DFRobot library at https://github.com/DFRobot/DFRobot_QMC5883
|
||||
//#define FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT // requires FEATURE_MASTER_WITH_SERIAL_SLAVE or FEATURE_MASTER_WITH_ETHERNET_SLAVE
|
||||
//#define FEATURE_AZ_POSITION_ADAFRUIT_LSM303 // Uncomment for azimuth using LSM303 compass and Adafruit library (https://github.com/adafruit/Adafruit_LSM303) (also uncomment object declaration below)
|
||||
//#define FEATURE_AZ_POSITION_POLOLU_LSM303 // Uncomment for azimuth using LSM303 compass and Polulu library
|
||||
//#define FEATURE_AZ_POSITION_HH12_AS5045_SSI
|
||||
// #define FEATURE_AZ_POSITION_PULSE_INPUT
|
||||
// #define FEATURE_AZ_POSITION_HMC5883L // HMC5883L digital compass support
|
||||
// #define FEATURE_AZ_POSITION_HMC5883L_USING_JARZEBSKI_LIBRARY // HMC5883L digital compass support using Jarzebski library at https://github.com/jarzebski/Arduino-HMC5883L
|
||||
// #define FEATURE_AZ_POSITION_DFROBOT_QMC5883 // QMC5883 digital compass support using DFRobot library at https://github.com/DFRobot/DFRobot_QMC5883
|
||||
// #define FEATURE_AZ_POSITION_GET_FROM_REMOTE_UNIT // requires FEATURE_MASTER_WITH_SERIAL_SLAVE or FEATURE_MASTER_WITH_ETHERNET_SLAVE
|
||||
// #define FEATURE_AZ_POSITION_ADAFRUIT_LSM303 // Uncomment for azimuth using LSM303 compass and Adafruit library (https://github.com/adafruit/Adafruit_LSM303) (also uncomment object declaration below)
|
||||
// #define FEATURE_AZ_POSITION_POLOLU_LSM303 // Uncomment for azimuth using LSM303 compass and Polulu library
|
||||
// #define FEATURE_AZ_POSITION_HH12_AS5045_SSI
|
||||
#define FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
|
||||
//#define FEATURE_AZ_POSITION_MECHASOLUTION_QMC5883 // QMC5883 digital compass support using Mechasolution library at https://github.com/keepworking/Mecha_QMC5883L
|
||||
// #define FEATURE_AZ_POSITION_A2_ABSOLUTE_ENCODER
|
||||
// #define FEATURE_AZ_POSITION_MECHASOLUTION_QMC5883 // QMC5883 digital compass support using Mechasolution library at https://github.com/keepworking/Mecha_QMC5883L
|
||||
|
||||
|
||||
//#define FEATURE_EL_POSITION_POTENTIOMETER
|
||||
//#define FEATURE_EL_POSITION_ROTARY_ENCODER
|
||||
// #define FEATURE_EL_POSITION_POTENTIOMETER
|
||||
// #define FEATURE_EL_POSITION_ROTARY_ENCODER
|
||||
// #define FEATURE_EL_POSITION_ROTARY_ENCODER_USE_PJRC_LIBRARY // library @ http://www.pjrc.com/teensy/td_libs_Encoder.html
|
||||
//#define FEATURE_EL_POSITION_PULSE_INPUT
|
||||
//#define FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB // Uncomment for elevation ADXL345 accelerometer support using ADXL345 library
|
||||
//#define FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB // Uncomment for elevation ADXL345 accelerometer support using Adafruit library
|
||||
//#define FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT // requires FEATURE_MASTER_WITH_SERIAL_SLAVE or FEATURE_MASTER_WITH_ETHERNET_SLAVE
|
||||
//#define FEATURE_EL_POSITION_ADAFRUIT_LSM303 // Uncomment for elevation using LSM303 accelerometer and Adafruit library (https://github.com/adafruit/Adafruit_LSM303) (also uncomment object declaration below)
|
||||
//#define FEATURE_EL_POSITION_POLOLU_LSM303 // Uncomment for elevation using LSM303 compass and Polulu library
|
||||
//#define FEATURE_EL_POSITION_HH12_AS5045_SSI
|
||||
// #define FEATURE_EL_POSITION_PULSE_INPUT
|
||||
// #define FEATURE_EL_POSITION_ADXL345_USING_LOVE_ELECTRON_LIB // Uncomment for elevation ADXL345 accelerometer support using ADXL345 library
|
||||
// #define FEATURE_EL_POSITION_ADXL345_USING_ADAFRUIT_LIB // Uncomment for elevation ADXL345 accelerometer support using Adafruit library
|
||||
// #define FEATURE_EL_POSITION_GET_FROM_REMOTE_UNIT // requires FEATURE_MASTER_WITH_SERIAL_SLAVE or FEATURE_MASTER_WITH_ETHERNET_SLAVE
|
||||
// #define FEATURE_EL_POSITION_ADAFRUIT_LSM303 // Uncomment for elevation using LSM303 accelerometer and Adafruit library (https://github.com/adafruit/Adafruit_LSM303) (also uncomment object declaration below)
|
||||
// #define FEATURE_EL_POSITION_POLOLU_LSM303 // Uncomment for elevation using LSM303 compass and Polulu library
|
||||
// #define FEATURE_EL_POSITION_HH12_AS5045_SSI
|
||||
#define FEATURE_EL_POSITION_INCREMENTAL_ENCODER
|
||||
//#define FEATURE_EL_POSITION_MEMSIC_2125
|
||||
// #define FEATURE_EL_POSITION_MEMSIC_2125
|
||||
// #define FEATURE_EL_POSITION_A2_ABSOLUTE_ENCODER
|
||||
|
||||
// And if you are using any display other than a 4 bit LCD, you must also change the feature setting in rotator_k3ngdisplay.h!!!!
|
||||
// #define FEATURE_4_BIT_LCD_DISPLAY // Uncomment for classic 4 bit LCD display (most common)
|
||||
#define FEATURE_4_BIT_LCD_DISPLAY // Uncomment for classic 4 bit LCD display (most common)
|
||||
// #define FEATURE_ADAFRUIT_I2C_LCD
|
||||
// #define FEATURE_ADAFRUIT_BUTTONS // Uncomment this to use Adafruit I2C LCD buttons for manual AZ/EL instead of normal buttons (also set this feature in rotator_k3ngdisplay.h)
|
||||
// #define FEATURE_YOURDUINO_I2C_LCD
|
||||
@ -80,84 +82,106 @@
|
||||
// #define FEATURE_YWROBOT_I2C_DISPLAY
|
||||
// #define FEATURE_SAINSMART_I2C_LCD
|
||||
// #define FEATURE_MIDAS_I2C_DISPLAY
|
||||
// #define FEATURE_FABO_LCD_PCF8574_DISPLAY
|
||||
|
||||
// #define FEATURE_NEXTION_DISPLAY // Documentation: https://github.com/k3ng/k3ng_rotator_controller/wiki/425-Human-Interface:-Nextion-Display
|
||||
|
||||
//#define FEATURE_ANALOG_OUTPUT_PINS
|
||||
// #define FEATURE_ANALOG_OUTPUT_PINS
|
||||
|
||||
// #define FEATURE_SUN_PUSHBUTTON_AZ_EL_CALIBRATION
|
||||
// #define FEATURE_MOON_PUSHBUTTON_AZ_EL_CALIBRATION
|
||||
|
||||
// #define FEATURE_AUDIBLE_ALERT
|
||||
|
||||
/* preset rotary encoder features and options */
|
||||
//#define FEATURE_AZ_PRESET_ENCODER // Uncomment for Rotary Encoder Azimuth Preset support
|
||||
//#define FEATURE_EL_PRESET_ENCODER // Uncomment for Rotary Encoder Elevation Preset support (requires FEATURE_AZ_PRESET_ENCODER above)
|
||||
// #define FEATURE_AZ_PRESET_ENCODER // Uncomment for Rotary Encoder Azimuth Preset support
|
||||
// #define FEATURE_EL_PRESET_ENCODER // Uncomment for Rotary Encoder Elevation Preset support (requires FEATURE_AZ_PRESET_ENCODER above)
|
||||
#define OPTION_ENCODER_HALF_STEP_MODE
|
||||
#define OPTION_ENCODER_ENABLE_PULLUPS // define to enable weak pullups on rotary encoder pins
|
||||
#define OPTION_INCREMENTAL_ENCODER_PULLUPS // define to enable weak pullups on 3 phase incremental rotary encoder pins
|
||||
//#define OPTION_PRESET_ENCODER_RELATIVE_CHANGE // this makes the encoder(s) change the az or el in a relative fashion rather then store an absolute setting
|
||||
//#define OPTION_PRESET_ENCODER_0_360_DEGREES
|
||||
// #define OPTION_PRESET_ENCODER_0_360_DEGREES
|
||||
|
||||
/* position sensor options */
|
||||
#define OPTION_AZ_POSITION_ROTARY_ENCODER_HARD_LIMIT // stop azimuth at lower and upper limit rather than rolling over
|
||||
#define OPTION_EL_POSITION_ROTARY_ENCODER_HARD_LIMIT // stop elevation at lower and upper limits rather than rolling over
|
||||
#define OPTION_AZ_POSITION_PULSE_HARD_LIMIT // stop azimuth at lower and upper limit rather than rolling over
|
||||
#define OPTION_EL_POSITION_PULSE_HARD_LIMIT // stop elevation at lower and upper limits rather than rolling over
|
||||
//#define OPTION_POSITION_PULSE_INPUT_PULLUPS // define to enable weak pullups on position pulse inputs
|
||||
#define OPTION_POSITION_PULSE_INPUT_PULLUPS // define to enable weak pullups on position pulse inputs
|
||||
|
||||
/* less often used features and options */
|
||||
//#define OPTION_GS_232B_EMULATION // comment this out to default to Yaesu GS-232A emulation when using FEATURE_YAESU_EMULATION above
|
||||
//#define FEATURE_ROTATION_INDICATOR_PIN // activate rotation_indication_pin to indicate rotation
|
||||
//#define FEATURE_LIMIT_SENSE
|
||||
//#define FEATURE_TIMED_BUFFER // Support for Yaesu timed buffer commands
|
||||
//#define OPTION_SERIAL_HELP_TEXT // Yaesu help command prints help
|
||||
//#define FEATURE_PARK
|
||||
//#define FEATURE_AUTOPARK // Requires FEATURE_PARK
|
||||
//#define OPTION_AZ_MANUAL_ROTATE_LIMITS // this option will automatically stop the L and R commands when hitting a CCW or CW limit (settings below - AZ_MANUAL_ROTATE_*_LIMIT)
|
||||
//#define OPTION_EL_MANUAL_ROTATE_LIMITS
|
||||
//#define OPTION_C_COMMAND_SENDS_AZ_AND_EL // uncomment this when using Yaesu emulation with Ham Radio Deluxe
|
||||
//#define OPTION_DELAY_C_CMD_OUTPUT // uncomment this when using Yaesu emulation with Ham Radio Deluxe
|
||||
//#define FEATURE_AZIMUTH_CORRECTION // correct the azimuth using a calibration table in rotator_settings.h
|
||||
//#define FEATURE_ELEVATION_CORRECTION // correct the elevation using a calibration table in rotator_settings.h
|
||||
//#define FEATURE_ANCILLARY_PIN_CONTROL // control I/O pins with serial commands \F, \N, \P
|
||||
//#define FEATURE_JOYSTICK_CONTROL // analog joystick support
|
||||
//#define OPTION_JOYSTICK_REVERSE_X_AXIS
|
||||
//#define OPTION_JOYSTICK_REVERSE_Y_AXIS
|
||||
#define OPTION_GS_232B_EMULATION // comment this out to default to Yaesu GS-232A emulation when using FEATURE_YAESU_EMULATION above
|
||||
#define FEATURE_ROTATION_INDICATOR_PIN // activate rotation_indication_pin to indicate rotation
|
||||
// #define FEATURE_LIMIT_SENSE
|
||||
// #define FEATURE_TIMED_BUFFER // Support for Yaesu timed buffer commands
|
||||
// #define OPTION_SERIAL_HELP_TEXT // Yaesu help command prints help
|
||||
// #define FEATURE_PARK
|
||||
// #define FEATURE_AUTOPARK // Requires FEATURE_PARK
|
||||
// #define OPTION_AZ_MANUAL_ROTATE_LIMITS // this option will automatically stop the L and R commands when hitting a CCW or CW limit (settings are AZ_MANUAL_ROTATE_CCW_LIMIT, AZ_MANUAL_ROTATE_CW_LIMIT)
|
||||
// #define OPTION_EL_MANUAL_ROTATE_LIMITS // (settings are EL_MANUAL_ROTATE_DOWN_LIMIT, EL_MANUAL_ROTATE_UP_LIMIT)
|
||||
// #define OPTION_C_COMMAND_SENDS_AZ_AND_EL // uncomment this when using Yaesu emulation with Ham Radio Deluxe
|
||||
// #define OPTION_DELAY_C_CMD_OUTPUT // uncomment this when using Yaesu emulation with Ham Radio Deluxe
|
||||
// #define FEATURE_AZIMUTH_CORRECTION // correct the azimuth using a calibration table in rotator_settings.h
|
||||
// #define FEATURE_ELEVATION_CORRECTION // correct the elevation using a calibration table in rotator_settings.h
|
||||
// #define FEATURE_AZ_ROTATION_STALL_DETECTION // Azimuth rotation stall detection - pin: az_rotation_stall_detected
|
||||
// #define FEATURE_EL_ROTATION_STALL_DETECTION // Elevation rotation stall detection - pin: el_rotation_stall_detected
|
||||
// #define OPTION_ROTATION_STALL_DETECTION_SERIAL_MESSAGE // Sends message out serial port when rotation stall has been detected
|
||||
// #define FEATURE_ANCILLARY_PIN_CONTROL // control I/O pins with serial commands \F, \N, \P
|
||||
#define FEATURE_JOYSTICK_CONTROL // analog joystick support
|
||||
#define OPTION_JOYSTICK_REVERSE_X_AXIS
|
||||
#define OPTION_JOYSTICK_REVERSE_Y_AXIS
|
||||
#define OPTION_EL_SPEED_FOLLOWS_AZ_SPEED // changing the azimith speed with Yaesu X commands or an azimuth speed pot will also change elevation speed
|
||||
//#define OPTION_PULSE_IGNORE_AMBIGUOUS_PULSES // for azimuth and elevation position pulse input feature, ignore pulses that arrive when no rotation is active
|
||||
//#define OPTION_BUTTON_RELEASE_NO_SLOWDOWN // disables slowdown when CW or CCW button is released, or stop button is depressed
|
||||
//#define OPTION_SYNC_RTC_TO_GPS // if both realtime clock and GPS are present, syncronize realtime clock to GPS
|
||||
//#define OPTION_DISPLAY_HHMM_CLOCK // display HH:MM clock on LCD row 1 (set position with #define LCD_HHMM_CLOCK_POSITION)
|
||||
//#define OPTION_DISPLAY_HHMMSS_CLOCK // display HH:MM:SS clock on LCD row 1 (set position with #define LCD_HHMMSS_CLOCK_POSITION)
|
||||
//#define OPTION_DISPLAY_ALT_HHMM_CLOCK_AND_MAIDENHEAD // display alternating HH:MM clock and maidenhead on LCD row 1 (set position with #define LCD_HHMMCLOCK_POSITION)
|
||||
//#define OPTION_DISPLAY_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD // display constant HH:MM:SS clock and maidenhead on LCD row 1 (set position with #define LCD_CONSTANT_HHMMSSCLOCK_MAIDENHEAD_POSITION)
|
||||
//#define OPTION_DISPLAY_BIG_CLOCK // display date & time clock (set row with #define LCD_BIG_CLOCK_ROW)
|
||||
//#define OPTION_CLOCK_ALWAYS_HAVE_HOUR_LEADING_ZERO
|
||||
//#define OPTION_DISPLAY_GPS_INDICATOR // display GPS indicator on LCD - set position with LCD_GPS_INDICATOR_POSITION and LCD_GPS_INDICATOR_ROW
|
||||
// #define OPTION_PULSE_IGNORE_AMBIGUOUS_PULSES // for azimuth and elevation position pulse input feature, ignore pulses that arrive when no rotation is active
|
||||
// #define OPTION_BUTTON_RELEASE_NO_SLOWDOWN // disables slowdown when CW or CCW button is released, or stop button is depressed
|
||||
// #define OPTION_SYNC_RTC_TO_GPS // if both realtime clock and GPS are present, synchronize realtime clock to GPS
|
||||
|
||||
#define OPTION_DISPLAY_STATUS
|
||||
#define OPTION_DISPLAY_HEADING
|
||||
// #define OPTION_DISPLAY_HEADING_AZ_ONLY
|
||||
// #define OPTION_DISPLAY_HEADING_EL_ONLY
|
||||
// #define OPTION_DISPLAY_HHMM_CLOCK // display HH:MM clock (set position with #define LCD_HHMM_CLOCK_POSITION)
|
||||
// #define OPTION_DISPLAY_HHMMSS_CLOCK // display HH:MM:SS clock (set position with #define LCD_HHMMSS_CLOCK_POSITION)
|
||||
// #define OPTION_DISPLAY_ALT_HHMM_CLOCK_AND_MAIDENHEAD // display alternating HH:MM clock and maidenhead on LCD row 1 (set position with #define LCD_HHMMCLOCK_POSITION)
|
||||
// #define OPTION_DISPLAY_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD // display constant HH:MM:SS clock and maidenhead on LCD row 1 (set position with #define LCD_CONSTANT_HHMMSSCLOCK_MAIDENHEAD_POSITION)
|
||||
// #define OPTION_DISPLAY_BIG_CLOCK // display date & time clock (set row with #define LCD_BIG_CLOCK_ROW)
|
||||
// #define OPTION_CLOCK_ALWAYS_HAVE_HOUR_LEADING_ZERO
|
||||
// #define OPTION_DISPLAY_GPS_INDICATOR // display GPS indicator on LCD - set position with LCD_GPS_INDICATOR_POSITION and LCD_GPS_INDICATOR_ROW
|
||||
// #define OPTION_DISPLAY_DIRECTION_STATUS // LCD N, W, E, S, NW, etc. direction indicator
|
||||
// #define OPTION_DISPLAY_MOON_TRACKING_CONTINUOUSLY // LCD
|
||||
// #define OPTION_DISPLAY_SATELLITE_TRACKING_CONTINUOUSLY // LCD
|
||||
// #define OPTION_DISPLAY_SATELLITE_TRACKING_ALTERNATING // LCD
|
||||
// #define OPTION_DISPLAY_SUN_TRACKING_CONTINUOUSLY // LCD
|
||||
// #define OPTION_DISPLAY_MOON_OR_SUN_OR_SAT_TRACKING_CONDITIONAL // LCD
|
||||
//#define OPTION_DISPLAY_VERSION_ON_STARTUP //code provided by Paolo, IT9IPQ
|
||||
//#define FEATURE_POWER_SWITCH
|
||||
//#define OPTION_EXTERNAL_ANALOG_REFERENCE //Activate external analog voltage reference (needed for RemoteQTH.com unit)
|
||||
//#define OPTION_SYNC_MASTER_CLOCK_TO_SLAVE
|
||||
//#define OPTION_DISABLE_HMC5883L_ERROR_CHECKING
|
||||
#define OPTION_HAMLIB_EASYCOM_AZ_EL_COMMAND_HACK
|
||||
//#define OPTION_HAMLIB_EASYCOM_NO_TERMINATOR_CHARACTER_HACK
|
||||
//#define OPTION_NO_ELEVATION_CHECK_TARGET_DELAY
|
||||
//#define OPTION_RESET_METHOD_JMP_ASM_0
|
||||
//#define OPTION_DONT_READ_GPS_PORT_AS_OFTEN
|
||||
//#define OPTION_GPS_DO_PORT_FLUSHES
|
||||
//#define OPTION_SEND_STRING_OUT_CONTROL_PORT_WHEN_INITIALIZING // change OPTION_SEND_STRING_OUT_CONTROL_PORT_WHEN_INITIALIZING_STRING in settings file
|
||||
//#define OPTION_SAVE_MEMORY_EXCLUDE_EXTENDED_COMMANDS
|
||||
//#define OPTION_SAVE_MEMORY_EXCLUDE_BACKSLASH_CMDS
|
||||
//#define OPTION_GPS_EXCLUDE_MISSING_LF_CR_HANDLING
|
||||
//#define OPTION_MORE_SERIAL_CHECKS
|
||||
//#define OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE
|
||||
#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
|
||||
#define OPTION_DISPLAY_VERSION_ON_STARTUP //code provided by Paolo, IT9IPQ
|
||||
// #define OPTION_LCD_HEADING_FIELD_FIXED_DECIMAL_PLACE
|
||||
// #define OPTION_REVERSE_AZ_HH12_AS5045
|
||||
// #define OPTION_REVERSE_EL_HH12_AS5045
|
||||
|
||||
#define OPTION_STEPPER_MOTOR_MAX_2_KHZ
|
||||
// #define FEATURE_POWER_SWITCH
|
||||
// #define OPTION_EXTERNAL_ANALOG_REFERENCE //Activate external analog voltage reference (needed for RemoteQTH.com unit)
|
||||
// #define OPTION_SYNC_MASTER_CLOCK_TO_SLAVE // use when GPS unit is connected to slave unit and you want to synchronize the master unit clock to the slave unit GPS clock
|
||||
// #define OPTION_SYNC_MASTER_COORDINATES_TO_SLAVE // use when GPS unit is connected to slave unit and you want to synchronize the master unit coordinates to the slave unit GPS
|
||||
// #define OPTION_DISABLE_HMC5883L_ERROR_CHECKING
|
||||
// #define OPTION_HAMLIB_EASYCOM_AZ_EL_COMMAND_HACK
|
||||
// #define OPTION_HAMLIB_EASYCOM_NO_TERMINATOR_CHARACTER_HACK
|
||||
// #define OPTION_NO_ELEVATION_CHECK_TARGET_DELAY
|
||||
// #define OPTION_BLINK_OVERLAP_LED
|
||||
// #define OPTION_EL_PULSE_DEBOUNCE
|
||||
// #define OPTION_SCANCON_2RMHF3600_INC_ENCODER // use with FEATURE_AZ_POSITION_INCREMENTAL_ENCODER and/or FEATURE_EL_POSITION_INCREMENTAL_ENCODER if using the ScanCon 2RMHF3600 incremental encoder
|
||||
// #define OPTION_RESET_METHOD_JMP_ASM_0
|
||||
// #define OPTION_SAVE_MEMORY_EXCLUDE_EXTENDED_COMMANDS
|
||||
// #define OPTION_SAVE_MEMORY_EXCLUDE_BACKSLASH_CMDS
|
||||
// #define OPTION_DONT_READ_GPS_PORT_AS_OFTEN
|
||||
// #define OPTION_GPS_DO_PORT_FLUSHES
|
||||
// #define OPTION_SEND_STRING_OUT_CONTROL_PORT_WHEN_INITIALIZING // change OPTION_SEND_STRING_OUT_CONTROL_PORT_WHEN_INITIALIZING_STRING in settings file
|
||||
// #define OPTION_GPS_EXCLUDE_MISSING_LF_CR_HANDLING
|
||||
// #define OPTION_MORE_SERIAL_CHECKS
|
||||
// #define OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE
|
||||
// #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
|
||||
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_2_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_5_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_10_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_20_KHZ
|
||||
// #define OPTION_STEPPER_MOTOR_MAX_50_KHZ
|
||||
#define OPTION_STEPPER_MOTOR_MAX_20_KHZ
|
||||
|
||||
// #define OPTION_STEPPER_DO_NOT_USE_DIGITALWRITEFAST_LIBRARY
|
||||
|
@ -10,181 +10,197 @@
|
||||
|
||||
/* azimuth pins --------------------- (use just the azimuth pins for an azimuth-only rotator) */
|
||||
|
||||
#define rotate_cw 6 // goes high to activate rotator R (CW) rotation - pin 1 on Yaesu connector
|
||||
#define rotate_ccw 7 // goes high to activate rotator L (CCW) rotation - pin 2 on Yaesu connector
|
||||
#define rotate_cw_ccw 35 // goes high for both CW and CCW rotation
|
||||
#define rotate_cw 7 //6 // goes high to activate rotator R (CW) rotation - pin 1 on Yaesu connector
|
||||
#define rotate_ccw 6 //7 // goes high to activate rotator L (CCW) rotation - pin 2 on Yaesu connector
|
||||
#define rotate_cw_ccw 0 // goes high for both CW and CCW rotation
|
||||
#define rotate_cw_pwm 0 // optional - PWM CW output - set to 0 to disable (must be PWM capable pin)
|
||||
#define rotate_ccw_pwm 0 // optional - PWM CCW output - set to 0 to disable (must be PWM capable pin)
|
||||
#define rotate_cw_ccw_pwm 0 // optional - PWM on CW and CCW output - set to 0 to disable (must be PWM capable pin)
|
||||
#define rotate_cw_freq 0 // optional - CW variable frequency output
|
||||
#define rotate_ccw_freq 0 // optional - CCW variable frequency output
|
||||
#define button_cw 43 // normally open button to ground for manual CW rotation (schematic pin: A1)
|
||||
#define button_ccw 39 // normally open button to ground for manual CCW rotation (schematic pin: A2)
|
||||
#define button_cw 43 // normally open button to ground for manual CW rotation (schematic pin: A2)
|
||||
#define button_ccw 39 // normally open button to ground for manual CCW rotation (schematic pin: A3)
|
||||
#define serial_led 0 // LED blinks when command is received on serial port (set to 0 to disable)
|
||||
#define rotator_analog_az A0 // reads analog azimuth voltage from rotator - pin 4 on Yaesu connector
|
||||
#define rotator_analog_az 0 // reads analog azimuth voltage from rotator - pin 4 on Yaesu connector
|
||||
#define azimuth_speed_voltage 0 // optional - PWM output for speed control voltage feed into rotator (on continually unlike rotate_cw_pwm and rotate_ccw_pwm)
|
||||
#define overlap_led 0 // line goes high when azimuth rotator is in overlap (> 360 rotators)
|
||||
#define overlap_led 0 // line goes active when azimuth rotator is in overlap (> 360 rotators)
|
||||
#define brake_az 0 // goes high to disengage azimuth brake (set to 0 to disable)
|
||||
#define az_speed_pot 0 // connect to wiper of 1K to 10K potentiometer for speed control (set to 0 to disable)
|
||||
#define az_speed_pot 0 // A5 // connect to wiper of 1K to 10K potentiometer for speed control (set to 0 to disable)
|
||||
#define az_preset_pot 0 // connect to wiper of 1K to 10K potentiometer for preset control (set to 0 to disable)
|
||||
#define preset_start_button 0 // connect to momentary switch (ground on button press) for preset start (set to 0 to disable or for preset automatic start)
|
||||
#define button_stop 41 // connect to momentary switch (ground on button press) for preset stop (set to 0 to disable or for preset automatic start)
|
||||
#define rotation_indication_pin 47
|
||||
#define rotation_indication_pin 37
|
||||
#define blink_led 0
|
||||
#define az_stepper_motor_pulse 33 //0
|
||||
#define az_stepper_motor_pulse 33
|
||||
#define az_rotation_stall_detected 0
|
||||
|
||||
|
||||
|
||||
/*----------- elevation pins --------------*/
|
||||
#ifdef FEATURE_ELEVATION_CONTROL
|
||||
#define rotate_up 31 // goes high to activate rotator elevation up
|
||||
#define rotate_down 0 // goes high to activate rotator elevation down
|
||||
#define rotate_up_or_down 27 // goes high when elevation up or down is activated
|
||||
#define rotate_up_pwm 0 // optional - PWM UP output - set to 0 to disable (must be PWM capable pin)
|
||||
#define rotate_down_pwm 0 // optional - PWM DOWN output - set to 0 to disable (must be PWM capable pin)
|
||||
#define rotate_up_down_pwm 0 // optional - PWM on both UP and DOWN (must be PWM capable pin)
|
||||
#define rotate_up_freq 0 // optional - UP variable frequency output
|
||||
#define rotate_down_freq 0 // optional - UP variable frequency output
|
||||
#define rotator_analog_el A1 // reads analog elevation voltage from rotator
|
||||
#define button_up 49 // normally open button to ground for manual up elevation
|
||||
#define button_down 45 // normally open button to ground for manual down rotation
|
||||
#define brake_el 0 // goes high to disengage elevation brake (set to 0 to disable)
|
||||
#define elevation_speed_voltage 0 // optional - PWM output for speed control voltage feed into rotator (on continually unlike rotate_up_pwm and rotate_down_pwm)
|
||||
#define el_stepper_motor_pulse 29
|
||||
#define rotate_up 8 // goes high to activate rotator elevation up
|
||||
#define rotate_down 9 // goes high to activate rotator elevation down
|
||||
#define rotate_up_or_down 27 // goes high when elevation up or down is activated
|
||||
#define rotate_up_pwm 0 // optional - PWM UP output - set to 0 to disable (must be PWM capable pin)
|
||||
#define rotate_down_pwm 0 // optional - PWM DOWN output - set to 0 to disable (must be PWM capable pin)
|
||||
#define rotate_up_down_pwm 0 // optional - PWM on both UP and DOWN (must be PWM capable pin)
|
||||
#define rotate_up_freq 0 // optional - UP variable frequency output
|
||||
#define rotate_down_freq 0 // optional - UP variable frequency output
|
||||
#define rotator_analog_el 0 // reads analog elevation voltage from rotator
|
||||
#define button_up 49 // normally open button to ground for manual up elevation
|
||||
#define button_down 45 // normally open button to ground for manual down rotation
|
||||
#define brake_el 0 // goes high to disengage elevation brake (set to 0 to disable)
|
||||
#define elevation_speed_voltage 0 // optional - PWM output for speed control voltage feed into rotator (on continually unlike rotate_up_pwm and rotate_down_pwm)
|
||||
#define el_stepper_motor_pulse 29
|
||||
#define el_rotation_stall_detected 0
|
||||
#endif //FEATURE_ELEVATION_CONTROL
|
||||
|
||||
// rotary encoder pins and options
|
||||
#ifdef FEATURE_AZ_PRESET_ENCODER
|
||||
#define az_rotary_preset_pin1 0 // CW Encoder Pin
|
||||
#define az_rotary_preset_pin2 0 // CCW Encoder Pin
|
||||
#define az_rotary_preset_pin1 0 // CW Encoder Pin
|
||||
#define az_rotary_preset_pin2 0 // CCW Encoder Pin
|
||||
#endif //FEATURE_AZ_PRESET_ENCODER
|
||||
|
||||
#ifdef FEATURE_EL_PRESET_ENCODER
|
||||
#define el_rotary_preset_pin1 0 // UP Encoder Pin
|
||||
#define el_rotary_preset_pin2 0 // DOWN Encoder Pin
|
||||
#define el_rotary_preset_pin1 0 // UP Encoder Pin
|
||||
#define el_rotary_preset_pin2 0 // DOWN Encoder Pin
|
||||
#endif //FEATURE_EL_PRESET_ENCODER
|
||||
|
||||
#if defined(FEATURE_AZ_POSITION_ROTARY_ENCODER) || defined(FEATURE_AZ_POSITION_ROTARY_ENCODER_USE_PJRC_LIBRARY)
|
||||
#define az_rotary_position_pin1 0 // CW Encoder Pin
|
||||
#define az_rotary_position_pin2 0 // CCW Encoder Pin
|
||||
#define az_rotary_position_pin1 0 // CW Encoder Pin
|
||||
#define az_rotary_position_pin2 0 // CCW Encoder Pin
|
||||
#endif //FEATURE_AZ_POSITION_ROTARY_ENCODER
|
||||
|
||||
#if defined(FEATURE_EL_POSITION_ROTARY_ENCODER) || defined(FEATURE_EL_POSITION_ROTARY_ENCODER_USE_PJRC_LIBRARY)
|
||||
#define el_rotary_position_pin1 0 // CW Encoder Pin
|
||||
#define el_rotary_position_pin2 0 // CCW Encoder Pin
|
||||
#define el_rotary_position_pin1 0 // CW Encoder Pin
|
||||
#define el_rotary_position_pin2 0 // CCW Encoder Pin
|
||||
#endif //FEATURE_EL_POSITION_ROTARY_ENCODER
|
||||
|
||||
#ifdef FEATURE_AZ_POSITION_PULSE_INPUT
|
||||
#define az_position_pulse_pin 0 // must be an interrupt capable pin!
|
||||
#define AZ_POSITION_PULSE_PIN_INTERRUPT 0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 ; Mega: pin 2 = interrupt 0, pin 3 = interrupt 1, pin 21 = interrupt 2, pin 20 = interrupt 3, pin 19 = interrupt 4, pin 18 = interrupt 5
|
||||
#define az_position_pulse_pin 0 // must be an interrupt capable pin!
|
||||
#define AZ_POSITION_PULSE_PIN_INTERRUPT 0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 ; Mega: pin 2 = interrupt 0, pin 3 = interrupt 1, pin 21 = interrupt 2, pin 20 = interrupt 3, pin 19 = interrupt 4, pin 18 = interrupt 5
|
||||
#endif // read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
|
||||
|
||||
#ifdef FEATURE_EL_POSITION_PULSE_INPUT
|
||||
#define el_position_pulse_pin 1 // must be an interrupt capable pin!
|
||||
#define EL_POSITION_PULSE_PIN_INTERRUPT 1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 ; Mega: pin 2 = interrupt 0, pin 3 = interrupt 1, pin 21 = interrupt 2, pin 20 = interrupt 3, pin 19 = interrupt 4, pin 18 = interrupt 5
|
||||
#define el_position_pulse_pin 1 // must be an interrupt capable pin!
|
||||
#define EL_POSITION_PULSE_PIN_INTERRUPT 1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 ; Mega: pin 2 = interrupt 0, pin 3 = interrupt 1, pin 21 = interrupt 2, pin 20 = interrupt 3, pin 19 = interrupt 4, pin 18 = interrupt 5
|
||||
#endif // read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
|
||||
|
||||
#ifdef FEATURE_PARK
|
||||
#define button_park 0
|
||||
#define button_park 0
|
||||
#endif
|
||||
|
||||
//classic 4 bit LCD pins
|
||||
#define lcd_4_bit_rs_pin 12
|
||||
#define lcd_4_bit_enable_pin 11
|
||||
#define lcd_4_bit_d4_pin 5
|
||||
#define lcd_4_bit_d5_pin 4
|
||||
#define lcd_4_bit_d6_pin 3
|
||||
#define lcd_4_bit_d7_pin 2
|
||||
#define lcd_4_bit_rs_pin 22
|
||||
#define lcd_4_bit_enable_pin 24
|
||||
#define lcd_4_bit_d4_pin 26
|
||||
#define lcd_4_bit_d5_pin 28
|
||||
#define lcd_4_bit_d6_pin 30
|
||||
#define lcd_4_bit_d7_pin 32
|
||||
|
||||
|
||||
#ifdef FEATURE_JOYSTICK_CONTROL
|
||||
#define pin_joystick_x A0
|
||||
#define pin_joystick_y A1
|
||||
#define pin_joystick_x A3
|
||||
#define pin_joystick_y A4
|
||||
#endif //FEATURE_JOYSTICK_CONTROL
|
||||
|
||||
#ifdef FEATURE_AZ_POSITION_HH12_AS5045_SSI
|
||||
#define az_hh12_clock_pin 11
|
||||
#define az_hh12_cs_pin 12
|
||||
#define az_hh12_data_pin 13
|
||||
#define az_hh12_clock_pin 11
|
||||
#define az_hh12_cs_pin 12
|
||||
#define az_hh12_data_pin 13
|
||||
#endif //FEATURE_AZ_POSITION_HH_12
|
||||
|
||||
#ifdef FEATURE_EL_POSITION_HH12_AS5045_SSI
|
||||
#define el_hh12_clock_pin 11
|
||||
#define el_hh12_cs_pin 12
|
||||
#define el_hh12_data_pin 13
|
||||
#define el_hh12_clock_pin 53 //11
|
||||
#define el_hh12_cs_pin 52 //12
|
||||
#define el_hh12_data_pin 51 //13
|
||||
#endif //FEATURE_EL_POSITION_HH_12
|
||||
|
||||
#ifdef FEATURE_PARK
|
||||
#define park_in_progress_pin 0 // goes high when a park has been initiated and rotation is in progress
|
||||
#define parked_pin 0 // goes high when in a parked position
|
||||
#define park_in_progress_pin 0 // goes high when a park has been initiated and rotation is in progress
|
||||
#define parked_pin 0 // goes high when in a parked position
|
||||
#endif //FEATURE_PARK
|
||||
|
||||
#define heading_reading_inhibit_pin 0 // input - a high will cause the controller to suspend taking azimuth (and elevation) readings; use when RF interferes with sensors
|
||||
|
||||
#ifdef FEATURE_LIMIT_SENSE
|
||||
#define az_limit_sense_pin 0 // input - low stops azimuthal rotation
|
||||
#define el_limit_sense_pin 0 // input - low stops elevation rotation
|
||||
#define az_limit_sense_pin 0 // input - low stops azimuthal rotation
|
||||
#define el_limit_sense_pin 0 // input - low stops elevation rotation
|
||||
#endif //FEATURE_LIMIT_SENSE
|
||||
|
||||
#ifdef FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
|
||||
#define az_incremental_encoder_pin_phase_a 18 //3 must be an interrupt capable pin
|
||||
#define az_incremental_encoder_pin_phase_b 19 //3 // must be an interrupt capable pin
|
||||
#define az_incremental_encoder_pin_phase_z 15 //4
|
||||
#define AZ_POSITION_INCREMENTAL_ENCODER_A_PIN_INTERRUPT 5 //0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 ; Mega: pin 2 = interrupt 0, pin 3 = interrupt 1, pin 21 = interrupt 2, pin 20 = interrupt 3, pin 19 = interrupt 4, pin 18 = interrupt 5
|
||||
#define AZ_POSITION_INCREMENTAL_ENCODER_B_PIN_INTERRUPT 4 //1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 ; Mega: pin 2 = interrupt 0, pin 3 = interrupt 1, pin 21 = interrupt 2, pin 20 = interrupt 3, pin 19 = interrupt 4, pin 18 = interrupt 5
|
||||
#define az_incremental_encoder_pin_phase_a 18 //3 must be an interrupt capable pin
|
||||
#define az_incremental_encoder_pin_phase_b 19 //3 // must be an interrupt capable pin
|
||||
#define az_incremental_encoder_pin_phase_z 15 //4
|
||||
#define AZ_POSITION_INCREMENTAL_ENCODER_A_PIN_INTERRUPT 5 //0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 ; Mega: pin 2 = interrupt 0, pin 3 = interrupt 1, pin 21 = interrupt 2, pin 20 = interrupt 3, pin 19 = interrupt 4, pin 18 = interrupt 5
|
||||
#define AZ_POSITION_INCREMENTAL_ENCODER_B_PIN_INTERRUPT 4 //1 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 ; Mega: pin 2 = interrupt 0, pin 3 = interrupt 1, pin 21 = interrupt 2, pin 20 = interrupt 3, pin 19 = interrupt 4, pin 18 = interrupt 5
|
||||
// read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
|
||||
#endif //FEATURE_AZ_POSITION_INCREMENTAL_ENCODER
|
||||
|
||||
#ifdef FEATURE_EL_POSITION_INCREMENTAL_ENCODER
|
||||
#define el_incremental_encoder_pin_phase_a 2 //2 // must be an interrupt capable pin
|
||||
#define el_incremental_encoder_pin_phase_b 3 //3 // must be an interrupt capable pin
|
||||
#define el_incremental_encoder_pin_phase_z 5 //4
|
||||
#define EL_POSITION_INCREMENTAL_ENCODER_A_PIN_INTERRUPT 0 //0 // Uno: pin 2 = interrupt 0, pin 3 = interrupt 1 ; Mega: pin 2 = interrupt 0, pin 3 = interrupt 1, pin 21 = interrupt 2, pin 20 = interrupt 3, pin 19 = interrupt 4, pin 18 = interrupt 5
|
||||
#define EL_POSITION_INCREMENTAL_ENCODER_B_PIN_INTERRUPT 1 //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
|
||||
#define el_incremental_encoder_pin_phase_a 2 //18 //2 // must be an interrupt capable pin
|
||||
#define el_incremental_encoder_pin_phase_b 3 //19 //3 // must be an interrupt capable pin
|
||||
#define el_incremental_encoder_pin_phase_z 5 //22 //4
|
||||
#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
|
||||
#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
|
||||
// read http://arduino.cc/en/Reference/AttachInterrupt for details on hardware and interrupts
|
||||
#endif //FEATURE_EL_POSITION_INCREMENTAL_ENCODER
|
||||
|
||||
#ifdef FEATURE_YOURDUINO_I2C_LCD
|
||||
#define En_pin 2
|
||||
#define Rw_pin 1
|
||||
#define Rs_pin 0
|
||||
#define D4_pin 4
|
||||
#define D5_pin 5
|
||||
#define D6_pin 6
|
||||
#define D7_pin 7
|
||||
#define En_pin 2
|
||||
#define Rw_pin 1
|
||||
#define Rs_pin 0
|
||||
#define D4_pin 4
|
||||
#define D5_pin 5
|
||||
#define D6_pin 6
|
||||
#define D7_pin 7
|
||||
#endif //FEATURE_YOURDUINO_I2C_LCD
|
||||
|
||||
#ifdef FEATURE_MOON_TRACKING
|
||||
#define moon_tracking_active_pin 0 // goes high when moon tracking is active
|
||||
#define moon_tracking_activate_line 0 // ground this pin to activate moon tracking (not for use with a button)
|
||||
#define moon_tracking_button 0 // use with a normally open momentary switch to ground
|
||||
#define moon_tracking_active_pin 0 // goes high when moon tracking is active
|
||||
#define moon_tracking_activate_line 0 // ground this pin to activate moon tracking (not for use with a button)
|
||||
#define moon_tracking_button 0 // use with a normally open momentary switch to ground
|
||||
#endif //FEATURE_MOON_TRACKING
|
||||
|
||||
#ifdef FEATURE_SUN_TRACKING
|
||||
#define sun_tracking_active_pin 0 // goes high when sun tracking is active
|
||||
#define sun_tracking_activate_line 0 // ground this pin to activate sun tracking (not for use with a button)
|
||||
#define sun_tracking_button 0 // use with a normally open momentary switch to ground
|
||||
#define sun_tracking_active_pin 0 // goes high when sun tracking is active
|
||||
#define sun_tracking_activate_line 0 // ground this pin to activate sun tracking (not for use with a button)
|
||||
#define sun_tracking_button 0 // use with a normally open momentary switch to ground
|
||||
#endif //FEATURE_SUN_TRACKING
|
||||
|
||||
#ifdef FEATURE_GPS
|
||||
#define gps_sync 0
|
||||
#define gps_sync 0
|
||||
#endif //FEATURE_GPS
|
||||
|
||||
#ifdef FEATURE_POWER_SWITCH
|
||||
#define power_switch 0 // use with FEATURE_POWER_SWITCH
|
||||
#define power_switch 0 // use with FEATURE_POWER_SWITCH
|
||||
#endif //FEATURE_POWER_SWITCH
|
||||
|
||||
#ifdef FEATURE_EL_POSITION_MEMSIC_2125
|
||||
#define pin_memsic_2125_x 0
|
||||
#define pin_memsic_2125_y 0
|
||||
#define pin_memsic_2125_x 0
|
||||
#define pin_memsic_2125_y 0
|
||||
#endif //FEATURE_EL_POSITION_MEMSIC_2125
|
||||
|
||||
#ifdef FEATURE_ANALOG_OUTPUT_PINS
|
||||
#define pin_analog_az_out 0
|
||||
#define pin_analog_el_out 0
|
||||
#define pin_analog_az_out 0
|
||||
#define pin_analog_el_out 0
|
||||
#endif //FEATURE_ANALOG_OUTPUT_PINS
|
||||
|
||||
#ifdef FEATURE_SUN_PUSHBUTTON_AZ_EL_CALIBRATION
|
||||
#define pin_sun_pushbutton_calibration 0 // normally HIGH, have button pull LOW
|
||||
#endif //FEATURE_SUN_PUSHBUTTON_AZ_EL_CALIBRATION
|
||||
|
||||
#ifdef FEATURE_MOON_PUSHBUTTON_AZ_EL_CALIBRATION
|
||||
#define pin_moon_pushbutton_calibration 0 // normally HIGH, have button pull LOW
|
||||
#endif //FEATURE_MOON_PUSHBUTTON_AZ_EL_CALIBRATION
|
||||
|
||||
//#define reset_pin 22 // if defined, goes HIGH to reset unit
|
||||
|
||||
#if defined(FEATURE_AZ_POSITION_A2_ABSOLUTE_ENCODER) || defined(FEATURE_EL_POSITION_A2_ABSOLUTE_ENCODER)
|
||||
#define pin_sei_bus_busy 24
|
||||
#define pin_sei_bus_send_receive 22
|
||||
#endif
|
||||
|
||||
#ifdef FEATURE_YWROBOT_I2C_DISPLAY
|
||||
#define ywrobot_address 0x3F
|
||||
#define ywrobot_pin_en 2
|
||||
@ -219,3 +235,4 @@
|
||||
#define satellite_tracking_active_pin 0
|
||||
#define satellite_tracking_activate_line 0
|
||||
#define satellite_tracking_button 0 // use with a normally open momentary switch to ground
|
||||
|
||||
|
@ -1,8 +1,8 @@
|
||||
|
||||
/* -------------------------- rotation settings ---------------------------------------*/
|
||||
|
||||
#define AZIMUTH_STARTING_POINT_EEPROM_INITIALIZE 180 // the starting point in degrees of the azimuthal rotator - only used for initializing EEPROM the first time the code is run
|
||||
#define AZIMUTH_ROTATION_CAPABILITY_EEPROM_INITIALIZE 450 // the default rotation capability of the rotator in degrees - only used for initializing EEPROM the first time the code is run
|
||||
#define AZIMUTH_STARTING_POINT_EEPROM_INITIALIZE 0 // the starting point in degrees of the azimuthal rotator - only used for initializing EEPROM the first time the code is run
|
||||
#define AZIMUTH_ROTATION_CAPABILITY_EEPROM_INITIALIZE 360 // the default rotation capability of the rotator in degrees - only used for initializing EEPROM the first time the code is run
|
||||
|
||||
/*
|
||||
|
||||
@ -41,59 +41,60 @@ You can tweak these, but read the online documentation!
|
||||
// turning on when going CW and crossing 180, ANALOG_AZ_OVERLAP_DEGREES should be set for 540 (180 + 360)
|
||||
// To totally disable overlap functionality, comment out this #define
|
||||
|
||||
#define OPTION_OVERLAP_LED_BLINK_MS 100
|
||||
|
||||
// PWM speed voltage settings
|
||||
#define PWM_SPEED_VOLTAGE_X1 74 // 0 to 255
|
||||
#define PWM_SPEED_VOLTAGE_X1 64 // 0 to 255
|
||||
#define PWM_SPEED_VOLTAGE_X2 128 // 0 to 255
|
||||
#define PWM_SPEED_VOLTAGE_X3 191 // 0 to 255
|
||||
#define PWM_SPEED_VOLTAGE_X4 253 // 0 to 255
|
||||
|
||||
//AZ
|
||||
#define AZ_SLOWSTART_DEFAULT 1 // 0 = off ; 1 = on
|
||||
#define AZ_SLOWDOWN_DEFAULT 1 // 0 = off ; 1 = on
|
||||
#define AZ_SLOW_START_UP_TIME 550 // if slow start is enabled, the unit will ramp up speed for this many milliseconds
|
||||
#define AZ_SLOW_START_STARTING_PWM 2 // PWM starting value for slow start (must be < 256)
|
||||
#define AZ_SLOW_START_STEPS 20 // must be < 256
|
||||
#define AZ_SLOWSTART_DEFAULT 0 // 0 = off ; 1 = on
|
||||
#define AZ_SLOWDOWN_DEFAULT 0 // 0 = off ; 1 = on
|
||||
#define AZ_SLOW_START_UP_TIME 2000 // if slow start is enabled, the unit will ramp up speed for this many milliseconds
|
||||
#define AZ_SLOW_START_STARTING_PWM 5 // PWM starting value for slow start (must be < 256)
|
||||
#define AZ_SLOW_START_STEPS 255 // must be < 256
|
||||
|
||||
|
||||
#define SLOW_DOWN_BEFORE_TARGET_AZ 5.0 // if slow down is enabled, slowdown will be activated within this many degrees of target azimuth
|
||||
#define AZ_SLOW_DOWN_PWM_START 150 // starting PWM value for slow down (must be < 256)
|
||||
#define AZ_SLOW_DOWN_PWM_STOP 10 // ending PWM value for slow down (must be < 256)
|
||||
#define AZ_SLOW_DOWN_STEPS 200 //20 // must be < 256
|
||||
#define AZ_INITIALLY_IN_SLOW_DOWN_PWM 10 // PWM value to start at if we're starting in the slow down zone (1 - 255)
|
||||
#define AZ_SLOW_DOWN_PWM_START 255 // starting PWM value for slow down (must be < 256)
|
||||
#define AZ_SLOW_DOWN_PWM_STOP 0 // ending PWM value for slow down (must be < 256)
|
||||
#define AZ_SLOW_DOWN_STEPS 255 //20 // must be < 256
|
||||
#define AZ_INITIALLY_IN_SLOW_DOWN_PWM 50 // PWM value to start at if we're starting in the slow down zone (1 - 255)
|
||||
|
||||
//EL
|
||||
#define EL_SLOWSTART_DEFAULT 1 // 0 = off ; 1 = on
|
||||
#define EL_SLOWDOWN_DEFAULT 1 // 0 = off ; 1 = on
|
||||
#define EL_SLOW_START_UP_TIME 200 // if slow start is enabled, the unit will ramp up speed for this many milliseconds
|
||||
#define EL_SLOW_START_STARTING_PWM 3 // PWM starting value for slow start (must be < 256 and > 0)
|
||||
#define EL_SLOW_START_STEPS 20 // must be < 256
|
||||
#define EL_SLOWSTART_DEFAULT 0 // 0 = off ; 1 = on
|
||||
#define EL_SLOWDOWN_DEFAULT 0 // 0 = off ; 1 = on
|
||||
#define EL_SLOW_START_UP_TIME 5000 // if slow start is enabled, the unit will ramp up speed for this many milliseconds
|
||||
#define EL_SLOW_START_STARTING_PWM 3 // PWM starting value for slow start (must be < 256)
|
||||
#define EL_SLOW_START_STEPS 255 // must be < 256
|
||||
|
||||
#define SLOW_DOWN_BEFORE_TARGET_EL 20.0 //5.0 // if slow down is enabled, slowdown will be activated within this many degrees of target elevtion
|
||||
#define EL_SLOW_DOWN_PWM_START 50 //150 // starting PWM value for slow down (must be < 256 and > 0)
|
||||
#define EL_SLOW_DOWN_PWM_STOP 1 // ending PWM value for slow down (must be < 256 and > 0)
|
||||
#define EL_SLOW_DOWN_STEPS 500 //200
|
||||
#define EL_INITIALLY_IN_SLOW_DOWN_PWM 10 // PWM value to start at if we're starting in the slow down zone (1 - 255)
|
||||
#define SLOW_DOWN_BEFORE_TARGET_EL 10.0 // if slow down is enabled, slowdown will be activated within this many degrees of target elevation
|
||||
#define EL_SLOW_DOWN_PWM_START 255 // starting PWM value for slow down (must be < 256)
|
||||
#define EL_SLOW_DOWN_PWM_STOP 4 // ending PWM value for slow down (must be < 256)
|
||||
#define EL_SLOW_DOWN_STEPS 255
|
||||
#define EL_INITIALLY_IN_SLOW_DOWN_PWM 20 // PWM value to start at if we're starting in the slow down zone (1 - 255)
|
||||
|
||||
#define TIMED_SLOW_DOWN_TIME 500
|
||||
#define TIMED_SLOW_DOWN_TIME 2000
|
||||
|
||||
// Variable frequency output settings and FEATURE_STEPPER_MOTOR settings
|
||||
#define AZ_VARIABLE_FREQ_OUTPUT_LOW 31 // Frequency in hertz of minimum speed (rotate_cw_freq, rotate_ccw_freq minimum value: 31 !)
|
||||
#define AZ_VARIABLE_FREQ_OUTPUT_HIGH 1000 // Frequency in hertz of maximum speed (FEATURE_STEPPER_MOTOR maximum value 2000 unless you change OPTION_STEPPER_MOTOR_MAX_X_KHZ in features file)
|
||||
#define EL_VARIABLE_FREQ_OUTPUT_LOW 31 // Frequency in hertz of minimum speed (rotate_up_freq, rotate_down_freq minimum value: 31 !)
|
||||
#define EL_VARIABLE_FREQ_OUTPUT_HIGH 1000 // Frequency in hertz of maximum speed (FEATURE_STEPPER_MOTOR maximum value: 2000 unless you change OPTION_STEPPER_MOTOR_MAX_X_KHZ in features file)
|
||||
#define AZ_VARIABLE_FREQ_OUTPUT_LOW 20 // Frequency in hertz of minimum speed (rotate_cw_freq, rotate_ccw_freq minimum value: 31 !)
|
||||
#define AZ_VARIABLE_FREQ_OUTPUT_HIGH 500 // Frequency in hertz of maximum speed (FEATURE_STEPPER_MOTOR maximum value 2000 unless you change OPTION_STEPPER_MOTOR_MAX_X_KHZ in features file)
|
||||
#define EL_VARIABLE_FREQ_OUTPUT_LOW 20 // Frequency in hertz of minimum speed (rotate_up_freq, rotate_down_freq minimum value: 31 !)
|
||||
#define EL_VARIABLE_FREQ_OUTPUT_HIGH 250 // Frequency in hertz of maximum speed (FEATURE_STEPPER_MOTOR maximum value: 2000 unless you change OPTION_STEPPER_MOTOR_MAX_X_KHZ in features file)
|
||||
|
||||
// Settings for OPTION_AZ_MANUAL_ROTATE_LIMITS
|
||||
#define AZ_MANUAL_ROTATE_CCW_LIMIT 179 // if using a rotator that starts at 180 degrees, set this to something like 185
|
||||
#define AZ_MANUAL_ROTATE_CW_LIMIT 539 // add 360 to this if you go past 0 degrees (i.e. 180 CW after 0 degrees = 540)
|
||||
#define AZ_MANUAL_ROTATE_CCW_LIMIT 0 // if using a rotator that starts at 180 degrees, set this to something like 185
|
||||
#define AZ_MANUAL_ROTATE_CW_LIMIT 535 // add 360 to this if you go past 0 degrees (i.e. 180 CW after 0 degrees = 540)
|
||||
|
||||
// Settings for OPTION_EL_MANUAL_ROTATE_LIMITS
|
||||
#define EL_MANUAL_ROTATE_DOWN_LIMIT 10
|
||||
#define EL_MANUAL_ROTATE_UP_LIMIT 170
|
||||
#define EL_MANUAL_ROTATE_DOWN_LIMIT -1
|
||||
#define EL_MANUAL_ROTATE_UP_LIMIT 181
|
||||
|
||||
// Speed pot settings
|
||||
#define SPEED_POT_LOW 0
|
||||
#define SPEED_POT_HIGH 1023
|
||||
#define SPEED_POT_HIGH 850
|
||||
#define SPEED_POT_LOW_MAP 1
|
||||
#define SPEED_POT_HIGH_MAP 255
|
||||
|
||||
@ -106,20 +107,20 @@ You can tweak these, but read the online documentation!
|
||||
#define ENCODER_PRESET_TIMEOUT 5000
|
||||
|
||||
// various code settings
|
||||
#define AZIMUTH_TOLERANCE 0.10 // rotator will stop within X degrees when doing autorotation
|
||||
#define AZIMUTH_TOLERANCE 0.1 // rotator will stop within X degrees when doing autorotation
|
||||
#define ELEVATION_TOLERANCE 0.1 //1.0
|
||||
#define OPERATION_TIMEOUT 120000 // timeout for any rotation operation in mS ; 120 seconds is usually enough unless you have the speed turned down
|
||||
#define TIMED_INTERVAL_ARRAY_SIZE 20
|
||||
|
||||
#define LCD_COLUMNS 20 //16
|
||||
#define LCD_ROWS 4 //2
|
||||
#define LCD_ROWS 4 //2 // this is automatically set below for HARDWARE_EA4TX_ARS_USB and HARDWARE_M0UPU
|
||||
#define LCD_UPDATE_TIME 1000 // LCD update time in milliseconds
|
||||
#define LCD_HHMM_CLOCK_POSITION LEFT //LEFT or RIGHT
|
||||
#define LCD_HHMMSS_CLOCK_POSITION LEFT //LEFT or RIGHT
|
||||
#define LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_POSITION LEFT
|
||||
#define LCD_ALT_HHMM_CLOCK_AND_MAIDENHEAD_ROW 1
|
||||
#define LCD_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD_POSITION LEFT
|
||||
#define LCD_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD_ROW 1
|
||||
#define LCD_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD_POSITION CENTER
|
||||
#define LCD_CONSTANT_HHMMSS_CLOCK_AND_MAIDENHEAD_ROW 3
|
||||
#define LCD_BIG_CLOCK_ROW 4
|
||||
#define LCD_GPS_INDICATOR_POSITION RIGHT //LEFT or RIGHT
|
||||
#define LCD_GPS_INDICATOR_ROW 1
|
||||
@ -135,6 +136,10 @@ You can tweak these, but read the online documentation!
|
||||
|
||||
#define LCD_HEADING_ROW 2
|
||||
#define LCD_HEADING_FIELD_SIZE 20
|
||||
#define LCD_AZ_ONLY_HEADING_ROW 1
|
||||
#define LCD_AZ_ONLY_HEADING_FIELD_SIZE 20
|
||||
#define LCD_EL_ONLY_HEADING_ROW 2
|
||||
#define LCD_EL_ONLY_HEADING_FIELD_SIZE 20
|
||||
#define LCD_STATUS_ROW 1
|
||||
#define LCD_STATUS_FIELD_SIZE 20
|
||||
#define LCD_DIRECTION_ROW 1
|
||||
@ -196,7 +201,6 @@ You can tweak these, but read the online documentation!
|
||||
#define MOON_AOS_ELEVATION_MIN 0
|
||||
#define MOON_AOS_ELEVATION_MAX 180
|
||||
|
||||
|
||||
#define SUN_TRACKING_CHECK_INTERVAL 5000 // This is only written to the configuration upon first boot of the code or when EEPROM_MAGIC_NUMBER is changed in rotator.h
|
||||
#define SUN_AOS_AZIMUTH_MIN 0
|
||||
#define SUN_AOS_AZIMUTH_MAX 360
|
||||
@ -218,10 +222,12 @@ You can tweak these, but read the online documentation!
|
||||
#define SYNC_RTC_TO_GPS_SECONDS 12 // synchronize realtime clock to GPS every x seconds
|
||||
|
||||
#define SYNC_MASTER_CLOCK_TO_SLAVE_CLOCK_SECS 10 // for OPTION_SYNC_MASTER_CLOCK_TO_SLAVE - use when GPS unit is connected to slave unit and you want to synchronize the master unit clock to the slave unit clock
|
||||
#define SYNC_MASTER_COORDINATES_TO_SLAVE_SECS 20 // for OPTION_SYNC_MASTER_COORDINATES_TO_SLAVE - use when GPS unit is connected to slave unit and you want to synchronize the master unit coordinates to the slave unit GPS
|
||||
|
||||
|
||||
#define ETHERNET_MAC_ADDRESS 0xDE,0xAD,0xBE,0xEF,0xFE,0xEE //<-DON'T FORGET TO USE DIFFERENT MAC ADDRESSES FOR MASTER AND SLAVE!!!
|
||||
#define ETHERNET_IP_ADDRESS 192,168,1,172 //<-DON'T FORGET TO USE DIFFERENT IP ADDRESSES FOR MASTER AND SLAVE!!!
|
||||
#define ETHERNET_IP_GATEWAY 192,168,1,254
|
||||
#define ETHERNET_IP_GATEWAY 192,168,1,1
|
||||
#define ETHERNET_IP_SUBNET_MASK 255,255,255,0
|
||||
#define ETHERNET_TCP_PORT_0 23
|
||||
#define ETHERNET_TCP_PORT_1 24
|
||||
@ -258,11 +264,12 @@ You can tweak these, but read the online documentation!
|
||||
// #define AZIMUTH_CALIBRATION_TO_ARRAY {359,0}
|
||||
|
||||
|
||||
//#define ELEVATION_CALIBRATION_FROM_ARRAY {-180,0,180}
|
||||
//#define ELEVATION_CALIBRATION_TO_ARRAY {-180,0,180}
|
||||
#define ELEVATION_CALIBRATION_FROM_ARRAY {-360,0,360}
|
||||
#define ELEVATION_CALIBRATION_TO_ARRAY {-360,0,360}
|
||||
|
||||
#define ELEVATION_CALIBRATION_FROM_ARRAY {0,269.9,270.0,359.9}
|
||||
#define ELEVATION_CALIBRATION_TO_ARRAY {0,269.9,-90.0,-0.1}
|
||||
// example: reverse elevation sensing
|
||||
//#define ELEVATION_CALIBRATION_FROM_ARRAY {0,180,360}
|
||||
//#define ELEVATION_CALIBRATION_TO_ARRAY {180,0,-180}
|
||||
|
||||
#define ANALOG_OUTPUT_MAX_EL_DEGREES 180
|
||||
|
||||
@ -300,8 +307,8 @@ You can tweak these, but read the online documentation!
|
||||
#define AUDIBLE_PIN_INACTIVE_STATE LOW
|
||||
#define AUDIBLE_PIN_TONE_FREQ 1000
|
||||
#define AUDIBLE_ALERT_AT_STARTUP 1
|
||||
#define AUDIBLE_ALERT_AT_AZ_TARGET 1
|
||||
#define AUDIBLE_ALERT_AT_EL_TARGET 1
|
||||
#define AUDIBLE_ALERT_AT_AZ_TARGET 1 // factory default setting
|
||||
#define AUDIBLE_ALERT_AT_EL_TARGET 1 // factory default setting
|
||||
|
||||
#define OVERLAP_LED_ACTIVE_STATE HIGH
|
||||
#define OVERLAP_LED_INACTIVE_STATE LOW
|
||||
@ -317,7 +324,7 @@ You can tweak these, but read the online documentation!
|
||||
|
||||
//#define SET_I2C_BUS_SPEED 800000L // Can set up to 800 kHz, depending on devices. 800000L = 800 khz, 400000L = 400 khz. Default is 100 khz
|
||||
|
||||
#define ROTATIONAL_AND_CONFIGURATION_CMD_IGNORE_TIME_MS 5000 // if OPTION_ALLOW_ROTATIONAL_AND_CONFIGURATION_CMDS_AT_BOOT_UP is enabled, ignore configuration and rotational command for this many mS after boot up
|
||||
#define ROTATIONAL_AND_CONFIGURATION_CMD_IGNORE_TIME_MS 100 // if OPTION_ALLOW_ROTATIONAL_AND_CONFIGURATION_CMDS_AT_BOOT_UP is enabled, ignore configuration and rotational command for this many mS after boot up
|
||||
|
||||
/* Deprecated in version 2020.06.20.01
|
||||
#define ROTATE_PIN_INACTIVE_VALUE LOW
|
||||
@ -332,7 +339,7 @@ You can tweak these, but read the online documentation!
|
||||
// Changed in 2020.06.26.02
|
||||
// Serial Port Settings
|
||||
#define CONTROL_PORT_MAPPED_TO &Serial // change this line to map the control port to a different serial port (Serial1, Serial2, etc.)
|
||||
#define CONTROL_PORT_BAUD_RATE 9600
|
||||
#define CONTROL_PORT_BAUD_RATE 115200 //9600
|
||||
//#define REMOTE_PORT Serial3 // used to control remote unit
|
||||
#define REMOTE_UNIT_PORT_BAUD_RATE 9600
|
||||
#define GPS_PORT Serial2
|
||||
@ -352,7 +359,7 @@ You can tweak these, but read the online documentation!
|
||||
|
||||
// Added in 2020.07.24.01
|
||||
#define SATELLITE_UPDATE_ARRAY_ORDER_INTERVAL_MS 5000
|
||||
#define SATELLITE_TRACKING_UPDATE_INTERVAL 5000 // This is only written to the configuration upon first boot of the code or when EEPROM_MAGIC_NUMBER is changed in rotator.h
|
||||
#define SATELLITE_TRACKING_UPDATE_INTERVAL 5000
|
||||
|
||||
// Added in 2020.07.25.01
|
||||
#define LCD_SATELLITE_TRACKING_ROW 4
|
||||
@ -371,15 +378,6 @@ You can tweak these, but read the online documentation!
|
||||
// Added in 2020.08.24.01
|
||||
#define NEXTION_NUMBER_OF_NEXT_SATELLITES 6
|
||||
|
||||
// Added / Updated in 2020.08.26.02
|
||||
// #define SATELLITE_CALC_THROTTLE_DOWN_TO_MEDIUM_RESOLUTION_MS 1000
|
||||
// #define SATELLITE_CALC_THROTTLE_DOWN_TO_LOW_RESOLUTION_MS 5000
|
||||
// #define SATELLITE_AOS_LOS_CALC_RESOLUTION_HIGH_SECS 10
|
||||
// #define SATELLITE_AOS_LOS_CALC_RESOLUTION_MEDIUM_SECS 30
|
||||
// #define SATELLITE_AOS_LOS_CALC_RESOLUTION_LOW_SECS 120
|
||||
// #define SATELLITE_AOS_LOS_CALC_RESOLUTION_HIGH_TRIGGER_SECS 3600 //300 //next event is < 5 minutes
|
||||
// #define SATELLITE_AOS_LOS_CALC_RESOLUTION_MEDIUM_TRIGGER_SECS 10800 //3600 //next < 1 hour
|
||||
|
||||
// Added / Updated in 2020.08.29.01
|
||||
#define SATELLITE_CALC_TIMEOUT_MS 10000
|
||||
#define SATELLITE_AOS_ELEVATION_MIN 0.0
|
||||
@ -387,6 +385,4 @@ You can tweak these, but read the online documentation!
|
||||
#define SATELLITE_CALC_STAGE_2_RESOLUTION_SECS 10
|
||||
#define SATELLITE_CALC_STAGE_3_RESOLUTION_SECS 1
|
||||
|
||||
// Deprecated in 2020.08.30.01
|
||||
// #define PARK_AZIMUTH 0.0 // replace the 0.0 with your park azimuth; azimuth is in raw degrees (i.e. on a 180 degree starting point rotator, 0 degrees = 360)
|
||||
// #define PARK_ELEVATION 0.0 // replace the 0.0 with your park elevation
|
||||
|
||||
|
16
libraries/digitalWriteFast/Examples/ReadFast/ReadFast.ino
Executable file
16
libraries/digitalWriteFast/Examples/ReadFast/ReadFast.ino
Executable file
@ -0,0 +1,16 @@
|
||||
#include <digitalWriteFast.h>
|
||||
#define pinNum 9
|
||||
//int pinNum = 9; //do not use variables, macro will revert to the slower pinMode()
|
||||
//const int pinNum = 9; //this is a constant, will use port manipulation (fast)
|
||||
|
||||
void setup() {
|
||||
pinModeFast(pinNum, INPUT);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
bool reading = digitalReadFast(pinNum);
|
||||
|
||||
if (reading == ERROR_SEQUENCE) { //ERROR_SEQUENCE defined as 0b10101010
|
||||
// pinNum is not a const and will always return as HIGH
|
||||
}
|
||||
}
|
45
libraries/digitalWriteFast/Examples/ToggleFast/ToggleFast.ino
Executable file
45
libraries/digitalWriteFast/Examples/ToggleFast/ToggleFast.ino
Executable file
@ -0,0 +1,45 @@
|
||||
#include <digitalWriteFast.h>
|
||||
#define pinNum 9
|
||||
//int pinNum = 9; //do not use variables, macro will revert to the slower digitalWrite()
|
||||
//const int pinNum = 9; //this is a constant, will use port manipulation (fast)
|
||||
void setup() {
|
||||
pinModeFast(pinNum, OUTPUT);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
//the pin is toggled multiple time before looping is because it took too long that the pin stayed low for 600ns, while clearing or setting the pin only took 125ns. For 16MHz Arduino Uno.
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
}
|
37
libraries/digitalWriteFast/Examples/ToggleSlow/ToggleSlow.ino
Executable file
37
libraries/digitalWriteFast/Examples/ToggleSlow/ToggleSlow.ino
Executable file
@ -0,0 +1,37 @@
|
||||
#define pinNum 9
|
||||
//int pinNum = 9; //for regular digitalWrite(), does matter constant or variable
|
||||
//const int pinNum = 9; //this is a constant
|
||||
|
||||
void setup() {
|
||||
pinMode(pinNum, OUTPUT);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
//digitalWrite is so slow that , you don't actually need to toggle multiple times in 1 loop
|
||||
// because digitalWrite takes 6280ns but to return to the start of loop takes only 600ns.
|
||||
// this only makes a big deal when using digitalWriteFast(pinNum, state);
|
||||
digitalWrite(pinNum, HIGH);
|
||||
digitalWrite(pinNum, LOW);
|
||||
digitalWrite(pinNum, HIGH);
|
||||
digitalWrite(pinNum, LOW);
|
||||
digitalWrite(pinNum, HIGH);
|
||||
digitalWrite(pinNum, LOW);
|
||||
digitalWrite(pinNum, HIGH);
|
||||
digitalWrite(pinNum, LOW);
|
||||
digitalWrite(pinNum, HIGH);
|
||||
digitalWrite(pinNum, LOW);
|
||||
digitalWrite(pinNum, HIGH);
|
||||
digitalWrite(pinNum, LOW);
|
||||
digitalWrite(pinNum, HIGH);
|
||||
digitalWrite(pinNum, LOW);
|
||||
digitalWrite(pinNum, HIGH);
|
||||
digitalWrite(pinNum, LOW);
|
||||
digitalWrite(pinNum, HIGH);
|
||||
digitalWrite(pinNum, LOW);
|
||||
digitalWrite(pinNum, HIGH);
|
||||
digitalWrite(pinNum, LOW);
|
||||
digitalWrite(pinNum, HIGH);
|
||||
digitalWrite(pinNum, LOW);
|
||||
digitalWrite(pinNum, HIGH);
|
||||
digitalWrite(pinNum, LOW);
|
||||
}
|
57
libraries/digitalWriteFast/NOTES/NOTES.md
Executable file
57
libraries/digitalWriteFast/NOTES/NOTES.md
Executable file
@ -0,0 +1,57 @@
|
||||
# Notes
|
||||
|
||||
Notes down the observations, experiences and occurrences during the development of the repo.
|
||||
|
||||
Useful for explaining certain decisions.
|
||||
|
||||
|
||||
###### speed of digitalWriteFast:
|
||||
|
||||
On Arduino Uno clone, 16MHz
|
||||
|
||||
digitalWriteFast is so fast that
|
||||
|
||||
```C++
|
||||
void loop() {
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
}
|
||||
```
|
||||
|
||||
The above did not result in 50% duty cycle.
|
||||
![Graph 1](graphs/1.png)
|
||||
|
||||
Rather, the pin stays low for quite some time until the program loops again.
|
||||
|
||||
Took around 600ns for the program to repeat
|
||||
|
||||
|
||||
So, the below was done instead:
|
||||
|
||||
```C++
|
||||
void loop() {
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
// ... and it goes on, multiple times
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
digitalWriteFast(pinNum, HIGH);
|
||||
digitalWriteFast(pinNum, LOW);
|
||||
}
|
||||
```
|
||||
|
||||
It only took 250ns to toggle, meaning it took only 250ns/2= **125ns** to set or clear the pin/port.
|
||||
![Graph 2](graphs/2.png)
|
||||
|
||||
###### speed of digitalWrite:
|
||||
|
||||
On Arduino Uno clone, 16MHz
|
||||
|
||||
It took 12.56us to toggle, meaning it took 12.56us/2= **6280ns** to set or clear the pin/port.
|
||||
|
||||
**50 times slower than direct port manipulation!**
|
||||
|
||||
![Graph 3](graphs/3.png)
|
||||
|
BIN
libraries/digitalWriteFast/NOTES/graphs/1.png
Executable file
BIN
libraries/digitalWriteFast/NOTES/graphs/1.png
Executable file
Binary file not shown.
After Width: | Height: | Size: 45 KiB |
BIN
libraries/digitalWriteFast/NOTES/graphs/2.png
Executable file
BIN
libraries/digitalWriteFast/NOTES/graphs/2.png
Executable file
Binary file not shown.
After Width: | Height: | Size: 50 KiB |
BIN
libraries/digitalWriteFast/NOTES/graphs/3.png
Executable file
BIN
libraries/digitalWriteFast/NOTES/graphs/3.png
Executable file
Binary file not shown.
After Width: | Height: | Size: 45 KiB |
64
libraries/digitalWriteFast/README.md
Executable file
64
libraries/digitalWriteFast/README.md
Executable file
@ -0,0 +1,64 @@
|
||||
# digitalWriteFast
|
||||
Arduino library for faster `digitalWrite()` using direct port manipulation and macro for ease in pin assignments.
|
||||
Which actually also does faster `pinMode()` and `digitalRead()`.
|
||||
|
||||
## Usage
|
||||
Include the library:
|
||||
`#include <digitalWriteFast.h>`
|
||||
|
||||
Macro definitions:
|
||||
* `digitalWriteFast(pinNum, state)` (sets or clears pin/port faster)
|
||||
* `pinModeFast(pinNum, mode)` (sets pin/port as input or output faster)
|
||||
* `digitalReadFast(pinNum)`(reads the state of pin/port faster)
|
||||
|
||||
Parameters:
|
||||
* `pinNum` is the number written on the Arduino board.
|
||||
* `state` is weather pin is to be set `HIGH` or `LOW`
|
||||
* `mode` is weather pin is to be set `INPUT` or `OUTPUT`
|
||||
|
||||
In order to toggle fast, all the three parameters above must be constant or defined by the macro for ease in changes during compilation.
|
||||
|
||||
For example:
|
||||
* use '#define pinNum 10' instead of `int pinNum = 10;`
|
||||
* use 'const int pinNum 10' instead of `int pinNum = 10;`
|
||||
|
||||
Setting the parameter as a variable would cause the macro to return an error during compilation.
|
||||
|
||||
This makes sure `digitalWriteFast` that produces faster toggling, and notifies the programmer the specific area where toggling is slow. Otherwise, use normal `digitalWrite`
|
||||
|
||||
This is opposed to the forked library form Watterott, where if a variable is used as the parameter, the macro would revert to use sold `digitalWrite`, and remain undetected.
|
||||
|
||||
|
||||
## Speed
|
||||
|
||||
The regular `digitalWrite()` in Arduino Uno core (16MHz) takes about **6280nS** while `digitalWriteFast()` port manipulation takes **125nS**.
|
||||
> More info in: [/NOTES/NOTES.md](/NOTES/NOTES.md)
|
||||
|
||||
This is a huge difference, especially or timing sensitive applications.
|
||||
|
||||
Direct port manipulation is troublesome where one has to refer to the pin assignment of the package and manipulate specific ports, instead of pin numbers on the Arduino board.
|
||||
|
||||
This library makes it easier by using `digitalWriteFast()` and the macro will replace it will the approritate port manipulation commands.
|
||||
|
||||
## Compatibility
|
||||
* Arduino Due
|
||||
* Arduino Zero
|
||||
* Arduino Mega
|
||||
* Arduino with ATmega644 or Atmega644P chip
|
||||
* Arduino Leonardo
|
||||
* Arduino Uno (I have only tested with uno)
|
||||
|
||||
If not in the list, the macro will revert back to `digitalWrite()`, `pinMode()` or `digitalRead()`
|
||||
|
||||
## Installation
|
||||
1. Download the repo as zip, extract and place into Arduino IDE libraries folder.
|
||||
2. Rename "digitalWriteFast-master" to "digitalWriteFast" Arduino IDE does not accept dash character.
|
||||
|
||||
|
||||
## Reference
|
||||
Fork of Watterott's https://github.com/watterott/Arduino-Libs/tree/master/digitalWriteFast
|
||||
I just forked the whole repo, and delete unrelated files, I tried sparse checkout and gave up.
|
||||
|
||||
Watterott's digitalWriteFast could have used the below links as referrence.
|
||||
* https://code.google.com/archive/p/digitalwritefast/downloads
|
||||
* http://forum.arduino.cc/index.php?topic=46896.0
|
353
libraries/digitalWriteFast/digitalWriteFast.h
Executable file
353
libraries/digitalWriteFast/digitalWriteFast.h
Executable file
@ -0,0 +1,353 @@
|
||||
/*
|
||||
Optimized digital functions for AVR microcontrollers
|
||||
by Watterott electronic (www.watterott.com)
|
||||
based on http://code.google.com/p/digitalwritefast
|
||||
*/
|
||||
|
||||
#ifndef __digitalWriteFast_h_
|
||||
#define __digitalWriteFast_h_ 1
|
||||
|
||||
#define ERROR_SEQUENCE 0b10101010 //digitalReadFast will return this value if pin number is not constant
|
||||
// general macros/defines
|
||||
#ifndef BIT_READ
|
||||
# define BIT_READ(value, bit) ((value) & (1UL << (bit)))
|
||||
#endif
|
||||
#ifndef BIT_SET
|
||||
# define BIT_SET(value, bit) ((value) |= (1UL << (bit)))
|
||||
#endif
|
||||
#ifndef BIT_CLEAR
|
||||
# define BIT_CLEAR(value, bit) ((value) &= ~(1UL << (bit)))
|
||||
#endif
|
||||
#ifndef BIT_WRITE
|
||||
# define BIT_WRITE(value, bit, bitvalue) (bitvalue ? BIT_SET(value, bit) : BIT_CLEAR(value, bit))
|
||||
#endif
|
||||
|
||||
#ifndef SWAP
|
||||
#define SWAP(x,y) do{ (x)=(x)^(y); (y)=(x)^(y); (x)=(x)^(y); }while(0)
|
||||
#endif
|
||||
|
||||
/* //not needed, rather it produces annoying warnings when compiled
|
||||
#ifndef DEC
|
||||
# define DEC (10)
|
||||
#endif
|
||||
#ifndef HEX
|
||||
# define HEX (16)
|
||||
#endif
|
||||
#ifndef OCT
|
||||
# define OCT (8)
|
||||
#endif
|
||||
#ifndef BIN
|
||||
# define BIN (2)
|
||||
#endif
|
||||
*/
|
||||
|
||||
// workarounds for ARM microcontrollers
|
||||
#if (!defined(__AVR__) || defined(ARDUINO_ARCH_SAM))
|
||||
#ifndef PROGMEM
|
||||
# define PROGMEM
|
||||
#endif
|
||||
#ifndef PGM_P
|
||||
# define PGM_P const char *
|
||||
#endif
|
||||
#ifndef PSTR
|
||||
# define PSTR(str) (str)
|
||||
#endif
|
||||
|
||||
#ifndef memcpy_P
|
||||
# define memcpy_P(dest, src, num) memcpy((dest), (src), (num))
|
||||
#endif
|
||||
#ifndef strcpy_P
|
||||
# define strcpy_P(dst, src) strcpy((dst), (src))
|
||||
#endif
|
||||
#ifndef strcat_P
|
||||
# define strcat_P(dst, src) strcat((dst), (src))
|
||||
#endif
|
||||
#ifndef strcmp_P
|
||||
# define strcmp_P(a, b) strcmp((a), (b))
|
||||
#endif
|
||||
#ifndef strcasecmp_P
|
||||
# define strcasecmp_P(a, b) strcasecmp((a), (b))
|
||||
#endif
|
||||
#ifndef strncmp_P
|
||||
# define strncmp_P(a, b, n) strncmp((a), (b), (n))
|
||||
#endif
|
||||
#ifndef strncasecmp_P
|
||||
# define strncasecmp_P(a, b, n) strncasecmp((a), (b), (n))
|
||||
#endif
|
||||
#ifndef strstr_P
|
||||
# define strstr_P(a, b) strstr((a), (b))
|
||||
#endif
|
||||
#ifndef strlen_P
|
||||
# define strlen_P(a) strlen((a))
|
||||
#endif
|
||||
#ifndef sprintf_P
|
||||
# define sprintf_P(s, f, ...) sprintf((s), (f), __VA_ARGS__)
|
||||
#endif
|
||||
|
||||
#ifndef pgm_read_byte
|
||||
# define pgm_read_byte(addr) (*(const unsigned char *)(addr))
|
||||
#endif
|
||||
#ifndef pgm_read_word
|
||||
# define pgm_read_word(addr) (*(const unsigned short *)(addr))
|
||||
#endif
|
||||
#ifndef pgm_read_dword
|
||||
# define pgm_read_dword(addr) (*(const unsigned long *)(addr))
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
// digital functions
|
||||
//#ifndef digitalPinToPortReg
|
||||
#define SPI_SW_SS_PIN (10) //SS on Uno (for software SPI)
|
||||
#define SPI_SW_MOSI_PIN (11) //MOSI on Uno (for software SPI)
|
||||
#define SPI_SW_MISO_PIN (12) //MISO on Uno (for software SPI)
|
||||
#define SPI_SW_SCK_PIN (13) //SCK on Uno (for software SPI)
|
||||
|
||||
|
||||
// --- Arduino Due ---
|
||||
#if (defined(ARDUINO_SAM_DUE) || defined(__SAM3X8E__))
|
||||
|
||||
#define UART_RX_PIN (0)
|
||||
#define UART_TX_PIN (1)
|
||||
|
||||
#define I2C_SDA_PIN (20)
|
||||
#define I2C_SCL_PIN (21)
|
||||
|
||||
#define SPI_HW_SS_PIN (78) //SS0:77, SS1:87, SS2:86, SS3:78
|
||||
#define SPI_HW_MOSI_PIN (75) //75
|
||||
#define SPI_HW_MISO_PIN (74) //74
|
||||
#define SPI_HW_SCK_PIN (76) //76
|
||||
|
||||
|
||||
// --- Arduino Zero ---
|
||||
#elif (defined(ARDUINO_SAM_ZERO) || defined(__SAMD21G18A__))
|
||||
|
||||
#define UART_RX_PIN (0)
|
||||
#define UART_TX_PIN (1)
|
||||
|
||||
#define I2C_SDA_PIN (16)
|
||||
#define I2C_SCL_PIN (17)
|
||||
|
||||
#define SPI_HW_SS_PIN (14) //14
|
||||
#define SPI_HW_MOSI_PIN (21) //21
|
||||
#define SPI_HW_MISO_PIN (18) //18
|
||||
#define SPI_HW_SCK_PIN (20) //20
|
||||
|
||||
|
||||
// --- Arduino Mega ---
|
||||
#elif (defined(ARDUINO_AVR_MEGA) || \
|
||||
defined(ARDUINO_AVR_MEGA1280) || \
|
||||
defined(ARDUINO_AVR_MEGA2560) || \
|
||||
defined(__AVR_ATmega1280__) || \
|
||||
defined(__AVR_ATmega1281__) || \
|
||||
defined(__AVR_ATmega2560__) || \
|
||||
defined(__AVR_ATmega2561__))
|
||||
|
||||
#define UART_RX_PIN (0) //PE0
|
||||
#define UART_TX_PIN (1) //PE1
|
||||
|
||||
#define I2C_SDA_PIN (20)
|
||||
#define I2C_SCL_PIN (21)
|
||||
|
||||
#define SPI_HW_SS_PIN (53) //PB0
|
||||
#define SPI_HW_MOSI_PIN (51) //PB2
|
||||
#define SPI_HW_MISO_PIN (50) //PB3
|
||||
#define SPI_HW_SCK_PIN (52) //PB1
|
||||
|
||||
#define __digitalPinToPortReg(P) \
|
||||
(((P) >= 22 && (P) <= 29) ? &PORTA : \
|
||||
((((P) >= 10 && (P) <= 13) || ((P) >= 50 && (P) <= 53)) ? &PORTB : \
|
||||
(((P) >= 30 && (P) <= 37) ? &PORTC : \
|
||||
((((P) >= 18 && (P) <= 21) || (P) == 38) ? &PORTD : \
|
||||
((((P) >= 0 && (P) <= 3) || (P) == 5) ? &PORTE : \
|
||||
(((P) >= 54 && (P) <= 61) ? &PORTF : \
|
||||
((((P) >= 39 && (P) <= 41) || (P) == 4) ? &PORTG : \
|
||||
((((P) >= 6 && (P) <= 9) || (P) == 16 || (P) == 17) ? &PORTH : \
|
||||
(((P) == 14 || (P) == 15) ? &PORTJ : \
|
||||
(((P) >= 62 && (P) <= 69) ? &PORTK : &PORTL))))))))))
|
||||
|
||||
#define __digitalPinToDDRReg(P) \
|
||||
(((P) >= 22 && (P) <= 29) ? &DDRA : \
|
||||
((((P) >= 10 && (P) <= 13) || ((P) >= 50 && (P) <= 53)) ? &DDRB : \
|
||||
(((P) >= 30 && (P) <= 37) ? &DDRC : \
|
||||
((((P) >= 18 && (P) <= 21) || (P) == 38) ? &DDRD : \
|
||||
((((P) >= 0 && (P) <= 3) || (P) == 5) ? &DDRE : \
|
||||
(((P) >= 54 && (P) <= 61) ? &DDRF : \
|
||||
((((P) >= 39 && (P) <= 41) || (P) == 4) ? &DDRG : \
|
||||
((((P) >= 6 && (P) <= 9) || (P) == 16 || (P) == 17) ? &DDRH : \
|
||||
(((P) == 14 || (P) == 15) ? &DDRJ : \
|
||||
(((P) >= 62 && (P) <= 69) ? &DDRK : &DDRL))))))))))
|
||||
|
||||
#define __digitalPinToPINReg(P) \
|
||||
(((P) >= 22 && (P) <= 29) ? &PINA : \
|
||||
((((P) >= 10 && (P) <= 13) || ((P) >= 50 && (P) <= 53)) ? &PINB : \
|
||||
(((P) >= 30 && (P) <= 37) ? &PINC : \
|
||||
((((P) >= 18 && (P) <= 21) || (P) == 38) ? &PIND : \
|
||||
((((P) >= 0 && (P) <= 3) || (P) == 5) ? &PINE : \
|
||||
(((P) >= 54 && (P) <= 61) ? &PINF : \
|
||||
((((P) >= 39 && (P) <= 41) || (P) == 4) ? &PING : \
|
||||
((((P) >= 6 && (P) <= 9) || (P) == 16 || (P) == 17) ? &PINH : \
|
||||
(((P) == 14 || (P) == 15) ? &PINJ : \
|
||||
(((P) >= 62 && (P) <= 69) ? &PINK : &PINL))))))))))
|
||||
|
||||
#define __digitalPinToBit(P) \
|
||||
(((P) >= 7 && (P) <= 9) ? (P) - 3 : \
|
||||
(((P) >= 10 && (P) <= 13) ? (P) - 6 : \
|
||||
(((P) >= 22 && (P) <= 29) ? (P) - 22 : \
|
||||
(((P) >= 30 && (P) <= 37) ? 37 - (P) : \
|
||||
(((P) >= 39 && (P) <= 41) ? 41 - (P) : \
|
||||
(((P) >= 42 && (P) <= 49) ? 49 - (P) : \
|
||||
(((P) >= 50 && (P) <= 53) ? 53 - (P) : \
|
||||
(((P) >= 54 && (P) <= 61) ? (P) - 54 : \
|
||||
(((P) >= 62 && (P) <= 69) ? (P) - 62 : \
|
||||
(((P) == 0 || (P) == 15 || (P) == 17 || (P) == 21) ? 0 : \
|
||||
(((P) == 1 || (P) == 14 || (P) == 16 || (P) == 20) ? 1 : \
|
||||
(((P) == 19) ? 2 : \
|
||||
(((P) == 5 || (P) == 6 || (P) == 18) ? 3 : \
|
||||
(((P) == 2) ? 4 : \
|
||||
(((P) == 3 || (P) == 4) ? 5 : 7)))))))))))))))
|
||||
|
||||
|
||||
// --- Arduino 644 ---
|
||||
#elif (defined(__AVR_ATmega644__) || \
|
||||
defined(__AVR_ATmega644P__))
|
||||
|
||||
#define UART_RX_PIN (8) //PD0
|
||||
#define UART_TX_PIN (9) //PD1
|
||||
|
||||
#define I2C_SDA_PIN (17) //PC1
|
||||
#define I2C_SCL_PIN (16) //PC0
|
||||
|
||||
#define SPI_HW_SS_PIN (4) //PB4
|
||||
#define SPI_HW_MOSI_PIN (5) //PB5
|
||||
#define SPI_HW_MISO_PIN (6) //PB6
|
||||
#define SPI_HW_SCK_PIN (7) //PB7
|
||||
|
||||
#define __digitalPinToPortReg(P) \
|
||||
(((P) >= 0 && (P) <= 7) ? &PORTB : (((P) >= 8 && (P) <= 15) ? &PORTD : (((P) >= 16 && (P) <= 23) ? &PORTC : &PORTA)))
|
||||
#define __digitalPinToDDRReg(P) \
|
||||
(((P) >= 0 && (P) <= 7) ? &DDRB : (((P) >= 8 && (P) <= 15) ? &DDRD : (((P) >= 8 && (P) <= 15) ? &DDRC : &DDRA)))
|
||||
#define __digitalPinToPINReg(P) \
|
||||
(((P) >= 0 && (P) <= 7) ? &PINB : (((P) >= 8 && (P) <= 15) ? &PIND : (((P) >= 8 && (P) <= 15) ? &PINC : &PINA)))
|
||||
#define __digitalPinToBit(P) \
|
||||
(((P) >= 0 && (P) <= 7) ? (P) : (((P) >= 8 && (P) <= 15) ? (P) - 8 : (((P) >= 16 && (P) <= 23) ? (P) - 16 : (P) - 24)))
|
||||
|
||||
|
||||
// --- Arduino Leonardo ---
|
||||
#elif (defined(ARDUINO_AVR_LEONARDO) || \
|
||||
defined(__AVR_ATmega16U4__) || \
|
||||
defined(__AVR_ATmega32U4__))
|
||||
|
||||
#define UART_RX_PIN (0) //PD2
|
||||
#define UART_TX_PIN (1) //PD3
|
||||
|
||||
#define I2C_SDA_PIN (2) //PD1
|
||||
#define I2C_SCL_PIN (3) //PD0
|
||||
|
||||
#define SPI_HW_SS_PIN (17) //PB0
|
||||
#define SPI_HW_MOSI_PIN (16) //PB2
|
||||
#define SPI_HW_MISO_PIN (14) //PB3
|
||||
#define SPI_HW_SCK_PIN (15) //PB1
|
||||
|
||||
#define __digitalPinToPortReg(P) \
|
||||
((((P) >= 0 && (P) <= 4) || (P) == 6 || (P) == 12 || (P) == 24 || (P) == 25 || (P) == 29) ? &PORTD : (((P) == 5 || (P) == 13) ? &PORTC : (((P) >= 18 && (P) <= 23)) ? &PORTF : (((P) == 7) ? &PORTE : &PORTB)))
|
||||
#define __digitalPinToDDRReg(P) \
|
||||
((((P) >= 0 && (P) <= 4) || (P) == 6 || (P) == 12 || (P) == 24 || (P) == 25 || (P) == 29) ? &DDRD : (((P) == 5 || (P) == 13) ? &DDRC : (((P) >= 18 && (P) <= 23)) ? &DDRF : (((P) == 7) ? &DDRE : &DDRB)))
|
||||
#define __digitalPinToPINReg(P) \
|
||||
((((P) >= 0 && (P) <= 4) || (P) == 6 || (P) == 12 || (P) == 24 || (P) == 25 || (P) == 29) ? &PIND : (((P) == 5 || (P) == 13) ? &PINC : (((P) >= 18 && (P) <= 23)) ? &PINF : (((P) == 7) ? &PINE : &PINB)))
|
||||
#define __digitalPinToBit(P) \
|
||||
(((P) >= 8 && (P) <= 11) ? (P) - 4 : (((P) >= 18 && (P) <= 21) ? 25 - (P) : (((P) == 0) ? 2 : (((P) == 1) ? 3 : (((P) == 2) ? 1 : (((P) == 3) ? 0 : (((P) == 4) ? 4 : (((P) == 6) ? 7 : (((P) == 13) ? 7 : (((P) == 14) ? 3 : (((P) == 15) ? 1 : (((P) == 16) ? 2 : (((P) == 17) ? 0 : (((P) == 22) ? 1 : (((P) == 23) ? 0 : (((P) == 24) ? 4 : (((P) == 25) ? 7 : (((P) == 26) ? 4 : (((P) == 27) ? 5 : 6 )))))))))))))))))))
|
||||
|
||||
|
||||
// --- Arduino Uno ---
|
||||
#elif (defined(ARDUINO_AVR_UNO) || \
|
||||
defined(ARDUINO_AVR_DUEMILANOVE) || \
|
||||
defined(ARDUINO_ARCH_AVR) || \
|
||||
defined(__AVR_ATmega328__) || \
|
||||
defined(__AVR_ATmega328P__) || \
|
||||
defined(__AVR__))
|
||||
|
||||
#define UART_RX_PIN (0) //PD0
|
||||
#define UART_TX_PIN (1) //PD1
|
||||
|
||||
#define I2C_SDA_PIN (18) //A4
|
||||
#define I2C_SCL_PIN (19) //A5
|
||||
|
||||
#define SPI_HW_SS_PIN (10) //PB0
|
||||
#define SPI_HW_MOSI_PIN (11) //PB2
|
||||
#define SPI_HW_MISO_PIN (12) //PB3
|
||||
#define SPI_HW_SCK_PIN (13) //PB1
|
||||
|
||||
#define __digitalPinToPortReg(P) \
|
||||
(((P) >= 0 && (P) <= 7) ? &PORTD : (((P) >= 8 && (P) <= 13) ? &PORTB : &PORTC))
|
||||
#define __digitalPinToDDRReg(P) \
|
||||
(((P) >= 0 && (P) <= 7) ? &DDRD : (((P) >= 8 && (P) <= 13) ? &DDRB : &DDRC))
|
||||
#define __digitalPinToPINReg(P) \
|
||||
(((P) >= 0 && (P) <= 7) ? &PIND : (((P) >= 8 && (P) <= 13) ? &PINB : &PINC))
|
||||
#define __digitalPinToBit(P) \
|
||||
(((P) >= 0 && (P) <= 7) ? (P) : (((P) >= 8 && (P) <= 13) ? (P) - 8 : (P) - 14))
|
||||
|
||||
|
||||
// --- Other ---
|
||||
#else
|
||||
|
||||
#define SPI_HW_SS_PIN SS
|
||||
#define SPI_HW_MOSI_PIN MOSI
|
||||
#define SPI_HW_MISO_PIN MISO
|
||||
#define SPI_HW_SCK_PIN SCK
|
||||
|
||||
|
||||
#endif
|
||||
//#endif //#ifndef digitalPinToPortReg
|
||||
|
||||
|
||||
//ref: http://forum.arduino.cc/index.php?topic=140409.msg1054868#msg1054868
|
||||
//void OutputsErrorIfCalled( void ) __attribute__ (( error( "Line: "__line__ "Variable used for digitalWriteFast") ));
|
||||
void NonConstantUsed( void ) __attribute__ (( error("") ));
|
||||
|
||||
|
||||
#ifndef digitalWriteFast
|
||||
#if (defined(__AVR__) || defined(ARDUINO_ARCH_AVR))
|
||||
#define digitalWriteFast(P, V) \
|
||||
if (__builtin_constant_p(P) && __builtin_constant_p(V)) { \
|
||||
BIT_WRITE(*__digitalPinToPortReg(P), __digitalPinToBit(P), (V)); \
|
||||
} else { \
|
||||
NonConstantUsed(); \
|
||||
}
|
||||
#else
|
||||
//#define digitalWriteFast digitalWrite
|
||||
#error Non-AVR device, unsupported.
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
#ifndef pinModeFast
|
||||
#if (defined(__AVR__) || defined(ARDUINO_ARCH_AVR))
|
||||
#define pinModeFast(P, V) \
|
||||
if (__builtin_constant_p(P) && __builtin_constant_p(V)) { \
|
||||
BIT_WRITE(*__digitalPinToDDRReg(P), __digitalPinToBit(P), (V)); \
|
||||
} else { \
|
||||
NonConstantUsed(); \
|
||||
}
|
||||
#else
|
||||
//#define pinModeFast pinMode
|
||||
#error Non-AVR device, unsupported.
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
#ifndef digitalReadFast
|
||||
#if (defined(__AVR__) || defined(ARDUINO_ARCH_AVR))
|
||||
#define digitalReadFast(P) ( (byte) __digitalReadFast((P)) )
|
||||
#define __digitalReadFast(P ) \
|
||||
(__builtin_constant_p(P) ) ? ( \
|
||||
( BIT_READ(*__digitalPinToPINReg(P), __digitalPinToBit(P))) ) : \
|
||||
ERROR_SEQUENCE
|
||||
#else
|
||||
//#define digitalReadFast digitalRead
|
||||
#error Non-AVR device, unsupported.
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#endif //__digitalWriteFast_h_
|
Loading…
Reference in New Issue
Block a user