Skip to content

Commit fed13f2

Browse files
V1.7.04 - Updates
- Fixed a bug that prevented the speed calibration factor adjustment to persist correctly. - Fixed a bug that did not adjust the tracking speed as you increased the speed calibration factor
1 parent 81e649a commit fed13f2

File tree

4 files changed

+72
-36
lines changed

4 files changed

+72
-36
lines changed

Software/Arduino code/OpenAstroTracker/Mount.cpp

Lines changed: 26 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -126,6 +126,10 @@ void Mount::readPersistentData()
126126
{
127127
// Read the magic marker byte and state
128128
int marker = EEPROM.read(4) + EEPROM.read(5) * 256;
129+
#ifdef DEBUG_MODE
130+
logv("EEPROM: Marker: %x ", marker);
131+
#endif
132+
129133
if ((marker & 0xFF01) == 0xBE01) {
130134
_stepsPerRADegree = EEPROM.read(6) + EEPROM.read(7) * 256;
131135
#ifdef DEBUG_MODE
@@ -143,9 +147,9 @@ void Mount::readPersistentData()
143147
float speed = 1.0;
144148
if ((marker & 0xFF04) == 0xBE04) {
145149
int adjust = EEPROM.read(0) + EEPROM.read(3) * 256;
146-
speed = 1.0 + adjust / 10000;
150+
speed = 1.0 + 1.0 * adjust / 10000.0;
147151
#ifdef DEBUG_MODE
148-
logv("EEPROM: Speed Marker OK! Speed adjust is %d", adjust);
152+
logv("EEPROM: Speed Marker OK! Speed adjust is %d, speedFactor is %f", adjust, speed);
149153
#endif
150154
}
151155

@@ -174,6 +178,9 @@ void Mount::writePersistentData(int which, int val)
174178
if (EEPROM.read(5) == 0xBE) {
175179
// ... read the current state ...
176180
flag = EEPROM.read(4);
181+
#ifdef DEBUG_MODE
182+
logv("EEPROM Write: Marker is 0xBE, flag is %x (%d)", flag, flag);
183+
#endif
177184
}
178185
switch (which) {
179186
case RA_STEPS:
@@ -199,6 +206,7 @@ void Mount::writePersistentData(int which, int val)
199206
loByteLocation = 0;
200207
hiByteLocation = 3;
201208
}
209+
break;
202210
case BACKLASH_CORRECTION:
203211
{
204212
// ... set bit 2 to indicate speed factor value has been written to 0/3
@@ -209,6 +217,9 @@ void Mount::writePersistentData(int which, int val)
209217
break;
210218
}
211219

220+
#ifdef DEBUG_MODE
221+
logv("EEPROM Write: New Marker is 0xBE, flag is %x (%d)", flag, flag);
222+
#endif
212223

213224
EEPROMupdate(4, flag);
214225
EEPROMupdate(5, 0xBE);
@@ -309,16 +320,21 @@ float Mount::getSpeedCalibration() {
309320
void Mount::setSpeedCalibration(float val, bool saveToStorage) {
310321
_trackingSpeedCalibration = val;
311322

323+
// The tracker simply needs to rotate at 15degrees/hour, adjusted for sidereal
324+
// time (i.e. the 15degrees is per 23h56m04s. 86164s/86400 = 0.99726852. 3590/3600 is the same ratio) So we only go 15 x 0.99726852 in an hour.
325+
_trackingSpeed = _trackingSpeedCalibration * _stepsPerRADegree * siderealDegreesInHour / 3600.0f;
326+
312327
if (saveToStorage) {
313328
val = (val - 1.0) * 10000;
314329
if (val > 32766) val = 32766;
315330
if (val < -32766) val = -32766;
316331
writePersistentData(SPEED_FACTOR_DECIMALS, (int)floor(val));
317332
}
318333

319-
// The tracker simply needs to rotate at 15degrees/hour, adjusted for sidereal
320-
// time (i.e. the 15degrees is per 23h56m04s. 86164s/86400 = 0.99726852. 3590/3600 is the same ratio) So we only go 15 x 0.99726852 in an hour.
321-
_trackingSpeed = _trackingSpeedCalibration * _stepsPerRADegree * siderealDegreesInHour / 3600.0f;
334+
// If we are currently tracking, update the speed.
335+
if (isSlewingTRK()) {
336+
_stepperTRK->setSpeed(_trackingSpeed);
337+
}
322338
}
323339

324340
/////////////////////////////////
@@ -1150,8 +1166,8 @@ void Mount::loop() {
11501166
bool raStillRunning = false;
11511167
bool decStillRunning = false;
11521168

1153-
// Since the ESP8266 cannot process timer interrupts at the required
1154-
// speed, we'll just stick to deterministic calls here.
1169+
// Since the ESP8266 cannot process timer interrupts at the required
1170+
// speed, we'll just stick to deterministic calls here.
11551171
#ifdef ESP8266
11561172
interruptLoop();
11571173
#endif
@@ -1161,7 +1177,7 @@ void Mount::loop() {
11611177
if (now - _lastMountPrint > 2000) {
11621178
Serial.println(getStatusString());
11631179
_lastMountPrint = now;
1164-
}
1180+
}
11651181
#endif
11661182
if (isGuiding()) {
11671183
if (millis() > _guideEndTime) {
@@ -1532,9 +1548,9 @@ void Mount::displayStepperPosition() {
15321548
_lcdMenu->setCursor(0, 1);
15331549
_lcdMenu->printMenu(scratchBuffer);
15341550
#endif
1535-
}
1551+
}
15361552
#endif
1537-
}
1553+
}
15381554

15391555
/////////////////////////////////
15401556
//

Software/Arduino code/OpenAstroTracker/OpenAstroTracker.ino

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@
1616
*/
1717
#include "Globals.h"
1818

19-
String version = "V1.7.02";
19+
String version = "V1.7.04";
2020

2121
///////////////////////////////////////////////////////////////////////////
2222
// Please see the Globals.h file for configuration of the firmware.
@@ -63,8 +63,6 @@ float DECStepsPerRevolution = 4096;
6363

6464
int DECStepsPerDegree = (565.5 / (DecPulleyTeeth * 2.0) * DECStepsPerRevolution / 360.0);
6565

66-
float speed = 1.000; // Use this value to slightly increase or decrese tracking speed. The values from the "CAL" menu will be added to this.
67-
6866
int RAspeed = 400; // You can change the speed and acceleration of the steppers here. Max. Speed = 600. High speeds tend to make
6967
int RAacceleration = 600; // these cheap steppers unprecice
7068
int DECspeed = 800;

Software/Arduino code/OpenAstroTracker/Utility.cpp

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,7 @@ float clamp(float current, float minVal, float maxVal)
5454
#ifdef DEBUG_MODE
5555

5656
String formatArg(const char* input, va_list args) {
57+
char* nibble = "0123456789ABCDEF";
5758
char achBuffer[255];
5859
char* p = achBuffer;
5960

@@ -89,6 +90,23 @@ String formatArg(const char* input, va_list args) {
8990
}
9091
break;
9192

93+
case 'x': {
94+
int n = (int)va_arg(args, int);
95+
int shift = 12;
96+
unsigned int mask = 0xF000;
97+
*p++ = '0';
98+
*p++ = 'x';
99+
while (shift >= 0) {
100+
int d=(n & mask) >> shift;
101+
*p++ = *(nibble + d);
102+
mask = mask >> 4;
103+
shift -= 4;
104+
}
105+
106+
*p = 0;
107+
}
108+
break;
109+
92110
case 'l': {
93111
String s = String((long)va_arg(args, long));
94112
strcpy(p, s.c_str());

Software/Arduino code/OpenAstroTracker/c76_menuCAL.ino

Lines changed: 27 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -43,10 +43,10 @@
4343
byte calState = HIGHLIGHT_FIRST;
4444

4545
// SPeed adjustment variable. Added to 1.0 after dividing by 10000 to get final speed
46-
float inputcal;
46+
float SpeedCalibration;
4747

4848
// The current delay in ms when changing calibration value. The longer a button is depressed, the smaller this gets.
49-
int calDelay = 150;
49+
int calDelay = 150;
5050

5151
// The index of durations that the user has selected.
5252
byte driftSubIndex = 1;
@@ -92,6 +92,9 @@ void gotoNextHighlightState(int dir) {
9292
else if (calState == HIGHLIGHT_BACKLASH_STEPS) {
9393
BacklashSteps = mount.getBacklashCorrection();
9494
}
95+
else if (calState == HIGHLIGHT_SPEED) {
96+
SpeedCalibration = (mount.getSpeedCalibration() - 1.0) * 10000.0 + 0.5;
97+
}
9598
}
9699

97100
bool processCalibrationKeys() {
@@ -101,19 +104,20 @@ bool processCalibrationKeys() {
101104

102105
if (calState == SPEED_CALIBRATION) {
103106
if (lcdButtons.currentState() == btnUP) {
104-
if (inputcal < 32760) { // Don't overflow 16 bit signed
105-
inputcal += 1; //0.0001;
106-
mount.setSpeedCalibration(speed + inputcal / 10000, false);
107+
if (SpeedCalibration < 32760) { // Don't overflow 16 bit signed
108+
SpeedCalibration += 1; //0.0001;
109+
mount.setSpeedCalibration(1.0 + SpeedCalibration / 10000.0, false);
110+
mount.setSpeedCalibration(1.0 + SpeedCalibration / 10000.0, false);
107111
}
108112

109113
mount.delay(calDelay);
110114
calDelay = max(5, 0.96 * calDelay);
111115
checkForKeyChange = false;
112116
}
113117
else if (lcdButtons.currentState() == btnDOWN) {
114-
if (inputcal > -32760) { // Don't overflow 16 bit signed
115-
inputcal -= 1; //0.0001;
116-
mount.setSpeedCalibration(speed + inputcal / 10000, false);
118+
if (SpeedCalibration > -32760) { // Don't overflow 16 bit signed
119+
SpeedCalibration -= 1; //0.0001;
120+
mount.setSpeedCalibration(1.0 + SpeedCalibration / 10000.0, false);
117121
}
118122

119123
mount.delay(calDelay);
@@ -184,25 +188,25 @@ bool processCalibrationKeys() {
184188
calState = HIGHLIGHT_POLAR;
185189
}
186190
}
187-
break;
191+
break;
188192

189193
case SPEED_CALIBRATION: {
190194
// UP and DOWN are handled above
191195
if (key == btnSELECT) {
192-
int cal = floor(inputcal);
193-
mount.setSpeedCalibration(speed + inputcal / 10000, true);
196+
mount.setSpeedCalibration(1.0 + SpeedCalibration / 10000.0, true);
194197
lcdMenu.printMenu("Speed Stored.");
195198
mount.delay(500);
196199
calState = HIGHLIGHT_SPEED;
197200
}
198201
else if (key == btnRIGHT) {
202+
mount.setSpeedCalibration(1.0 + SpeedCalibration / 10000.0, true);
199203
lcdMenu.setNextActive();
200204
calState = HIGHLIGHT_SPEED;
201205
}
202206
}
203-
break;
207+
break;
204208

205-
case RA_STEP_CALIBRATION:
209+
case RA_STEP_CALIBRATION:
206210
{
207211
// UP and DOWN are handled above
208212
if (key == btnSELECT) {
@@ -271,7 +275,7 @@ bool processCalibrationKeys() {
271275
lcdMenu.setNextActive();
272276
}
273277
}
274-
break;
278+
break;
275279

276280
case POLAR_CALIBRATION_WAIT: {
277281
if (key == btnSELECT) {
@@ -287,7 +291,7 @@ bool processCalibrationKeys() {
287291
calState = HIGHLIGHT_POLAR;
288292
}
289293
}
290-
break;
294+
break;
291295

292296
case HIGHLIGHT_SPEED: {
293297
if (key == btnDOWN) gotoNextHighlightState(1);
@@ -298,7 +302,7 @@ bool processCalibrationKeys() {
298302
calState = HIGHLIGHT_POLAR;
299303
}
300304
}
301-
break;
305+
break;
302306

303307
case HIGHLIGHT_DRIFT: {
304308
if (key == btnDOWN) gotoNextHighlightState(1);
@@ -309,7 +313,7 @@ bool processCalibrationKeys() {
309313
calState = HIGHLIGHT_POLAR;
310314
}
311315
}
312-
break;
316+
break;
313317

314318
case DRIFT_CALIBRATION_WAIT: {
315319
if (key == btnDOWN || key == btnLEFT) {
@@ -331,7 +335,7 @@ bool processCalibrationKeys() {
331335
driftSubIndex = 1;
332336
}
333337
}
334-
break;
338+
break;
335339

336340
case HIGHLIGHT_RA_STEPS: {
337341
if (key == btnDOWN) gotoNextHighlightState(1);
@@ -342,7 +346,7 @@ bool processCalibrationKeys() {
342346
calState = HIGHLIGHT_FIRST;
343347
}
344348
}
345-
break;
349+
break;
346350

347351
case HIGHLIGHT_DEC_STEPS: {
348352
if (key == btnDOWN) gotoNextHighlightState(1);
@@ -353,18 +357,18 @@ bool processCalibrationKeys() {
353357
calState = HIGHLIGHT_FIRST;
354358
}
355359
}
356-
break;
360+
break;
357361

358-
case HIGHLIGHT_BACKLASH_STEPS : {
359-
if (key == btnDOWN) gotoNextHighlightState(1);
362+
case HIGHLIGHT_BACKLASH_STEPS: {
363+
if (key == btnDOWN) gotoNextHighlightState(1);
360364
if (key == btnUP) gotoNextHighlightState(-1);
361365
else if (key == btnSELECT) calState = BACKLASH_CALIBRATION;
362366
else if (key == btnRIGHT) {
363367
lcdMenu.setNextActive();
364368
calState = HIGHLIGHT_FIRST;
365369
}
366370
}
367-
break;
371+
break;
368372
}
369373
}
370374

0 commit comments

Comments
 (0)