#include <LiquidCrystal_I2C.h> // Подключаем библиотеку LiquidCrystal для работы с ЖК-дисплеем
#include "GyverTimer.h" // библиотека для назначение таймеров
#include <SimpleKeypad.h>
#include <EEPROM.h>
#include <GyverWDT.h>
//выходы на реле
#define RIGHT 14 // включение мотора для поворота вправо
#define LEFT 15 // включение мотора для поворота влево
#define UP 16 // включение мотора для поворота вверх
#define DOWN 17 // включение мотора для поворота вниз
#define LED 13 // светодиод
#define KP_ROWS 5 // количество строчек в клавиатуре
#define KP_COLS 4 // количество столбцов
#define ANGLE_UP 1 //датчик предельного верхнего положения
#define ANGLE_DOWN 0 // датчик предельного нижнего положения
#define AZ_ZERO 11 // датчик выставления на нуль азимута
#define AN_ZERO 12 // датчик выставления на нуль угла
LiquidCrystal_I2C lcd(0x27, 20, 4); // инициализация жк дисплея с переходником l2c помогает уменьшить количество проводов
//// Если надпись не появилась, замените адрес 0x27 на 0x3F
byte up_arrow[] = {
B00000,
B00100,
B01110,
B10101,
B00100,
B00100,
B00100,
B00000
};
byte down_arrow[] = {
B00000,
B00100,
B00100,
B00100,
B10101,
B01110,
B00100,
B00000
};
byte one[] = {
B00000,
B11111,
B00100,
B00100,
B00100,
B00100,
B11111,
B00000
};
byte two[] = {
B00000,
B11111,
B01010,
B01010,
B01010,
B01010,
B11111,
B00000
};
byte three[] = {
B11111,
B00010,
B00100,
B01000,
B11111,
B00010,
B00100,
B01000
};
byte four[] = {
B00000,
B00000,
B10101,
B10101,
B10101,
B10010,
B00000,
B00000
};
// ТЕКУЩИЕ значения азимута и угла места
float azimuth = 0; // значение азимута только в градусах для корректной работы поворота
float elevation_angle = 0; // значение угла места в градусах например 34,37 градусов
int x_degrees = 0; // значение азиута восле преобразования в градусы минуты и секунды
int x_minutes = 0;
int x_second = 0;
int y_degrees = 0; // значение угла места восле преобразования в градусы минуты и секунды
int y_minutes = 0;
int y_second = 0;
// значения УСТАНОВКИ которые пишутся оператором или берутся из памяти
float set_azimuth = 0;
float set_elevation_angle = 0;
int set_x_degrees = 0; // значение азиута восле преобразования в градусы минуты и секунды
int set_x_minutes = 0;
int set_x_second = 0;
int set_y_degrees = 0; // значение угла места восле преобразования в градусы минуты и секунды
int set_y_minutes = 0;
int set_y_second = 0;
// значения координат сохранённых в ПЗУ
float azimuth_1 = 0; //
float elevation_angle_1 = 0;
float azimuth_2 = 0; //
float elevation_angle_2 = 0;
float azimuth_3 = 0; //
float elevation_angle_3 = 0;
float azimuth_4 = 0; //
float elevation_angle_4 = 0;
// значения ПАМЯТИ которые получаются в результате преобразования значений сохранённых в пзу
int mem_x_degrees = 0; // значение азиута восле преобразования в градусы минуты и секунды
int mem_x_minutes = 0;
int mem_x_second = 0;
int mem_y_degrees = 0; // значение угла места восле преобразования в градусы минуты и секунды
int mem_y_minutes = 0;
int mem_y_second = 0;
int i = 0; // значение ячейки памяти
// переменные для работы с клавиатурой
String strinput = ""; // для преобразования значения клавиш в строку
int rcv = 0; // индикатор нажатия кнопки
// описание переменных для цикла колибровки
int quest_start = 0; // вопрос о начале колибровки
int u = 0; // для показывания красивых точечек
int calibration_azimuth = 0; // начало цикла колибровки азимута
int calibration_angle = 0; // начало цикла колибровки угла места
int zero_check = 0; // прохождение контрольных точек во время колибровки
float min_angle = 0; // минимальное значение угла места
float max_angle = 0; // максимальное значение угла места
int set_min_max = 0; // цикл установки мин и макс значений угла места
int change = 0; // при нажатии ент будет переход к вводу другого значение
// опитсание переменных для режима установки
int set_mode = 0; // цикл для установки значений
int cur = 0; // для мигания курсора
int number = 0; // входное число которое записали
int input_number = 0; // входная цифра
int unit = 0; // номер числа их всего 6: 0- x_degrees 1 - x_minutes 2 - x_second 3 - y_degrees 4 - y_minutes 5 - y_second
int minus = 0; // символ минус пришел
int in_num = 0; // счетчик принятых символов (порядковый номер цифры в числе)
// описание переменных для вращения
float timer_up = 0; // таймер подьема
float timer_down = 0; // таймер опускания
float timer_right = 0; // таймер вращ вправо
float timer_left = 0; // таймер вращ влево
float angle_move = 0; // считает кол-во милисекунд вращения угла места
float k_angle_up = 0; // коэф перевода из милисекунд в градусы
float k_angle_down = 0; // коэф перевода из милисекунд в градусы
float azimuth_move = 0; // считает кол-во милисекунд вращения азимута
float k_azimuth_right = 0; // коэф перевода из милисекунд в градусы
float k_azimuth_left = 0; // коэф перевода из милисекунд в градусы
int led_blink = 0; // для мигания светодиодом на плате
int moving_mode = 0; // запуск цила для перехода к значениям установки
int start = 0; // для определения происходящих действий в цикле движения
// описание таймеров
GTimer TimerBUT(MS); // таймер для кнопок замена функции delay
GTimer Timer500(MS); // таймер для красоты
GTimer TimerLED(MS); // таймер для мигания лампочки при установки одного из датчиков в 0
GTimer TimerMOV(MS); // время поворота в режиме движения
// клавиатура
// пины подключения (по порядку штекера)
byte colPins[KP_COLS] = {5, 4, 3, 2};
byte rowPins[KP_ROWS] = {10, 9, 8, 7, 6};
// массив имён кнопок
char keys[KP_ROWS][KP_COLS] = {
{'A', 'B', 'C', 'D'},
{'1', '2', '3', '^'},
{'4', '5', '6', '!'},
{'7', '8', '9', 'O'},
{'<', '0', '>', 'E'}
};
// создаём клавиатуру
SimpleKeypad pad((char*)keys, rowPins, colPins, KP_ROWS, KP_COLS);
void display() // функция отображения значений на экране
{
lcd.clear();
// первая строка текущее положение
lcd.setCursor(0,0);
lcd.print("X");
lcd.print(x_degrees);
lcd.print(char(223));
lcd.print(abs(x_minutes));
lcd.print("'");
lcd.print(abs(x_second));
lcd.setCursor(10,0);
lcd.print("Y");
lcd.print(y_degrees);
lcd.print(char(223));
lcd.print(abs(y_minutes));
lcd.print("'");
lcd.print(abs(y_second));
// вторая строка пустая для удобства
// третья строка установленные значения
lcd.setCursor(0,2);
lcd.print("X");
lcd.print(set_x_degrees);
lcd.print(char(223));
lcd.print(set_x_minutes);
lcd.print("'");
lcd.print(set_x_second);
lcd.setCursor(10,2);
lcd.print("Y");
lcd.print(set_y_degrees);
lcd.print(char(223));
lcd.print(abs(set_y_minutes));
lcd.print("'");
lcd.print(abs(set_y_second));
// четвертая строка
lcd.setCursor(0,3);
if (i == 1) lcd.write(2);
else if (i == 2) lcd.write(3);
else if (i == 3) lcd.write(4);
else if (i == 4) lcd.write(5);
lcd.print(mem_x_degrees);
lcd.print(char(223));
lcd.print(mem_x_minutes);
lcd.print("'");
lcd.print(mem_x_second);
lcd.setCursor(10,3);
lcd.print(" ");
lcd.print(mem_y_degrees);
lcd.print(char(223));
lcd.print(abs(mem_y_minutes));
lcd.print("'");
lcd.print(abs(mem_y_second));
}
void from_degrees(float deg_in, int& deg_out, int& min_out, int& sec_out) // функция разбиения градусов на градусы минуты и секунды
{
deg_out = int(deg_in);
min_out = int((deg_in - deg_out) * 60);
sec_out = int((((deg_in - deg_out) * 60) - min_out) * 60);
}
void to_degrees(int deg_in, int min_in, int sec_in, float& deg_out) // функция соединени градусов минут и секунд в градусы с запятой
{
deg_out = deg_in + (float(min_in) / 60) + (float(sec_in) / 3600);
}
void set_cursor(int uni, int num) // функция определения курсора в режиме установки значений в зависимости от того какой символ вводится перемещается курсор
{
if (minus == 0) // если не пришёл минус
{
lcd.setCursor(0,2);
lcd.print("X");
lcd.setCursor(4,2);
lcd.print(char(223));
lcd.setCursor(7,2);
lcd.print("'");
lcd.setCursor(10,2);
lcd.print("Y");
lcd.setCursor(13,2);
lcd.print(char(223));
lcd.setCursor(16,2);
lcd.print("'");
if ((uni == 0) && (num == 1)) lcd.setCursor(2,2);
else if ((uni == 0) && (num == 2)) lcd.setCursor(3,2);
else if ((uni == 1) && (num == 0)) lcd.setCursor(5,2);
else if ((uni == 1) && (num == 1)) lcd.setCursor(6,2);
else if ((uni == 2) && (num == 0)) lcd.setCursor(8,2);
else if ((uni == 2) && (num == 1)) lcd.setCursor(9,2);
else if ((uni == 3) && (num == 0)) lcd.setCursor(11,2);
else if ((uni == 3) && (num == 1)) lcd.setCursor(12,2);
else if ((uni == 4) && (num == 0)) lcd.setCursor(14,2);
else if ((uni == 4) && (num == 1)) lcd.setCursor(15,2);
else if ((uni == 5) && (num == 0)) lcd.setCursor(17,2);
else if ((uni == 5) && (num == 1)) lcd.setCursor(18,2);
}
else // если минус не пришёл
{
lcd.setCursor(0,2);
lcd.print("X");
lcd.setCursor(4,2);
lcd.print(char(223));
lcd.setCursor(7,2);
lcd.print("'");
lcd.setCursor(10,2);
lcd.print("Y");
lcd.setCursor(14,2);
lcd.print(char(223));
lcd.setCursor(17,2);
lcd.print("'");
if ((uni == 0) && (num == 1)) lcd.setCursor(2,2);
else if ((uni == 0) && (num == 2)) lcd.setCursor(3,2);
else if ((uni == 1) && (num == 0)) lcd.setCursor(5,2);
else if ((uni == 1) && (num == 1)) lcd.setCursor(6,2);
else if ((uni == 2) && (num == 0)) lcd.setCursor(8,2);
else if ((uni == 2) && (num == 1)) lcd.setCursor(9,2);
else if ((uni == 3) && (num == 1)) lcd.setCursor(13,2);
else if ((uni == 4) && (num == 0)) lcd.setCursor(15,2);
else if ((uni == 4) && (num == 1)) lcd.setCursor(16,2);
else if ((uni == 5) && (num == 0)) lcd.setCursor(18,2);
else if ((uni == 5) && (num == 1)) lcd.setCursor(19,2);
}
}
void enumerate_numbers(int& next_unit_f, int& in_num_f, int val, int& number_f) // функция подсчета принятых символов и образования чисел
{
if ((in_num_f == 0) && (next_unit_f == 0)) // если трехзначное число
{
number_f = 100 * val;
}
else if (((in_num_f == 1) && (next_unit_f == 0)) || (in_num_f == 0)) // вторая цифра в 3х значном или первая в двухзначном
{
number_f += 10 * val;
}
else // если 2 или 3 цифра пришла
{
number_f += val; // записываем полученную цифру
}
if (next_unit_f == 0) // если 3 х значное число
{
if (in_num_f == 2) // пришел 3й символ
{
set_x_degrees = number_f; // 3 символа только у азимута градусы
number_f = 0; // обнуляем число приняли
in_num_f = 0;
next_unit_f += 1; // пришел последний символ переход на новое место
}
else
{
in_num_f += 1; // пришел первый или второй символ
}
}
else // если 2х значное число
{
if (in_num_f == 1) // пришел 2й символ
{// записываем после приема символов в установку
if (next_unit_f == 1) set_x_minutes = number_f;
else if (next_unit_f == 2) set_x_second = number_f;
else if (next_unit_f == 3) set_y_degrees = number_f;
else if (next_unit_f == 4) set_y_minutes = number_f;
else if (next_unit_f == 5) set_y_second = number_f;
number_f = 0; // обнуляем число приняли
in_num_f = 0;
next_unit_f += 1; // пришел последний символ переход на новое место
}
else
{
in_num_f += 1; // пришел первый символ
}
}
}
void action(String phrase) // функция для движения моторов и подсчета времени работы
{
if (phrase == "UP")
{
digitalWrite(UP, LOW);
timer_up = millis();
lcd.setCursor(18,1);
lcd.write(0);
}
else if (phrase == "LEFT")
{
digitalWrite(LEFT, LOW);
timer_left = millis();
lcd.setCursor(17,1);
lcd.print(char(127));
}
else if (phrase == "RIGHT")
{
digitalWrite(RIGHT, LOW);
timer_right = millis();
lcd.setCursor(19,1);
lcd.print(char(126));
}
else if (phrase == "DOWN")
{
digitalWrite(DOWN, LOW);
timer_down = millis();
lcd.setCursor(18,1);
lcd.write(1);
}
else if (phrase == "STOP")
{
digitalWrite(UP, HIGH);// отключаем все привода
digitalWrite(DOWN, HIGH);
digitalWrite(RIGHT, HIGH);
digitalWrite(LEFT, HIGH);
lcd.setCursor(17,1);
lcd.print(" ");
if (timer_up != 0)
{
angle_move = (millis() - timer_up); // фиксируем положение по вертикали
elevation_angle += ((angle_move / 1000) * k_angle_up);
}
else if (timer_down != 0)
{
angle_move = (millis() - timer_down);
elevation_angle -= ((angle_move / 1000) * k_angle_down);
}
timer_up = 0;
timer_down = 0;
if (timer_right != 0)
{
azimuth_move = (millis() - timer_right); // фиксируем положение по горизонтали
azimuth += ((azimuth_move / 1000) * k_azimuth_right);
}
else if (timer_left != 0)
{
azimuth_move = (millis() - timer_left);
azimuth -= ((azimuth_move / 1000) * k_azimuth_left);
}
timer_right = 0;
timer_left = 0;
}
}
void setup() {
// считываем данные из памяти
EEPROM.get(0,azimuth_1); //
EEPROM.get(4,elevation_angle_1);
EEPROM.get(8,azimuth_2); //
EEPROM.get(12,elevation_angle_2);
EEPROM.get(16,azimuth_3); //
EEPROM.get(20,elevation_angle_3);
EEPROM.get(24,azimuth_4); //
EEPROM.get(28,elevation_angle_4);
EEPROM.get(32,k_azimuth_right); //
EEPROM.get(36,k_azimuth_left);
EEPROM.get(40,k_angle_up); //
EEPROM.get(44,k_angle_down);
EEPROM.get(48,max_angle); //
EEPROM.get(52,min_angle);
// если данных нет пишем нуль или значение
if (isnan(azimuth_1)) azimuth_1 = 0;
if (isnan(elevation_angle_1)) elevation_angle_1 = 0;
if (isnan(azimuth_2)) azimuth_2 = 0;
if (isnan(elevation_angle_2)) elevation_angle_2 = 0;
if (isnan(azimuth_3)) azimuth_3 = 0;
if (isnan(elevation_angle_3)) elevation_angle_3 = 0;
if (isnan(azimuth_4)) azimuth_4 = 0;
if (isnan(elevation_angle_4)) elevation_angle_4 = 0;
if (isnan(k_azimuth_right)) k_azimuth_right = 1;
if (isnan(k_azimuth_left)) k_azimuth_left = 1;
if (isnan(k_angle_up)) k_angle_up = 1;
if (isnan(k_angle_down)) k_angle_down = 1;
if (isnan(max_angle)) max_angle = 45;
if (isnan(min_angle)) min_angle = -45;
Watchdog.enable(RESET_MODE, WDT_PRESCALER_1024); // Режим сторожевого сброса , таймаут ~8с
TimerBUT.setTimeout(350); // запуск в режиме однократного срабатывания
TimerBUT.stop(); // остановка таймера
TimerMOV.setTimeout(1000);
TimerMOV.stop();
Timer500.setInterval(500); // запуск в режиме заданного интервала
Timer500.stop();
TimerLED.setInterval(3000); // запуск в режиме заданного интервала
TimerLED.stop();
//Serial.begin(115200);
//delay(1000);
pinMode(RIGHT, OUTPUT); // устанавливает режим работы - выход
pinMode(LEFT, OUTPUT); // устанавливает режим работы - выход
pinMode(UP, OUTPUT); // устанавливает режим работы - выход
pinMode(DOWN, OUTPUT); // устанавливает режим работы - выход
pinMode(LED, OUTPUT); // устанавливает режим работы - выход
pinMode(ANGLE_UP, INPUT_PULLUP); // Устаовили тип пина входной для кнопки
pinMode(ANGLE_DOWN, INPUT_PULLUP);
pinMode(AZ_ZERO, INPUT_PULLUP);
pinMode(AN_ZERO, INPUT_PULLUP);
digitalWrite(RIGHT, HIGH); // изначально дом выключен приходится ставить HIGH т к реле срабатывает от низкого сигнала
digitalWrite(LEFT, HIGH); // изначально дом выключен приходится ставить HIGH т к реле срабатывает от низкого сигнала
digitalWrite(UP, HIGH);
digitalWrite(DOWN, HIGH);
digitalWrite(LED, HIGH);
digitalWrite(ANGLE_UP, HIGH);
digitalWrite(ANGLE_DOWN, HIGH);
digitalWrite(AZ_ZERO, HIGH);
digitalWrite(AN_ZERO, HIGH);
lcd.init();
lcd.backlight();
// создаем страшненькие символы и записываем их в память lcd
lcd.createChar(0, up_arrow);
lcd.createChar(1, down_arrow);
lcd.createChar(2, one);
lcd.createChar(3, two);
lcd.createChar(4, three);
lcd.createChar(5, four);
display();// показываем экран
}
void loop()
{
Watchdog.reset(); // сброс пса
// считываем данные с клавиатуры
char key = pad.scan();// непрерывное считывание данных с клавиатуры
if (key) // если кнопка нажата (не 0 символ)
{
strinput += key; // делаем переход на string
// если нажаты кнопки ручного управления
if ((strinput == "^") && (rcv == 0) && (digitalRead(ANGLE_UP) == HIGH) && (quest_start == 0)) //вверх
{
rcv = 1;
action("UP");
}
else if ((strinput == "<") && (rcv == 0) && (quest_start == 0)) // влево
{
rcv = 1;
action("LEFT");
}
else if ((strinput == ">") && (rcv == 0) && (quest_start == 0)) // вправо
{
rcv = 1;
action("RIGHT");
}
else if ((strinput == "!") && (rcv == 0) && (digitalRead(ANGLE_DOWN) == HIGH) && (quest_start == 0)) // вниз
{
rcv = 1;
action("DOWN");
}
else if ((strinput == "A") && (quest_start == 1) && (rcv == 0))// колибровка азимута
{
rcv = 1;
TimerBUT.start();
calibration_azimuth = 1;
quest_start = 0;
Timer500.start();
lcd.clear();
lcd.setCursor(0,2);
lcd.print("Colibration_azimuth");
lcd.setCursor(0,3);
lcd.print("Processing...:");
}
else if ((strinput == "A") && (quest_start == 0) && (rcv == 0) && (calibration_azimuth == 0))//выбор колибровки
{
rcv = 1;
TimerBUT.start();
lcd.clear();
lcd.setCursor(0,0);
lcd.print("Start_calibration?");
lcd.setCursor(0,1);
lcd.print("F1 to calib azimuth");
lcd.setCursor(0,2);
lcd.print("F2 to calib angle");
lcd.setCursor(0,3);
lcd.print("Press esc to exit");
quest_start = 1;
}
else if ((strinput == "B") && (quest_start == 1) && (rcv == 0))// колибровка угла
{
rcv = 1;
TimerBUT.start();
calibration_angle = 1;
quest_start = 0;
Timer500.start();
lcd.clear();
lcd.setCursor(0,2);
lcd.print("Colibration_angle");
lcd.setCursor(0,3);
lcd.print("Processing...:");
}
else if ((strinput == "B") && (quest_start == 0) && (rcv == 0))// чтение из памяти
{
rcv = 1;
TimerBUT.start();
set_x_degrees = mem_x_degrees;
set_x_minutes = mem_x_minutes;
set_x_second = mem_x_second;
set_y_degrees = mem_y_degrees;
set_y_minutes = mem_y_minutes;
set_y_second = mem_y_second;
display();
}
else if ((strinput == "C") && (rcv == 0) && (quest_start == 0))// выбор ячейки памяти
{
rcv = 1;
TimerBUT.start();
i += 1;
if ((i == 1) || (i == 5))
{
if (i == 5) i = 1;
from_degrees(azimuth_1, mem_x_degrees, mem_x_minutes, mem_x_second);
from_degrees(elevation_angle_1, mem_y_degrees, mem_y_minutes, mem_y_second);
lcd.setCursor(0,3);
lcd.print(" ");
lcd.setCursor(0,3);
lcd.write(2);
}
else if (i == 2)
{
from_degrees(azimuth_2, mem_x_degrees, mem_x_minutes, mem_x_second);
from_degrees(elevation_angle_2, mem_y_degrees, mem_y_minutes, mem_y_second);
lcd.setCursor(0,3);
lcd.print(" ");
lcd.setCursor(0,3);
lcd.write(3);
}
else if (i == 3)
{
from_degrees(azimuth_3, mem_x_degrees, mem_x_minutes, mem_x_second);
from_degrees(elevation_angle_3, mem_y_degrees, mem_y_minutes, mem_y_second);
lcd.setCursor(0,3);
lcd.print(" ");
lcd.setCursor(0,3);
lcd.write(4);
}
else if (i == 4)
{
from_degrees(azimuth_4, mem_x_degrees, mem_x_minutes, mem_x_second);
from_degrees(elevation_angle_4, mem_y_degrees, mem_y_minutes, mem_y_second);
lcd.setCursor(0,3);
lcd.print(" ");
lcd.setCursor(0,3);
lcd.write(5);
//i = 0;
}
lcd.print(mem_x_degrees);
lcd.print(char(223));
lcd.print(abs(mem_x_minutes));
lcd.print("'");
lcd.print(abs(mem_x_second));
lcd.setCursor(10,3);
lcd.print(" ");
lcd.print(mem_y_degrees);
lcd.print(char(223));
lcd.print(abs(mem_y_minutes));
lcd.print("'");
lcd.print(abs(mem_y_second));
}
else if ((strinput == "D") && (rcv == 0) && (quest_start == 0))// запись в память
{
rcv = 1;
TimerBUT.start();
mem_x_degrees = x_degrees;
mem_x_minutes = x_minutes;
mem_x_second = x_second;
mem_y_degrees = y_degrees;
mem_y_minutes = y_minutes;
mem_y_second = y_second;
if (i == 1)
{
to_degrees(mem_x_degrees, mem_x_minutes, mem_x_second, azimuth_1);
to_degrees(mem_y_degrees, mem_y_minutes, mem_y_second, elevation_angle_1);
EEPROM.put(0,azimuth_1); //
EEPROM.put(4,elevation_angle_1);
}
else if (i == 2)
{
to_degrees(mem_x_degrees, mem_x_minutes, mem_x_second, azimuth_2);
to_degrees(mem_y_degrees, mem_y_minutes, mem_y_second, elevation_angle_2);
EEPROM.put(8,azimuth_2); //
EEPROM.put(12,elevation_angle_2);
}
else if (i == 3)
{
to_degrees(mem_x_degrees, mem_x_minutes, mem_x_second, azimuth_3);
to_degrees(mem_y_degrees, mem_y_minutes, mem_y_second, elevation_angle_3);
EEPROM.put(16,azimuth_3); //
EEPROM.put(20,elevation_angle_3);
}
else if (i == 4)
{
to_degrees(mem_x_degrees, mem_x_minutes, mem_x_second, azimuth_4);
to_degrees(mem_y_degrees, mem_y_minutes, mem_y_second, elevation_angle_4);
EEPROM.put(24,azimuth_4); //
EEPROM.put(28,elevation_angle_4);
}
lcd.setCursor(0,1);
lcd.print("Writing memory...");
delay(3000);
display();
}
else if ((strinput == "O") && (rcv == 0) && (quest_start == 1)) // выход
{
rcv = 1;
TimerBUT.start();
quest_start = 0;
display();
}
else if ((strinput == "O") && (rcv == 0) && (quest_start == 0)) // переход в режим установки
{
rcv = 1;
TimerBUT.start();
display();
set_mode = 1;
lcd.setCursor(0,1);
lcd.print("Set_mode");
lcd.setCursor(0,2);
lcd.print(" ");
lcd.setCursor(0,2);
lcd.print("X");
lcd.setCursor(10,2);
lcd.print("Y");
lcd.setCursor(1,2);
Timer500.start();
}
else if ((strinput == "E") && (rcv == 0) && (quest_start == 0)) // переход в режим движения к установленным значениям
{
rcv = 1;
TimerBUT.start();
display();
moving_mode = 1;
lcd.setCursor(0,1);
lcd.print("Moving_mode");
}
else if ((strinput == "1") && (rcv == 0) && (quest_start == 0))// вывод подсказки
{
rcv = 1;
TimerBUT.start();
lcd.clear();
lcd.setCursor(0,0);
lcd.print("F1 calibration");
lcd.setCursor(0,1);
lcd.print("F2 read from memory");
lcd.setCursor(0,2);
lcd.print("# change memory");
lcd.setCursor(0,3);
lcd.print("* write to memory");
delay(6000);
Watchdog.reset(); // сброс пса
lcd.clear();
lcd.setCursor(0,0);
lcd.print("esc to set mode");
lcd.setCursor(0,1);
lcd.print("ent from set to move");
lcd.setCursor(0,2);
lcd.print("arrow to hand move");
lcd.setCursor(0,3);
lcd.print("2 to min,max set");
delay(6000);
display();
}
else if ((strinput == "2") && (rcv == 0) && (quest_start == 0)) // установка мин макса
{
rcv = 1;
TimerBUT.start();
lcd.clear();
set_min_max = 1;
lcd.setCursor(0,0);
lcd.print("set min,max angle");
lcd.setCursor(0,1);
lcd.print("use arrow,ent");
lcd.setCursor(0,2);
lcd.print("min angle:");
lcd.print(min_angle);
lcd.setCursor(0,3);
lcd.print("max angle:");
lcd.print(max_angle);
}
} //если кнопка не нажата то выключаем если было включено
else if ((digitalRead(RIGHT) == LOW) || (digitalRead(LEFT) == LOW) || (digitalRead(UP) == LOW) || (digitalRead(DOWN) == LOW)) // выключение двигателей в ручном режиме
{
rcv = 0;
action("STOP");
from_degrees(azimuth, x_degrees, x_minutes, x_second);
from_degrees(elevation_angle, y_degrees, y_minutes, y_second);
lcd.setCursor(0,0);
lcd.print(" ");
lcd.setCursor(0,0);
lcd.print("X");
lcd.print(x_degrees);
lcd.print(char(223));
lcd.print(abs(x_minutes));
lcd.print("'");
lcd.print(abs(x_second));
lcd.setCursor(10,0);
lcd.print("Y");
lcd.print(y_degrees);
lcd.print(char(223));
lcd.print(abs(y_minutes));
lcd.print("'");
lcd.print(abs(y_second));
//display();
}
strinput =""; // обнуляем переменную чтобы можно было потом ей вопользоваться
// если светодиод мигает - значит работает один из датчиков нуля если горит - значит оба работают
if ((digitalRead(AZ_ZERO) == LOW) && (digitalRead(AN_ZERO) == LOW)) digitalWrite(LED, HIGH);
else if (((digitalRead(AZ_ZERO) == LOW) || (digitalRead(AN_ZERO) == LOW)) && (led_blink == 0))
{
TimerLED.start();
led_blink = 1;
}
else if (((digitalRead(AZ_ZERO) == HIGH) && (digitalRead(AN_ZERO) == HIGH)))
{
digitalWrite(LED, LOW);
TimerLED.stop();
led_blink = 0;
}
if (TimerLED.isReady())
{
if (digitalRead(LED) == LOW) digitalWrite(LED, HIGH);
else digitalWrite(LED, LOW);
}
if (TimerBUT.isReady()) rcv = 0; // позволяет снова дать кнопке сработать
// запускаем цикл вращения к установленным значениям
while (moving_mode == 1)
{
Watchdog.reset(); // сброс пса
char key = pad.scan();// позволяем выйти из цикла
if (key)
{
strinput += key;
if (strinput == "O")
{
start = 4;
TimerMOV.stop();
action("STOP"); // останавливаем все двигатели
}
strinput ="";
}
if (start == 0) // начало установки азимута
{
to_degrees(set_x_degrees, set_x_minutes, set_x_second, set_azimuth);
start += 1;
if ((((set_azimuth - azimuth) / k_azimuth_right) * 1000) > 1)
{
action("RIGHT"); // крутим вправо
TimerMOV.setTimeout(((set_azimuth - azimuth) / k_azimuth_right) * 1000) ;
}
else if ((((azimuth - set_azimuth) / k_azimuth_left) * 1000) > 1)
{
action("LEFT"); // крутим влево
TimerMOV.setTimeout(((azimuth - set_azimuth) / k_azimuth_left) * 1000);
}
else if (abs(set_azimuth - azimuth) < 0.01) start += 1;
}
if (start == 2) // когда завершена установка азимута происходит установка угла места
{
to_degrees(set_y_degrees, set_y_minutes, set_y_second, set_elevation_angle);
start += 1;
if (((((set_elevation_angle - elevation_angle) / k_angle_up) * 1000) > 1) && (digitalRead(ANGLE_UP) == HIGH))
{
action("UP"); // поднимаем вверх
TimerMOV.setTimeout(((set_elevation_angle - elevation_angle) / k_angle_up) * 1000);
}
else if (((((elevation_angle - set_elevation_angle) / k_angle_down) * 1000) > 1) && (digitalRead(ANGLE_DOWN) == HIGH))
{
action("DOWN"); // опускаем
TimerMOV.setTimeout(((elevation_angle - set_elevation_angle) / k_angle_down) * 1000);
}
else if (abs(set_elevation_angle - elevation_angle) < 0.01) start += 1;
}
if (((digitalRead(ANGLE_UP) == LOW) && (timer_up != 0)) || ((digitalRead(ANGLE_DOWN) == LOW) && (timer_down != 0))) // вырубает движение при сработке датчиков для безопасности двигателя
{
TimerMOV.stop();
start += 1;
action("STOP"); // останавливаем все двигатели
}
if (TimerMOV.isReady()) // таймер сработки выключения движения
{
start += 1;
action("STOP"); // останавливаем все двигатели
}
if (start >= 4) // выход из программы и вывод полученных значений и установка значений при сработанном датчике
{
if (digitalRead(ANGLE_UP) == LOW) elevation_angle = max_angle;
else if (digitalRead(ANGLE_DOWN) == LOW) elevation_angle = min_angle;
else if (digitalRead(AN_ZERO) == LOW) elevation_angle = 0;
if (digitalRead(AZ_ZERO) == LOW) azimuth = 0;
from_degrees(azimuth, x_degrees, x_minutes, x_second); // перевод из значения в минуты
from_degrees(elevation_angle, y_degrees, y_minutes, y_second);
moving_mode = 0;
start = 0;
display();
delay(1000);
}
}
// запускаем цикл колибровки
while (calibration_azimuth == 1)// колибровка азимута
{
Watchdog.reset(); // сброс пса
if ((digitalRead(AZ_ZERO) == HIGH) && (zero_check == 0)) // при начале колибровки должно стоять на нуле
{
lcd.clear();
lcd.setCursor(0,2);
lcd.print("ERROR!");
lcd.setCursor(0,3);
lcd.print("Need_zero_azimuth");
delay(3000);
calibration_azimuth = 0;
Timer500.stop();
display();
}
else if ((digitalRead(AZ_ZERO) == LOW) && (zero_check == 0)) // первый шаг движение вправо
{
action("RIGHT");
zero_check += 1;
lcd.setCursor(14,3);
lcd.print(zero_check);
lcd.print(" of 5");
}
else if ((digitalRead(AZ_ZERO) == HIGH) && (zero_check == 1))
{
zero_check += 1;
lcd.setCursor(14,3);
lcd.print(zero_check);
lcd.print(" of 5");
}
else if ((digitalRead(AZ_ZERO) == LOW) && (zero_check == 2)) // третий шаг остановка и подсчет времени и коэф движения вправо
{
action("STOP");
k_azimuth_right = 360000 / azimuth_move; // расчитываем коэф для движения вправо
EEPROM.put(32,k_azimuth_right);
action("LEFT");// начинаем движение влево
zero_check += 1;
lcd.setCursor(14,3);
lcd.print(zero_check);
lcd.print(" of 5");
}
else if ((digitalRead(AZ_ZERO) == HIGH) && (zero_check == 3))
{
zero_check += 1;
lcd.setCursor(14,3);
lcd.print(zero_check);
lcd.print(" of 5");
}
else if ((digitalRead(AZ_ZERO) == LOW) && (zero_check == 4)) // пятый шаг подсчет движения влево и коэф
{
action("STOP");
k_azimuth_left = 360000 / azimuth_move;// расчитываем коэф для движения влево
EEPROM.put(36,k_azimuth_left);
azimuth = 0;
from_degrees(azimuth, x_degrees, x_minutes, x_second);
zero_check += 1;
lcd.setCursor(14,3);
lcd.print(zero_check);
lcd.print(" of 5");
}
char key = pad.scan();// позволяем выйти из цикла
if (Timer500.isReady()) // мигание точечек
{
if (u == 3)
{
u = 0;
}
if (u == 0)
{
lcd.setCursor(10,3);
lcd.print(" ");
lcd.setCursor(10,3);
lcd.print(".");
u += 1;
}
else if (u == 1)
{
lcd.setCursor(10,3);
lcd.print(" ");
lcd.setCursor(10,3);
lcd.print("..");
u += 1;
}
else
{
lcd.setCursor(10,3);
lcd.print(" ");
lcd.setCursor(10,3);
lcd.print("...");
u += 1;
}
}
if (key) // позволяет выйти из цикла
{
strinput += key;
if (strinput == "O")
{
action("STOP");
from_degrees(azimuth, x_degrees, x_minutes, x_second);
calibration_azimuth = 0;
zero_check = 0;
Timer500.stop();
display();
delay(1000);
}
strinput ="";
}
if (zero_check == 5)// завершение колибровки
{
zero_check = 0;
lcd.setCursor(0,3);
lcd.print(" ");
lcd.setCursor(0,3);
lcd.print("Completed !");
delay(3000);
calibration_azimuth = 0;
Timer500.stop();
display();
}
}
while (calibration_angle == 1) // колибровка угла места
{
Watchdog.reset(); // сброс пса
if ((digitalRead(AN_ZERO) == HIGH) && (zero_check == 0)) // при начале колибровки должно стоять на нуле
{
lcd.clear();
lcd.setCursor(0,2);
lcd.print("ERROR!");
lcd.setCursor(0,3);
lcd.print("Need_zero_angle");
delay(3000);
calibration_angle = 0;
Timer500.stop();
display();
}
else if ((digitalRead(AN_ZERO) == LOW) && (zero_check == 0)) // движение вниз
{
action("DOWN");
zero_check += 1;
lcd.setCursor(14,3);
lcd.print(zero_check);
lcd.print(" of 5");
}
else if ((digitalRead(AN_ZERO) == HIGH) && (zero_check == 1))
{
zero_check += 1;
lcd.setCursor(14,3);
lcd.print(zero_check);
lcd.print(" of 5");
}
else if ((digitalRead(ANGLE_DOWN) == LOW) && (zero_check == 2)) // подсчет
{
action("STOP");
k_angle_down = (abs(min_angle) * 1000) / angle_move; // расчитываем коэф для движения вправо
EEPROM.put(44,k_angle_down);
action("UP"); // движение вверх
zero_check += 1;
lcd.setCursor(14,3);
lcd.print(zero_check);
lcd.print(" of 5");
}
else if ((digitalRead(ANGLE_DOWN) == HIGH) && (zero_check == 3))
{
zero_check += 1;
lcd.setCursor(14,3);
lcd.print(zero_check);
lcd.print(" of 5");
}
else if ((digitalRead(AN_ZERO) == LOW) && (zero_check == 4)) // подсчет
{
action("STOP");
k_angle_up = (abs(min_angle) * 1000) / angle_move;// расчитываем коэф для движения влево
EEPROM.put(40,k_angle_up);
elevation_angle = 0;
from_degrees(elevation_angle, y_degrees, y_minutes, y_second);
zero_check += 1;
lcd.setCursor(14,3);
lcd.print(zero_check);
lcd.print(" of 5");
}
char key = pad.scan();// позволяем выйти из цикла
if (Timer500.isReady()) // для красоты
{
if (u == 3)
{
u = 0;
}
if (u == 0)
{
lcd.setCursor(10,3);
lcd.print(" ");
lcd.setCursor(10,3);
lcd.print(".");
u += 1;
}
else if (u == 1)
{
lcd.setCursor(10,3);
lcd.print(" ");
lcd.setCursor(10,3);
lcd.print("..");
u += 1;
}
else
{
lcd.setCursor(10,3);
lcd.print(" ");
lcd.setCursor(10,3);
lcd.print("...");
u += 1;
}
}
if (key)
{
strinput += key;
if (strinput == "O")
{
action("STOP");
from_degrees(elevation_angle, y_degrees, y_minutes, y_second);
calibration_angle = 0;
zero_check = 0;
Timer500.stop();
display();
delay(1000);
}
strinput ="";
}
if (zero_check == 5) // завершение колибровки
{
zero_check = 0;
lcd.setCursor(0,3);
lcd.print(" ");
lcd.setCursor(0,3);
lcd.print("Completed !");
delay(3000);
calibration_angle = 0;
Timer500.stop();
display();
}
}
// запускаем цикл установки
while (set_mode == 1)
{
Watchdog.reset(); // сброс пса
char key = pad.getKey();// режим нажатия позволяет избежать двойного нажатия
if (key) // выход из цикла
{
strinput += key;
if (strinput == "O")
{
Timer500.stop();
lcd.noCursor();
set_mode = 0;
unit = 0;
in_num = 0;
number = 0;
minus = 0;
display();
delay(1000);
}
else if (strinput == "0") // нажимаем 0
{
input_number = 0;
lcd.print(input_number);// пишем полученную цифру на экране
enumerate_numbers(unit, in_num, input_number, number);// считаем цифры и переходим в другой разряд
set_cursor(unit, in_num); // переводим курсор на следующую цифру
}
else if ((strinput == "1") && (((unit == 0) && (number < 360)) || ((unit > 0) && (abs(number) < 60))))
{
input_number = 1;
lcd.print(input_number);// пишем полученную цифру на экране
if (minus == 1) input_number = -input_number; // если нажат минус то число будет отрицательное
enumerate_numbers(unit, in_num, input_number, number);// считаем цифры и переходим в другой разряд
set_cursor(unit, in_num); // переводим курсор на следующую цифру
}
else if ((strinput == "2") && (((unit == 0) && (number < 360)) || ((unit > 0) && (abs(number) < 60))))
{
input_number = 2;
lcd.print(input_number);// пишем полученную цифру на экране
if (minus == 1) input_number = -input_number;
enumerate_numbers(unit, in_num, input_number, number);// считаем цифры и переходим в другой разряд
set_cursor(unit, in_num); // переводим курсор на следующую цифру
}
else if ((strinput == "3") && (((unit == 0) && (number < 360)) || ((unit > 0) && (abs(number) < 60))))
{
input_number = 3;
lcd.print(input_number);// пишем полученную цифру на экране
if (minus == 1) input_number = -input_number;
enumerate_numbers(unit, in_num, input_number, number);// считаем цифры и переходим в другой разряд
set_cursor(unit, in_num); // переводим курсор на следующую цифру
}
else if ((strinput == "4") && (((unit == 0) && ((in_num == 1) || (in_num == 2)) && (number < 360)) || ((unit > 0) && (abs(number) < 60)))) // у 3х знчного только 2 или 3
{
input_number = 4;
lcd.print(input_number);// пишем полученную цифру на экране
if (minus == 1) input_number = -input_number;
enumerate_numbers(unit, in_num, input_number, number);// считаем цифры и переходим в другой разряд
set_cursor(unit, in_num); // переводим курсор на следующую цифру
}
else if ((strinput == "5") && (((unit == 0) && ((in_num == 1) || (in_num == 2)) && (number < 360)) || ((unit > 0) && (abs(number) < 60)))) //у 3х знчного только 2 или 3
{
input_number = 5;
lcd.print(input_number);// пишем полученную цифру на экране
if (minus == 1) input_number = -input_number;
enumerate_numbers(unit, in_num, input_number, number);// считаем цифры и переходим в другой разряд
set_cursor(unit, in_num); // переводим курсор на следующую цифру
}
else if ((strinput == "6") && (((unit == 0) && ((in_num == 1) || (in_num == 2)) && (number < 360)) || ((unit > 0) && (in_num == 1) && (abs(number) < 60)))) //у 3х знчного только 2 или 3
{
input_number = 6;
lcd.print(input_number);// пишем полученную цифру на экране
if (minus == 1) input_number = -input_number;
enumerate_numbers(unit, in_num, input_number, number);// считаем цифры и переходим в другой разряд
set_cursor(unit, in_num); // переводим курсор на следующую цифру
}
else if ((strinput == "7") && (((unit == 0) && ((in_num == 1) || (in_num == 2)) && (number < 360)) || ((unit > 0) && (in_num == 1) && (abs(number) < 60)))) //у 3х знчного только 2 или 3 у 2х только 2
{
input_number = 7;
lcd.print(input_number);// пишем полученную цифру на экране
if (minus == 1) input_number = -input_number;
enumerate_numbers(unit, in_num, input_number, number);// считаем цифры и переходим в другой разряд
set_cursor(unit, in_num); // переводим курсор на следующую цифру
}
else if ((strinput == "8") && (((unit == 0) && ((in_num == 1) || (in_num == 2)) && (number < 360)) || ((unit > 0) && (in_num == 1) && (abs(number) < 60)))) //у 3х знчного только 2 или 3 у 2х только 2
{
input_number = 8;
lcd.print(input_number);// пишем полученную цифру на экране
if (minus == 1) input_number = -input_number;
enumerate_numbers(unit, in_num, input_number, number);// считаем цифры и переходим в другой разряд
set_cursor(unit, in_num); // переводим курсор на следующую цифру
}
else if ((strinput == "9") && (((unit == 0) && ((in_num == 1) || (in_num == 2)) && (number < 360)) || ((unit > 0) && (in_num == 1) && (abs(number) < 60)))) //у 3х знчного только 2 или 3 у 2х только 2
{
input_number = 9;
lcd.print(input_number);// пишем полученную цифру на экране
if (minus == 1) input_number = -input_number;
enumerate_numbers(unit, in_num, input_number, number);// считаем цифры и переходим в другой разряд
set_cursor(unit, in_num); // переводим курсор на следующую цифру
}
else if ((strinput == "D") && (unit == 3) && (in_num == 0)) // нажимаем звездочку и получаем отрицательное число
{
minus = 1;
lcd.setCursor(11,2);
lcd.print(" ");
lcd.setCursor(11,2);
lcd.print("-");
lcd.setCursor(12,2);
}
strinput ="";
}
if (unit > 5)// приняли все сиволы выходим
{
Timer500.stop();
lcd.noCursor();
set_mode = 0;
minus = 0;
display();
unit = 0;
in_num = 0;
number = 0;
delay(1000);
}
if (Timer500.isReady())// мигание курсора
{
if (cur == 0)
{
lcd.cursor();
cur = 1;
}
else
{
cur = 0;
lcd.noCursor();
}
}
}
// запускаем цикл установки минимальных и максимальных значений
while (set_min_max == 1)
{
Watchdog.reset(); // сброс пса
char key = pad.getKey();// позволяем выйти из цикла
if (key)
{
strinput += key;
if (strinput == "O")
{
set_min_max = 0;
display();
delay(1000);
}
else if ((strinput == "^") && (change == 0) && (min_angle < -1))
{
min_angle += 1;
lcd.setCursor(0,2);
lcd.print("min angle:");
lcd.print(min_angle);
}
else if ((strinput == "!") && (change == 0) && (min_angle > -59))
{
min_angle -= 1;
lcd.setCursor(0,2);
lcd.print("min angle:");
lcd.print(min_angle);
}
else if ((strinput == "^") && (change == 1) && (max_angle < 59))
{
max_angle += 1;
lcd.setCursor(0,3);
lcd.print("max angle:");
lcd.print(max_angle);
}
else if ((strinput == "!") && (change == 1) && (max_angle > 1))
{
max_angle -= 1;
lcd.setCursor(0,3);
lcd.print("max angle:");
lcd.print(max_angle);
}
else if (strinput == "E")// при нажатии ент переход на изменение другой величены
{
change += 1;
}
strinput ="";
}
if (change == 2)// нажат ентер и выход из цикла
{
set_min_max = 0;
change = 0;
lcd.setCursor(0,1);
lcd.print("writing memory...");
EEPROM.put(48,max_angle); //
EEPROM.put(52,min_angle);
delay(3000);
display();
}
}
}