Skip to content

Commit ad9cfca

Browse files
V1.6.15 - Updates
- SELECT on HA does not leave the HA menu (except during guided Startup). Use RIGHT as usual. - The Polar alignment in CAL now slews to Polaris, prompts you to center it, then slews to the point beyond Polaris, and prompts you to center it. - Fixed a bug where when one axis completed a slew before the other it displayed the starting coordinate instead of the target.
1 parent 9615a4b commit ad9cfca

File tree

4 files changed

+60
-21
lines changed

4 files changed

+60
-21
lines changed

Software/Arduino code/OpenAstroTracker/Mount.cpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -486,6 +486,13 @@ void Mount::loop() {
486486
}
487487

488488
if (raStillRunning || decStillRunning) {
489+
if (!raStillRunning) {
490+
_currentRA = _targetRA;
491+
}
492+
if (!decStillRunning) {
493+
_currentDEC = _targetDEC;
494+
}
495+
489496
//Serial.println("Loop: RA " + String(raStillRunning) + String(decStillRunning) );
490497
displayStepperPositionThrottled();
491498
}

Software/Arduino code/OpenAstroTracker/OpenAstroTracker.ino

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
/*
22
=======================================================================================================================================
33
4-
Version 1.6.14
4+
Version 1.6.15
55
66
1. Connect your Arduino, under tools choose "Arduino Uno", set the right Port and set "Arduino ISP" as the Programmer.
77
2. Hit upload (Ctrl-U)
@@ -14,7 +14,7 @@
1414
1515
=======================================================================================================================================
1616
*/
17-
String version = "V1.6.14";
17+
String version = "V1.6.15";
1818

1919
// See NORTHERN_HEMISPHERE in Globals.h if you not in the northern hemisphere
2020

Software/Arduino code/OpenAstroTracker/c72_menuHA.ino

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@ bool processHAKeys() {
2020
// slow down key repetitions
2121
mount.delay(200);
2222
waitForRelease = false;
23-
}
23+
}
2424
else if (lcdButtons.keyChanged(key)) {
2525
switch (key) {
2626

@@ -29,18 +29,20 @@ bool processHAKeys() {
2929
}
3030
break;
3131

32-
case btnSELECT:
33-
case btnRIGHT: {
32+
case btnSELECT: {
3433
EEPROM.update(1, mount.HA().getHours());
3534
EEPROM.update(2, mount.HA().getMinutes());
3635
lcdMenu.printMenu("Stored.");
3736
mount.delay(500);
38-
3937
if (startupState == StartupWaitForHACompletion) {
4038
startupState = StartupHAConfirmed;
4139
inStartup = true;
4240
}
43-
else {
41+
}
42+
break;
43+
44+
case btnRIGHT: {
45+
if (startupState != StartupWaitForHACompletion) {
4446
lcdMenu.setNextActive();
4547
}
4648
}

Software/Arduino code/OpenAstroTracker/c76_menuCAL.ino

Lines changed: 44 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,9 @@
11
#define HIGHLIGHT_POLAR 1
22
#define HIGHLIGHT_SPEED 2
3-
#define POLAR_CALIBRATION 3
4-
#define SPEED_CALIBRATION 4
3+
#define POLAR_CALIBRATION_WAIT 3
4+
#define POLAR_CALIBRATION_GO 4
5+
#define POLAR_CALIBRATION_WAIT_HOME 5
6+
#define SPEED_CALIBRATION 6
57

68
byte calState = HIGHLIGHT_POLAR;
79

@@ -29,25 +31,36 @@ bool processCalibrationKeys() {
2931
else {
3032
calDelay = 150;
3133
}
34+
}
35+
else if (calState == POLAR_CALIBRATION_WAIT_HOME) {
36+
if (!mount.isSlewingRAorDEC()) {
37+
lcdMenu.updateDisplay();
38+
calState = HIGHLIGHT_POLAR;
39+
}
3240
}
3341

42+
43+
3444
if (checkForKeyChange && lcdButtons.keyChanged(key)) {
3545
waitForRelease = true;
3646

3747
switch (calState) {
38-
case POLAR_CALIBRATION: {
48+
49+
case POLAR_CALIBRATION_GO: {
3950
if (key == btnSELECT) {
51+
lcdMenu.printMenu("Aligned, homing");
52+
mount.delay(600);
4053
mount.setTargetToHome();
4154
mount.startSlewingToTarget();
42-
lcdMenu.setNextActive();
43-
calState = HIGHLIGHT_POLAR;
55+
calState = POLAR_CALIBRATION_WAIT_HOME;
4456
}
4557
if (key == btnRIGHT) {
4658
lcdMenu.setNextActive();
4759
calState = HIGHLIGHT_POLAR;
4860
}
4961
}
5062
break;
63+
5164
case SPEED_CALIBRATION: {
5265
// UP and DOWN are handled above
5366
if (key == btnSELECT) {
@@ -67,16 +80,27 @@ bool processCalibrationKeys() {
6780
case HIGHLIGHT_POLAR:
6881
if (key == btnDOWN) calState = HIGHLIGHT_SPEED;
6982
else if (key == btnSELECT) {
70-
calState = POLAR_CALIBRATION;
71-
83+
calState = POLAR_CALIBRATION_WAIT;
84+
7285
// Move the RA to that of Polaris. Moving to this RA aligns the DEC axis such that
7386
// it swings along the line between Polaris and the Celestial Pole.
74-
mount.targetRA() = DayTime(2, 57, 56); // This is Polaris RA.
87+
mount.targetRA() = DayTime(2, 57, 56); // This is Polaris RA.
7588
// Account for the current settings.
7689
mount.targetRA().addTime(mount.getHACorrection());
7790
mount.targetRA().subtractTime(mount.HA());
78-
79-
// Now set DEC to move the same distance past Polaris as it is from the Celestial Pole. That equates to 88deg 42' 6".
91+
92+
// Now set DEC to move to Polaris
93+
mount.targetDEC() = DegreeTime(89 - (NORTHERN_HEMISPHERE ? 90 : -90), 21, 3);
94+
mount.startSlewingToTarget();
95+
}
96+
break;
97+
98+
case POLAR_CALIBRATION_WAIT:
99+
if (key == btnSELECT) {
100+
calState = POLAR_CALIBRATION_GO;
101+
102+
// RA is already set. Now set DEC to move the same distance past Polaris as
103+
// it is from the Celestial Pole. That equates to 88deg 42' 6".
80104
mount.targetDEC() = DegreeTime(88 - (NORTHERN_HEMISPHERE ? 90 : -90), 42, 6);
81105
mount.startSlewingToTarget();
82106
}
@@ -106,14 +130,20 @@ void printCalibrationSubmenu() {
106130
case HIGHLIGHT_POLAR :
107131
lcdMenu.printMenu(">Polar alignment");
108132
break;
109-
case HIGHLIGHT_SPEED:
110-
lcdMenu.printMenu(">Speed calibratn");
111-
break;
112-
case POLAR_CALIBRATION :
133+
case POLAR_CALIBRATION_WAIT_HOME:
134+
case POLAR_CALIBRATION_WAIT:
135+
case POLAR_CALIBRATION_GO :
113136
if (!mount.isSlewingRAorDEC()) {
137+
lcdMenu.setCursor(0, 0);
114138
lcdMenu.printMenu("Centr on Polaris");
139+
lcdMenu.setCursor(0, 1);
140+
lcdMenu.printMenu(">Centered");
115141
}
116142
break;
143+
144+
case HIGHLIGHT_SPEED:
145+
lcdMenu.printMenu(">Speed calibratn");
146+
break;
117147
case SPEED_CALIBRATION :
118148
sprintf(scratchBuffer, "SpdFctr: ");
119149
dtostrf(mount.getSpeedCalibration(), 6, 4, &scratchBuffer[9]);

0 commit comments

Comments
 (0)