Skip to content

Commit 6cc5ebd

Browse files
V1.8.52 - Updates
- Moved LCD updates out of the mount loop. - Fixed a bug that did not correctly handle displaying Roll and Pitch offset. - Added ability to define DEC limits. Limits are not enforced yet, that code is still in development. - Added new debug channel for digital level.
1 parent 19bfdee commit 6cc5ebd

File tree

9 files changed

+247
-57
lines changed

9 files changed

+247
-57
lines changed

Software/Arduino code/OpenAstroTracker/Configuration_adv.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -209,7 +209,7 @@
209209
//
210210
// SETTINGS
211211
//
212-
#define INFRA_SSID "YouSSID"
212+
#define INFRA_SSID "YourSSID"
213213
#define INFRA_WPAKEY "YourWPAKey"
214214
#define OAT_WPAKEY "superSecret"
215215
#define HOSTNAME "OATerScope"
@@ -244,6 +244,7 @@
244244
#define DEBUG_VERBOSE 0x0080
245245
#define DEBUG_STEPPERS 0x0100
246246
#define DEBUG_EEPROM 0x0200
247+
#define DEBUG_GYRO 0x0400
247248
#define DEBUG_ANY 0xFFFF
248249

249250
////////////////////////////
Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1 +1 @@
1-
#define VERSION "V1.8.51"
1+
#define VERSION "V1.8.52"

Software/Arduino code/OpenAstroTracker/src/Mount.cpp

Lines changed: 76 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -78,6 +78,7 @@
7878

7979
// Extended bits
8080
#define EEPROM_PARKING_POS_MARKER_BIT 0x0001
81+
#define EEPROM_DEC_LIMIT_MARKER_BIT 0x0002
8182

8283
const char* formatStringsDEC[] = {
8384
"",
@@ -155,6 +156,8 @@ Mount::Mount(int stepsPerRADegree, int stepsPerDECDegree, LcdMenu* lcdMenu) {
155156
_slewingToPark = false;
156157
_raParkingPos = 0;
157158
_decParkingPos = 0;
159+
_decLowerLimit = 0;
160+
_decUpperLimit = 0;
158161

159162
#if USE_GYRO_LEVEL == 1
160163
_pitchCalibrationAngle = 0;
@@ -324,6 +327,15 @@ void Mount::readPersistentData()
324327
else{
325328
LOGV1(DEBUG_INFO|DEBUG_EEPROM,F("Mount: EEPROM: No stored value for Parking position"));
326329
}
330+
if (nextMarker & EEPROM_DEC_LIMIT_MARKER_BIT){
331+
_decLowerLimit = EPROMStore::readInt32(31); // 31-34
332+
_decUpperLimit = EPROMStore::readInt32(35); // 35-38
333+
LOGV3(DEBUG_INFO|DEBUG_EEPROM,F("Mount: EEPROM: DEC limitsread as %l -> %l"), _decLowerLimit, _decUpperLimit );
334+
}
335+
else{
336+
LOGV1(DEBUG_INFO|DEBUG_EEPROM,F("Mount: EEPROM: No stored value for Parking position"));
337+
}
338+
327339
}
328340
else {
329341
LOGV1(DEBUG_INFO|DEBUG_EEPROM,F("Mount: EEPROM: No ExtendedMarker present"));
@@ -444,7 +456,7 @@ void Mount::writePersistentData(int which, long val)
444456
case EEPROM_RA_PARKING_POS:
445457
case EEPROM_DEC_PARKING_POS:
446458
{
447-
// ... set bit 8 to indicate pitch offset angle value has been written to 19/20
459+
// ... set bit 0 in extended flag to indicate Parking pos has been written to 23-30
448460
writeExtended = true;
449461
extendedFlag |= EEPROM_PARKING_POS_MARKER_BIT;
450462
if (which == EEPROM_RA_PARKING_POS ){
@@ -457,6 +469,23 @@ void Mount::writePersistentData(int which, long val)
457469
}
458470
}
459471
break;
472+
473+
case EEPROM_DEC_UPPER_LIMIT:
474+
case EEPROM_DEC_LOWER_LIMIT:
475+
{
476+
// ... set bit 1 in extended flag to indicate Parking pos has been written to 23-30
477+
writeExtended = true;
478+
extendedFlag |= EEPROM_DEC_LIMIT_MARKER_BIT;
479+
if (which == EEPROM_DEC_UPPER_LIMIT ){
480+
EPROMStore::updateInt32(31, val);
481+
LOGV2(DEBUG_INFO|DEBUG_EEPROM,F("Mount: EEPROM Write: Updating DEC Upper limit to %l at 31-34"), val);
482+
}
483+
else {
484+
EPROMStore::updateInt32(35, val);
485+
LOGV2(DEBUG_INFO|DEBUG_EEPROM,F("Mount: EEPROM Write: Updating DEC Lower limit to %l at 35-38"), val);
486+
}
487+
}
488+
break;
460489
}
461490

462491

@@ -704,6 +733,7 @@ float Mount::getPitchCalibrationAngle()
704733
void Mount::setPitchCalibrationAngle(float angle)
705734
{
706735
uint16_t angleValue = (angle * 100) + 16384;
736+
LOGV3(DEBUG_GYRO, "Mount: Setting Pitch calibration to %d (%f)", angleValue, angle);
707737
writePersistentData(EEPROM_PITCH_OFFSET, angleValue);
708738
_pitchCalibrationAngle = angle;
709739
}
@@ -727,6 +757,7 @@ float Mount::getRollCalibrationAngle()
727757
void Mount::setRollCalibrationAngle(float angle)
728758
{
729759
uint16_t angleValue = (angle * 100) + 16384;
760+
LOGV3(DEBUG_GYRO, "Mount: Setting Roll calibration to %d (%f)", angleValue, angle);
730761
writePersistentData(EEPROM_ROLL_OFFSET, angleValue);
731762
_rollCalibrationAngle = angle;
732763
}
@@ -1867,7 +1898,6 @@ void Mount::interruptLoop()
18671898
// Process any stepper changes.
18681899
/////////////////////////////////
18691900
void Mount::loop() {
1870-
unsigned long now = millis();
18711901
bool raStillRunning = false;
18721902
bool decStillRunning = false;
18731903

@@ -2005,7 +2035,7 @@ void Mount::loop() {
20052035
_stepperDEC->moveTo(_decParkingPos);
20062036
_totalDECMove = 1.0f * _stepperDEC->distanceToGo();
20072037
_totalRAMove = 1.0f * _stepperRA->distanceToGo();
2008-
LOGV5(DEBUG_MOUNT|DEBUG_STEPPERS,F("Mount::Loop: Park Position is R:%l D:%l, TotalMove is R:%f, D:%f"), _raParkingPos,_decParkingPos,_totalRAMove, _totalDECMove);
2038+
LOGV5(DEBUG_MOUNT|DEBUG_STEPPERS,F("Mount::Loop: Park Position is R:%l D:%l, TotalMove is R:%f, D:%f"), _raParkingPos, _decParkingPos,_totalRAMove, _totalDECMove);
20092039
if ((_stepperDEC->distanceToGo() != 0) || (_stepperRA->distanceToGo() != 0)) {
20102040
_mountStatus |= STATUS_PARKING_POS | STATUS_SLEWING;
20112041
}
@@ -2026,17 +2056,8 @@ void Mount::loop() {
20262056

20272057
// Make sure we do one last update when the steppers have stopped.
20282058
displayStepperPosition();
2029-
if (!inSerialControl) {
2030-
_lcdMenu->updateDisplay();
2031-
}
20322059
}
20332060
}
2034-
2035-
if ((_bootComplete) && (now - _lastTrackingPrint > 200)) {
2036-
_lcdMenu->printAt(15,0, isSlewingTRK() ? '&' : '`');
2037-
_lastTrackingPrint = now;
2038-
}
2039-
20402061
}
20412062

20422063
_stepperWasRunning = raStillRunning || decStillRunning;
@@ -2051,12 +2072,18 @@ void Mount::bootComplete() {
20512072
_bootComplete = true;
20522073
}
20532074

2075+
bool Mount::isBootComplete(){
2076+
return _bootComplete;
2077+
}
2078+
2079+
2080+
20542081
/////////////////////////////////
20552082
//
20562083
// setParkingPosition
20572084
//
20582085
/////////////////////////////////
2059-
void Mount::setParkingPosition(){
2086+
void Mount::setParkingPosition() {
20602087
_raParkingPos = _stepperRA->currentPosition() - _stepperTRK->currentPosition();
20612088
_decParkingPos = _stepperDEC->currentPosition();
20622089

@@ -2066,6 +2093,42 @@ void Mount::setParkingPosition(){
20662093
writePersistentData(EEPROM_DEC_PARKING_POS, _decParkingPos);
20672094
}
20682095

2096+
/////////////////////////////////
2097+
//
2098+
// setDecLimitPosition
2099+
//
2100+
/////////////////////////////////
2101+
void Mount::setDecLimitPosition(bool upper) {
2102+
if (upper) {
2103+
_decUpperLimit = _stepperDEC->currentPosition();
2104+
writePersistentData(EEPROM_DEC_UPPER_LIMIT, _decUpperLimit);
2105+
LOGV3(DEBUG_MOUNT,F("Mount::setDecLimitPosition(Upper): limit DEC: %l -> %l"), _decLowerLimit, _decUpperLimit);
2106+
}
2107+
else{
2108+
_decLowerLimit = _stepperDEC->currentPosition();
2109+
writePersistentData(EEPROM_DEC_LOWER_LIMIT, _decLowerLimit);
2110+
LOGV3(DEBUG_MOUNT,F("Mount::setDecLimitPosition(Lower): limit DEC: %l -> %l"), _decLowerLimit, _decUpperLimit);
2111+
}
2112+
}
2113+
2114+
/////////////////////////////////
2115+
//
2116+
// clearDecLimitPosition
2117+
//
2118+
/////////////////////////////////
2119+
void Mount::clearDecLimitPosition(bool upper) {
2120+
if (upper) {
2121+
_decUpperLimit = 0;
2122+
writePersistentData(EEPROM_DEC_UPPER_LIMIT, _decUpperLimit);
2123+
LOGV3(DEBUG_MOUNT,F("Mount::clearDecLimitPosition(Upper): limit DEC: %l -> %l"), _decLowerLimit, _decUpperLimit);
2124+
}
2125+
else{
2126+
_decLowerLimit = 0;
2127+
writePersistentData(EEPROM_DEC_LOWER_LIMIT, _decLowerLimit);
2128+
LOGV3(DEBUG_MOUNT,F("Mount::clearDecLimitPosition(Lower): limit DEC: %l -> %l"), _decLowerLimit, _decUpperLimit);
2129+
}
2130+
}
2131+
20692132
/////////////////////////////////
20702133
//
20712134
// setHome

Software/Arduino code/OpenAstroTracker/src/Mount.hpp

Lines changed: 14 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,8 @@
5353
#define EEPROM_ROLL_OFFSET 8
5454
#define EEPROM_RA_PARKING_POS 9
5555
#define EEPROM_DEC_PARKING_POS 10
56+
#define EEPROM_DEC_LOWER_LIMIT 11
57+
#define EEPROM_DEC_UPPER_LIMIT 12
5658

5759
//////////////////////////////////////////////////////////////////
5860
//
@@ -206,6 +208,12 @@ class Mount {
206208
// Set the current stepper positions to be parking position.
207209
void setParkingPosition();
208210

211+
// Set the DEC limit position to the current stepper position. If upper is true, sets the upper limit, else the lower limit.
212+
void setDecLimitPosition(bool upper);
213+
214+
// Clear the DEC limit position. If upper is true, clears upper limit, else the lower limit.
215+
void clearDecLimitPosition(bool upper);
216+
209217
// Auto Home with TMC2209 UART
210218
#if (RA_DRIVER_TYPE == DRIVER_TYPE_TMC2209_UART) || (DEC_DRIVER_TYPE == DRIVER_TYPE_TMC2209_UART)
211219
void startFindingHomeRA();
@@ -261,7 +269,7 @@ class Mount {
261269
int getBacklashCorrection();
262270

263271
// Called when startup is complete and the mount needs to start updating steppers.
264-
void startTimerInterrupts();
272+
void startTimerInterrupts();
265273

266274
// Read the saved configuration from persistent storage
267275
void readConfiguration();
@@ -272,6 +280,9 @@ class Mount {
272280
// Get Mount configuration data
273281
String getMountHardwareInfo();
274282

283+
// Returns a flag indicating whether the mount is fully booted.
284+
bool isBootComplete();
285+
275286
// Let the mount know that the system has finished booting
276287
void bootComplete();
277288
private:
@@ -310,6 +321,8 @@ class Mount {
310321
int _moveRate;
311322
long _raParkingPos;
312323
long _decParkingPos;
324+
long _decLowerLimit;
325+
long _decUpperLimit;
313326

314327
#if USE_GYRO_LEVEL == 1
315328
float _pitchCalibrationAngle;

Software/Arduino code/OpenAstroTracker/src/a_inits.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -113,6 +113,7 @@ bool inStartup = false; // Start with a guided startup
113113

114114
// Serial control variables
115115
bool inSerialControl = false; // When the serial port is in control
116+
bool okToUpdateMenu = true; // Can be used to supress rendering the first line of the menu.
116117
bool quitSerialOnNextButtonRelease = false; // Used to detect SELECT button to quit Serial mode.
117118

118119
// Global variables

Software/Arduino code/OpenAstroTracker/src/c65_startup.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@ void startupIsCompleted() {
3939

4040
startupState = StartupCompleted;
4141
inStartup = false;
42+
okToUpdateMenu = true;
4243

4344
mount.startSlewing(TRACKING);
4445

@@ -87,6 +88,7 @@ bool processStartupKeys() {
8788
#else
8889
startupState = StartupWaitForPoleCompletion;
8990
inStartup = false;
91+
okToUpdateMenu = false;
9092
lcdMenu.setCursor(0, 0);
9193
lcdMenu.printMenu("Home with ^~<>");
9294
lcdMenu.setActive(Control_Menu);

Software/Arduino code/OpenAstroTracker/src/c75_menuCTRL.hpp

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -121,15 +121,11 @@ bool processControlKeys()
121121
mount.startSlewing(TRACKING);
122122
}
123123

124-
// Set flag to prevent resetting zero point when moving over the menu items
125-
ctrlState = HIGHLIGHT_MANUAL;
126-
127124
#if SUPPORT_GUIDED_STARTUP == 1
128125
if (startupState == StartupWaitForPoleCompletion)
129126
{
130127
startupState = StartupPoleConfirmed;
131128
inStartup = true;
132-
ctrlState = HIGHLIGHT_MANUAL;
133129
}
134130
else
135131
#endif
@@ -138,6 +134,7 @@ bool processControlKeys()
138134
}
139135

140136
ctrlState = HIGHLIGHT_MANUAL;
137+
okToUpdateMenu = true;
141138
setZeroPoint = true;
142139
}
143140
else if (key == btnLEFT)
@@ -192,6 +189,7 @@ bool processControlKeys()
192189
else
193190
#endif
194191
{
192+
okToUpdateMenu = false;
195193
lcdMenu.setCursor(0, 0);
196194
lcdMenu.printMenu("Set home pos?");
197195
ctrlState = MANUAL_CONTROL_CONFIRM_HOME;

0 commit comments

Comments
 (0)