Skip to content

Commit 92f58df

Browse files
V1.7.25.Az01 - Updates
- Added support for the Altitude motor (using pins 46, 48, 50, and 52)
1 parent 35827ca commit 92f58df

File tree

4 files changed

+95
-21
lines changed

4 files changed

+95
-21
lines changed

Software/Arduino code/OpenAstroTracker/MeadeCommandProcessor.cpp

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -319,6 +319,14 @@
319319
// Get the current LST of the mount.
320320
// Returns: HHMMSS
321321
//
322+
// :XGZ#
323+
// Get speed of Azimuth motor
324+
// Returns: n.nn
325+
//
326+
// :XGI#
327+
// Get speed of Altitude motor
328+
// Returns: n.nn
329+
//
322330
// :XSBn#
323331
// Set Backlash correction steps
324332
// Sets the number of steps the RA stepper motor needs to overshoot and backtrack when slewing east.
@@ -358,6 +366,14 @@
358366
// Set the speed of the DEC motor, immediately. Must be in manual slewing mode.
359367
// Returns: nothing
360368
//
369+
// :XSZn.nn#
370+
// Set speed of Azimuth motor
371+
// Returns: nothing
372+
//
373+
// :XSIn.nn#
374+
// Set speed of ALtitude motor
375+
// Returns: nothing
376+
//
361377
/////////////////////////////////////////////////////////////////////////////////////////
362378

363379
MeadeCommandProcessor* MeadeCommandProcessor::_instance = nullptr;
@@ -724,6 +740,12 @@ String MeadeCommandProcessor::handleMeadeExtraCommands(String inCmd) {
724740
else if (inCmd[1] == 'T') {
725741
return String(_mount->getSpeed(TRACKING), 7) + "#";
726742
}
743+
else if (inCmd[1] == 'Z') {
744+
return String(_mount->getSpeed(AZIMUTH_STEPS), 2) + "#";
745+
}
746+
else if (inCmd[1] == 'I') {
747+
return String(_mount->getSpeed(ALTITUDE_STEPS), 2) + "#";
748+
}
727749
else if (inCmd[1] == 'B') {
728750
return String(_mount->getBacklashCorrection()) + "#";
729751
}
@@ -770,6 +792,9 @@ String MeadeCommandProcessor::handleMeadeExtraCommands(String inCmd) {
770792
else if (inCmd[1] == 'Z') {
771793
_mount->setSpeed(AZIMUTH_STEPS, inCmd.substring(2).toFloat());
772794
}
795+
else if (inCmd[1] == 'I') {
796+
_mount->setSpeed(ALTITUDE_STEPS, inCmd.substring(2).toFloat());
797+
}
773798
else if (inCmd[1] == 'B') {
774799
_mount->setBacklashCorrection(inCmd.substring(2).toInt());
775800
}

Software/Arduino code/OpenAstroTracker/Mount.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -315,6 +315,10 @@ void Mount::configureDECStepper(byte stepMode, byte pin1, byte pin2, byte pin3,
315315
_stepperAZ ->setSpeed(0);
316316
_stepperAZ ->setMaxSpeed(300);
317317
_stepperAZ->setAcceleration(400);
318+
_stepperALT = new AccelStepper(FULLSTEP, 46, 50, 48, 52);
319+
_stepperALT ->setSpeed(0);
320+
_stepperALT ->setMaxSpeed(300);
321+
_stepperALT->setAcceleration(400);
318322
#endif
319323
}
320324
#endif
@@ -853,6 +857,9 @@ void Mount::setSpeed(int which, float speed) {
853857
else if (which == AZIMUTH_STEPS) {
854858
_stepperAZ->setSpeed(speed);
855859
}
860+
else if (which == ALTITUDE_STEPS) {
861+
_stepperALT->setSpeed(speed);
862+
}
856863
#endif
857864
}
858865

@@ -1240,6 +1247,7 @@ void Mount::interruptLoop()
12401247

12411248
#if AZIMUTH_MOTOR
12421249
_stepperAZ->runSpeed();
1250+
_stepperALT->runSpeed();
12431251
#endif
12441252

12451253
}

Software/Arduino code/OpenAstroTracker/Mount.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@
3333
#define SPEED_FACTOR_DECIMALS 3
3434
#define BACKLASH_CORRECTION 4
3535
#define AZIMUTH_STEPS 5
36+
#define ALTITUDE_STEPS 6
3637

3738
//////////////////////////////////////////////////////////////////
3839
//
@@ -252,6 +253,7 @@ class Mount {
252253

253254
#if AZIMUTH_MOTOR
254255
AccelStepper* _stepperAZ;
256+
AccelStepper* _stepperALT;
255257
#endif
256258

257259
unsigned long _guideEndTime;

Software/Arduino code/OpenAstroTracker/c76_menuCAL.hpp

Lines changed: 60 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@
1313
#define HIGHLIGHT_RA_STEPS 4
1414
#define HIGHLIGHT_DEC_STEPS 5
1515
#define HIGHLIGHT_BACKLASH_STEPS 6
16-
#define HIGHLIGHT_AZIMUTH_CONTROL 7
16+
#define HIGHLIGHT_AZIMUTH_ALTITUDE_CONTROL 7
1717
#define HIGHLIGHT_LAST 7
1818

1919
// Polar calibration goes through these three states:
@@ -45,7 +45,7 @@
4545
// #define BACKLIGHT_CALIBRATION 20
4646

4747
// Azimuth control only has one state, allowing you to move the motor UP and DOWN
48-
#define AZIMUTH_CONTROL 20
48+
#define AZIMUTH_ALTITUDE_CONTROL 20
4949

5050
// Start off with Polar Alignment higlighted.
5151
byte calState = HIGHLIGHT_FIRST;
@@ -68,6 +68,8 @@ int BacklashSteps = 0;
6868
// The speed of the Azimuth Motor (scaled from 0-100)
6969
int AzimuthSpeed = 0;
7070
int lastAzimuthSpeed = 0;
71+
int AltitudeSpeed = 0;
72+
int lastAltitudeSpeed = 0;
7173

7274
// The brightness of the backlight of the LCD shield.
7375
// int Brightness = 255;
@@ -148,7 +150,7 @@ bool processCalibrationKeys() {
148150
calDelay = 150;
149151
}
150152
}
151-
else if (calState == AZIMUTH_CONTROL) {
153+
else if (calState == AZIMUTH_ALTITUDE_CONTROL) {
152154
if (lcdButtons.currentState() == btnLEFT) {
153155
// Speed up to the left
154156
if (AzimuthSpeed < 100) {
@@ -159,7 +161,7 @@ bool processCalibrationKeys() {
159161
calDelay = max(2, 0.98 * calDelay);
160162
checkForKeyChange = false;
161163
}
162-
else if (lcdButtons.currentState() == btnRIGHT) {
164+
if (lcdButtons.currentState() == btnRIGHT) {
163165
// Speed up to the right
164166
if (AzimuthSpeed > -100) {
165167
AzimuthSpeed -= 1; //0.0001;
@@ -169,18 +171,51 @@ bool processCalibrationKeys() {
169171
calDelay = max(2, 0.98 * calDelay);
170172
checkForKeyChange = false;
171173
}
172-
else {
173-
// No more buttons pressed, decelerate at 3% per cycle
174+
// If neither Left nor Right is pressed...
175+
if ((lcdButtons.currentState() != btnRIGHT) && (lcdButtons.currentState() != btnLEFT)) {
176+
// ... decelerate at 3% per cycle
174177
if (AzimuthSpeed > 0) {
175178
AzimuthSpeed = adjustClamp(AzimuthSpeed, -3, 0, 100);
176179
}
177180
else if (AzimuthSpeed < 0) {
178181
AzimuthSpeed = adjustClamp(AzimuthSpeed, 3, -100, 0);
179182
}
180-
else {
183+
}
184+
185+
if (lcdButtons.currentState() == btnUP) {
186+
// Speed up to the left
187+
if (AltitudeSpeed < 100) {
188+
AltitudeSpeed += 1; //0.0001;
189+
}
190+
191+
// Accelerate speed increase over time
192+
calDelay = max(2, 0.98 * calDelay);
193+
checkForKeyChange = false;
194+
}
195+
if (lcdButtons.currentState() == btnDOWN) {
196+
// Speed up to the right
197+
if (AltitudeSpeed > -100) {
198+
AltitudeSpeed -= 1; //0.0001;
199+
}
200+
201+
// Accelerate speed increase over time
202+
calDelay = max(2, 0.98 * calDelay);
203+
checkForKeyChange = false;
204+
}
205+
// If neither Up nor Down is pressed...
206+
if ((lcdButtons.currentState() != btnUP) && (lcdButtons.currentState() != btnDOWN)) {
207+
// ... decelerate at 3% per cycle
208+
if (AltitudeSpeed > 0) {
209+
AltitudeSpeed = adjustClamp(AltitudeSpeed, -3, 0, 100);
210+
}
211+
else if (AltitudeSpeed < 0) {
212+
AltitudeSpeed = adjustClamp(AltitudeSpeed, 3, -100, 0);
213+
}
214+
}
215+
216+
if ((AzimuthSpeed == 0) && (AltitudeSpeed == 0)) {
181217
// Once we're stopped, set the initial key delay back to 100ms
182218
calDelay = 100;
183-
}
184219
}
185220

186221
// If we changed speeds, tell the mount motor
@@ -189,6 +224,11 @@ bool processCalibrationKeys() {
189224
lastAzimuthSpeed = AzimuthSpeed;
190225
}
191226

227+
if (AltitudeSpeed != lastAltitudeSpeed) {
228+
mount.setSpeed(ALTITUDE_STEPS, 300.0 * AltitudeSpeed / 100.0);
229+
lastAltitudeSpeed = AltitudeSpeed;
230+
}
231+
192232
mount.delay(calDelay);
193233
}
194234
else if (calState == RA_STEP_CALIBRATION) {
@@ -325,15 +365,14 @@ bool processCalibrationKeys() {
325365
}
326366
break;
327367

328-
case AZIMUTH_CONTROL:
368+
case AZIMUTH_ALTITUDE_CONTROL:
329369
{
330-
// UP and DOWN are handled above
370+
// UP, DOWN, LEFT, and RIGHT are handled above
331371
if (key == btnSELECT) {
332-
calState = HIGHLIGHT_AZIMUTH_CONTROL;
333-
}
334-
else if (key == btnRIGHT) {
335-
lcdMenu.setNextActive();
336-
calState = HIGHLIGHT_AZIMUTH_CONTROL;
372+
// Make sure motors are stoppped!
373+
mount.setSpeed(AZIMUTH_STEPS, 0);
374+
mount.setSpeed(ALTITUDE_STEPS, 0);
375+
calState = HIGHLIGHT_AZIMUTH_ALTITUDE_CONTROL;
337376
}
338377
}
339378
break;
@@ -501,14 +540,14 @@ bool processCalibrationKeys() {
501540
}
502541
break;
503542

504-
case HIGHLIGHT_AZIMUTH_CONTROL:
543+
case HIGHLIGHT_AZIMUTH_ALTITUDE_CONTROL:
505544
{
506545
if (key == btnDOWN)
507546
gotoNextHighlightState(1);
508547
if (key == btnUP)
509548
gotoNextHighlightState(-1);
510549
else if (key == btnSELECT)
511-
calState = AZIMUTH_CONTROL;
550+
calState = AZIMUTH_ALTITUDE_CONTROL;
512551
else if (key == btnRIGHT) {
513552
lcdMenu.setNextActive();
514553
calState = HIGHLIGHT_FIRST;
@@ -553,8 +592,8 @@ void printCalibrationSubmenu()
553592
else if (calState == HIGHLIGHT_BACKLASH_STEPS) {
554593
lcdMenu.printMenu(">Backlash Adjust");
555594
}
556-
else if (calState == HIGHLIGHT_AZIMUTH_CONTROL) {
557-
lcdMenu.printMenu(">Azimuth Control");
595+
else if (calState == HIGHLIGHT_AZIMUTH_ALTITUDE_CONTROL) {
596+
lcdMenu.printMenu(">Az/Alt Control");
558597
}
559598
// else if (calState == HIGHLIGHT_BACKLIGHT) {
560599
// lcdMenu.printMenu(">LCD Brightness");
@@ -589,8 +628,8 @@ void printCalibrationSubmenu()
589628
sprintf(scratchBuffer, "Backlash: %d", BacklashSteps);
590629
lcdMenu.printMenu(scratchBuffer);
591630
}
592-
else if (calState == AZIMUTH_CONTROL) {
593-
sprintf(scratchBuffer, "AzimuthSpd: %d%%", AzimuthSpeed);
631+
else if (calState == AZIMUTH_ALTITUDE_CONTROL) {
632+
sprintf(scratchBuffer, "Az/Alt: %d%% %d%%", AzimuthSpeed, AltitudeSpeed);
594633
lcdMenu.printMenu(scratchBuffer);
595634
}
596635
// else if (calState == BACKLIGHT_CALIBRATION) {

0 commit comments

Comments
 (0)