Skip to content

Commit 6f8f4ad

Browse files
V1.8.11 - Updates
- Added support for electronic levelling via MPU-6050 module (CAL menu) (thanks to Marcel Isler for initial code) - Disabled AzAlt stepper motors after leaving CAL menu - Moved an overlapping EEPROM storage space (brightness, not used)
1 parent 1aff4c6 commit 6f8f4ad

File tree

9 files changed

+854
-327
lines changed

9 files changed

+854
-327
lines changed

Software/Arduino code/OpenAstroTracker/Configuration.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@
1818
=======================================================================================================================================
1919
*/
2020

21-
String version = "V1.8.10";
21+
String version = "V1.8.11";
2222

2323
///////////////////////////////////////////////////////////////////////////
2424
// Also use Configuration_adv for further adjustments!

Software/Arduino code/OpenAstroTracker/Configuration_adv.hpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -133,6 +133,8 @@
133133
#define ALTITUDE_ARC_SECONDS_PER_STEP (0.61761f)
134134
#define ALTITUDE_STEPS_PER_ARC_MINUTE (60.0f/ALTITUDE_ARC_SECONDS_PER_STEP)
135135

136+
137+
136138
//
137139
// Set this to 1 if you are using a NEO6m GPS module for HA/LST and location automatic determination.
138140
// GPS uses Serial1 by default, which is pins 18/19 on Mega. Change in configuration_adv.hpp
@@ -141,6 +143,16 @@
141143

142144

143145

146+
//
147+
// Set this to 1 if you are using a MPU6050 electronic level
148+
// Wire the board to 20/21 on Mega. Change in configuration_adv.hpp
149+
#define GYRO_LEVEL 0
150+
151+
// Set this to 1 if your gyro is mounted such that roll and pitch are in the wrong direction
152+
#define GYRO_AXIS_SWAP 0
153+
154+
155+
144156
#if HEADLESS_CLIENT == 0 // <-- Ignore this line
145157
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
146158
// ///
Lines changed: 77 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,77 @@
1+
#include "Configuration_adv.hpp"
2+
3+
#if GYRO_LEVEL == 1
4+
#include <Wire.h> // I2C communication library
5+
6+
#include "Utility.hpp"
7+
#include "Gyro.hpp"
8+
9+
const int MPU = 0x68; // I2C address of the MPU6050 accelerometer
10+
11+
int16_t Gyro::AcX, Gyro::AcY, Gyro::AcZ;
12+
int16_t Gyro::AcXOffset, Gyro::AcYOffset, Gyro::AcZOffset;
13+
14+
static void Gyro::startup()
15+
{
16+
// Initialize interface to the MPU6050
17+
LOGV1(DEBUG_INFO, "GYRO:: Starting");
18+
Wire.begin();
19+
Wire.beginTransmission(MPU);
20+
Wire.write(0x6B);
21+
Wire.write(0);
22+
Wire.endTransmission(true);
23+
24+
// read the values 100 times for them to stabilize
25+
for (int i = 0; i < 100; i++)
26+
{
27+
Wire.beginTransmission(MPU);
28+
Wire.write(0x3B); // Start with register 0x3B (ACCEL_XOUT_H)
29+
Wire.endTransmission(false);
30+
Wire.requestFrom(MPU, 6, true); // Read 6 registers total, each axis value is stored in 2 registers
31+
AcX = Wire.read() << 8 | Wire.read(); // X-axis value
32+
AcY = Wire.read() << 8 | Wire.read(); // Y-axis value
33+
AcZ = Wire.read() << 8 | Wire.read(); // Z-axis value
34+
}
35+
LOGV1(DEBUG_INFO, "GYRO:: Started");
36+
}
37+
38+
static void Gyro::shutdown()
39+
{
40+
LOGV1(DEBUG_INFO, "GYRO: Shutdown");
41+
Wire.end();
42+
}
43+
44+
static angle_t Gyro::getCurrentAngles()
45+
{
46+
const int windowSize = 16;
47+
// Read the accelerometer data
48+
struct angle_t result;
49+
result.pitchAngle = 0;
50+
result.rollAngle = 0;
51+
for (int i = 0; i < windowSize; i++)
52+
{
53+
Wire.beginTransmission(MPU);
54+
Wire.write(0x3B); // Start with register 0x3B (ACCEL_XOUT_H)
55+
Wire.endTransmission(false);
56+
Wire.requestFrom(MPU, 6, true); // Read 6 registers total, each axis value is stored in 2 registers
57+
AcX = Wire.read() << 8 | Wire.read(); // X-axis value
58+
AcY = Wire.read() << 8 | Wire.read(); // Y-axis value
59+
AcZ = Wire.read() << 8 | Wire.read(); // Z-axis value
60+
61+
// Calculating the Pitch angle (rotation around Y-axis)
62+
result.pitchAngle += ((atan(-1 * AcX / sqrt(pow(AcY, 2) + pow(AcZ, 2))) * 180.0 / PI) * 2.0) / 2.0;
63+
// Calculating the Roll angle (rotation around X-axis)
64+
result.rollAngle += ((atan(-1 * AcY / sqrt(pow(AcX, 2) + pow(AcZ, 2))) * 180.0 / PI) * 2.0) / 2.0;
65+
}
66+
67+
result.pitchAngle /= windowSize;
68+
result.rollAngle /= windowSize;
69+
#if GYRO_AXIS_SWAP == 1
70+
float temp = result.pitchAngle;
71+
result.pitchAngle = result.rollAngle;
72+
result.rollAngle = temp;
73+
#endif
74+
return result;
75+
}
76+
77+
#endif
Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
#pragma once
2+
3+
#include "Configuration_adv.hpp"
4+
5+
#if GYRO_LEVEL == 1
6+
struct angle_t { float pitchAngle; float rollAngle; };
7+
8+
class Gyro
9+
{
10+
public:
11+
static void startup();
12+
static void shutdown();
13+
static angle_t getCurrentAngles();
14+
15+
private:
16+
static int16_t AcX, AcY, AcZ;
17+
static int16_t AcXOffset, AcYOffset, AcZOffset;
18+
};
19+
#endif

Software/Arduino code/OpenAstroTracker/LcdMenu.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ LcdMenu::LcdMenu(byte cols, byte rows, int maxItems) : _lcd(8, 9, 4, 5, 6, 7) {
1919
_lastDisplay[1] = "";
2020
_menuItems = new MenuItem * [maxItems];
2121

22-
_brightness = EPROMStore::Storage()->read(11);
22+
_brightness = EPROMStore::Storage()->read(16);
2323
LOGV2(DEBUG_INFO, "LCD: Brightness from EEPROM is %d", _brightness);
2424
// pinMode(10, OUTPUT);
2525
// analogWrite(10, _brightness);
@@ -87,7 +87,7 @@ void LcdMenu::setBacklightBrightness(int level, bool persist) {
8787
LOGV2(DEBUG_INFO, "LCD: Wrote %d as brightness", _brightness );
8888
if (persist) {
8989
LOGV2(DEBUG_INFO, "LCD: Saving %d as brightness", (_brightness & 0x00FF));
90-
EPROMStore::Storage()->update(11, (byte)(_brightness & 0x00FF));
90+
EPROMStore::Storage()->update(16, (byte)(_brightness & 0x00FF));
9191
}
9292
}
9393

Software/Arduino code/OpenAstroTracker/Mount.cpp

Lines changed: 125 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -135,8 +135,10 @@ void Mount::readConfiguration()
135135
//
136136
// EEPROM storage location 5 must be 0xBE for the mount to read any data
137137
// Location 4 indicates what has been stored so far: 00000000
138-
// ^^^^^^
139-
// ||||||
138+
// ^^^^^^^^
139+
// ||||||||
140+
// Roll angle offset (19/20) -----+|||||||
141+
// Pitch angle offset (17/18) ------+||||||
140142
// Longitude (14/15) -------+|||||
141143
// Latitude (12/13) --------+||||
142144
// Backlash steps (10/11) ---------+|||
@@ -201,6 +203,26 @@ void Mount::readPersistentData()
201203
LOGV1(DEBUG_INFO,"Mount: EEPROM: No stored value for longitude");
202204
}
203205

206+
#if GYRO_LEVEL == 1
207+
if ((marker & 0xFF40) == 0xBE40) {
208+
uint16_t angleValue = EPROMStore::Storage()->readInt16(17, 18);
209+
_pitchCalibrationAngle = (((long)angleValue) - 16384) / 100.0;
210+
LOGV3(DEBUG_INFO,"Mount: EEPROM: Pitch Offset Marker OK! Pitch Offset is %x (%f)", angleValue, _pitchCalibrationAngle);
211+
}
212+
else{
213+
LOGV1(DEBUG_INFO,"Mount: EEPROM: No stored value for Pitch Offset");
214+
}
215+
216+
if ((marker & 0xFF80) == 0xBE80) {
217+
uint16_t angleValue = EPROMStore::Storage()->readInt16(19,20);
218+
_rollCalibrationAngle = (((long)angleValue) - 16384) / 100.0;
219+
LOGV3(DEBUG_INFO,"Mount: EEPROM: Roll Offset Marker OK! Roll Offset is %x (%f)", angleValue, _rollCalibrationAngle);
220+
}
221+
else {
222+
LOGV1(DEBUG_INFO,"Mount: EEPROM: No stored value for Roll Offset");
223+
}
224+
#endif
225+
204226
setSpeedCalibration(speed, false);
205227
}
206228

@@ -278,6 +300,25 @@ void Mount::writePersistentData(int which, int val)
278300
LOGV2(DEBUG_INFO,"Mount: EEPROM Write: Updating Longitude to %d", val);
279301
}
280302
break;
303+
case EEPROM_PITCH_OFFSET:
304+
{
305+
// ... set bit 7 to indicate pitch offset angle value has been written to 17/18
306+
flag |= 0x40;
307+
loByteLocation = 17;
308+
hiByteLocation = 18;
309+
LOGV2(DEBUG_INFO,"Mount: EEPROM Write: Updating Pitch Offset to %d", val);
310+
}
311+
break;
312+
case EEPROM_ROLL_OFFSET:
313+
{
314+
// ... set bit 8 to indicate pitch offset angle value has been written to 19/20
315+
flag |= 0x80;
316+
loByteLocation = 19;
317+
hiByteLocation = 20;
318+
LOGV2(DEBUG_INFO,"Mount: EEPROM Write: Updating Roll Offset to %d", val);
319+
}
320+
break;
321+
281322
}
282323

283324
LOGV3(DEBUG_INFO,"Mount: EEPROM Write: New Marker is 0xBE, flag is %x (%d)", flag, flag);
@@ -491,6 +532,54 @@ void Mount::setSpeedCalibration(float val, bool saveToStorage) {
491532
}
492533
}
493534

535+
#if GYRO_LEVEL == 1
536+
/////////////////////////////////
537+
//
538+
// getPitchCalibrationAngle
539+
//
540+
// The pitch value at which the mount is level
541+
/////////////////////////////////
542+
float Mount::getPitchCalibrationAngle()
543+
{
544+
return _pitchCalibrationAngle;
545+
}
546+
547+
/////////////////////////////////
548+
//
549+
// setPitchCalibrationAngle
550+
//
551+
/////////////////////////////////
552+
void Mount::setPitchCalibrationAngle(float angle)
553+
{
554+
uint16_t angleValue = (angle * 100) + 16384;
555+
writePersistentData(EEPROM_PITCH_OFFSET, angleValue);
556+
_pitchCalibrationAngle = angle;
557+
}
558+
559+
/////////////////////////////////
560+
//
561+
// getRollCalibration
562+
//
563+
// The roll value at which the mount is level
564+
/////////////////////////////////
565+
float Mount::getRollCalibrationAngle()
566+
{
567+
return _rollCalibrationAngle;
568+
}
569+
570+
/////////////////////////////////
571+
//
572+
// setRollCalibration
573+
//
574+
/////////////////////////////////
575+
void Mount::setRollCalibrationAngle(float angle)
576+
{
577+
uint16_t angleValue = (angle * 100) + 16384;
578+
writePersistentData(EEPROM_ROLL_OFFSET, angleValue);
579+
_rollCalibrationAngle = angle;
580+
}
581+
#endif
582+
494583
/////////////////////////////////
495584
//
496585
// getStepsPerDegree
@@ -589,6 +678,12 @@ String Mount::getMountHardwareInfo()
589678
ret += "NO_AZ_ALT,";
590679
#endif
591680

681+
#if GYRO_LEVEL == 1
682+
ret += "GYRO,";
683+
#else
684+
ret += "NO_GYRO,";
685+
#endif
686+
592687
return ret;
593688
}
594689

@@ -1046,14 +1141,14 @@ void Mount::goHome()
10461141
_slewingToHome = true;
10471142
}
10481143

1144+
#if AZIMUTH_ALTITUDE_MOTORS == 1
10491145
/////////////////////////////////
10501146
//
10511147
// moveBy
10521148
//
10531149
/////////////////////////////////
10541150
void Mount::moveBy(int direction, float arcMinutes)
10551151
{
1056-
#if AZIMUTH_ALTITUDE_MOTORS == 1
10571152
if (direction == AZIMUTH_STEPS){
10581153
int stepsToMove = 2.0f * arcMinutes * AZIMUTH_STEPS_PER_ARC_MINUTE;
10591154
_stepperAZ->move(stepsToMove);
@@ -1062,9 +1157,35 @@ void Mount::moveBy(int direction, float arcMinutes)
10621157
int stepsToMove = arcMinutes * ALTITUDE_STEPS_PER_ARC_MINUTE;
10631158
_stepperALT->move(stepsToMove);
10641159
}
1065-
#endif
10661160
}
10671161

1162+
/////////////////////////////////
1163+
//
1164+
// disableAzAltMotors
1165+
//
1166+
/////////////////////////////////
1167+
void Mount::disableAzAltMotors() {
1168+
_stepperALT->stop();
1169+
_stepperAZ->stop();
1170+
while (_stepperALT->isRunning() || _stepperAZ->isRunning()){
1171+
loop();
1172+
}
1173+
_stepperALT->disableOutputs();
1174+
_stepperAZ->disableOutputs();
1175+
}
1176+
1177+
/////////////////////////////////
1178+
//
1179+
// disableAzAltMotors
1180+
//
1181+
/////////////////////////////////
1182+
void Mount::enableAzAltMotors() {
1183+
_stepperALT->enableOutputs();
1184+
_stepperAZ->enableOutputs();
1185+
}
1186+
1187+
#endif
1188+
10681189
/////////////////////////////////
10691190
//
10701191
// mountStatus

0 commit comments

Comments
 (0)