Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
101 changes: 101 additions & 0 deletions CLAUDE.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,101 @@
# CLAUDE.md

This file provides guidance to Claude Code (claude.ai/code) when working with code in this repository.

## Project Overview

OpenAstroTracker-Firmware is embedded C++ firmware for the OpenAstroTracker automated astronomy mount. It supports multiple hardware platforms (AVR ATmega2560 and ESP32) with various stepper motor drivers, display types, and accessories.

## Build System

PlatformIO is the build system. The project uses the Arduino framework.

### Common Commands

```shell
# Build for a specific board environment
pio run -e ramps
pio run -e esp32
pio run -e mksgenlv21
pio run -e mksgenlv2
pio run -e mksgenlv1
pio run -e oaeboardv1

# Upload firmware
pio run -e ramps -t upload

# Run unit tests (native platform)
pio test -e native

# Run matrix build (tests many configuration combinations across boards)
python matrix_build.py -b ramps # single board
python matrix_build.py # all boards

# Format code (clang-format v12 required, enforced by CI)
bash -c 'shopt -s nullglob globstar;GLOBIGNORE=./src/libs/TimerInterrupt/*; for i in ./{.,src/**,unit_tests,boards/**}/*.{c,cpp,h,hpp}; do clang-format -i $i; done'

# Debug (ATmega2560 only, uses avr-stub)
pio run -e ramps -t clean && piodebuggdb -e ramps

# Generate Meade command Wiki docs
python scripts/MeadeCommandParser.py
```

### Build Notes

- `-Werror` is enabled: all warnings are errors
- Uses ETL (Embedded Template Library) in non-STL mode (`-D ETL_NO_STL`), not the C++ standard library
- Optimization: `-O2` (production), `-Og` (debug)
- Monitor baud rate: 19200
- `src/libs/TimerInterrupt/` is excluded from formatting checks
- CI runs on every PR: build all boards, clang-format check, unit tests

## Architecture

### Configuration Hierarchy (evaluated in this order)

1. **`Configuration_local.hpp`** - User hardware config (not tracked by git). Generate at https://config.openastrotech.com/
2. **`Configuration_local_<board>.hpp`** - Board-specific local config variant
3. **`Configuration.hpp`** - Default values for anything not set in local config
4. **`Configuration_adv.hpp`** - Advanced settings (motor steps, speed, microstepping, TMC driver params)
5. **`Constants.hpp`** - System constants (board IDs, feature flag values). **Do not modify for user configuration.**

### Core Modules

- **`Mount` (src/Mount.hpp/cpp)** - Central controller. Manages stepper motors (RA, DEC, AZ, ALT, Focus), coordinate calculations, slewing, tracking, parking, and guiding. This is by far the largest module (~150KB source).
- **`MeadeCommandProcessor` (src/MeadeCommandProcessor.hpp/cpp)** - Serial command interface implementing the Meade LX200 protocol. Handles all external communication.
- **`EPROMStore` (src/EPROMStore.hpp/cpp)** - Platform-agnostic non-volatile storage abstraction (coordinates, calibration, motor config). Uses magic markers `0xCE`/`0xCF` for validation.
- **`b_setup.hpp`** - Arduino `setup()` implementation and hardware initialization.
- **`a_inits.hpp`** - Global variable initialization.

### Entry Point

`OpenAstroTracker-Firmware.ino` is the Arduino sketch entry point. It delegates to `src/a_inits.hpp` (globals) and `src/b_setup.hpp` (setup/loop).

### Stepper Control

Two modes depending on platform:

- **AVR (NEW_STEPPER_LIB)**: Interrupt-driven via Timer 3 (RA) and Timer 4 (DEC) at 2 kHz. Uses `InterruptAccelStepper` library. Configured via `StepperConfiguration.hpp`.
- **ESP32**: FreeRTOS task on Core 0 at 1 kHz (`stepperControlTask`). Core 1 runs `loop()` for serial/UI.

Both call `Mount::interruptLoop()` for step generation.

### Board Pin Definitions

Board-specific pin mappings live in `boards/<board_name>/pins_<board>.h`. Each board has its own directory.

### Display & UI

Optional LCD menu system (`LcdMenu`, `LcdButtons`) supporting multiple display types: direct LCD keypad, I2C LCD (MCP23008/MCP23017), and I2C SSD1306 OLED with joystick. An optional separate 128x64 info display shows real-time status.

## Key Conventions

- Primary branch: `develop`
- PRs must pass CI (build all boards + clang-format + unit tests)
- PR comments are resolved by OAT developers, not PR authors
- clang-format v12 is the enforced formatter (column limit: 140, Allman-style braces, 4-space indent, no tabs)
- Pointer alignment: right (`int *ptr`)
- Supported driver types: `DRIVER_TYPE_A4988_GENERIC`, `DRIVER_TYPE_TMC2209_STANDALONE`, `DRIVER_TYPE_TMC2209_UART`
- Supported stepper types: `STEPPER_TYPE_NONE`, `STEPPER_TYPE_ENABLED`
- Debug logging uses bit-flag levels (INFO, SERIAL, WIFI, MOUNT, MEADE, STEPPERS, EEPROM, GYRO, GPS, FOCUS, etc.)
4 changes: 4 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
@@ -1,3 +1,7 @@
**V1.13.20 - Updates**
- Code improvement to stability, multithreading, memory usage, user input, etc.
- Fixed a bug that caused Latitude to overwrite Longitude in the EEPROM code.

**V1.13.19 - Updates**
- Support inverting and mirroring InfoDisplays.

Expand Down
2 changes: 1 addition & 1 deletion Version.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,4 +3,4 @@
// Also, numbers are interpreted as simple numbers. _ __ _
// So 1.8 is actually 1.08, meaning that 1.12 is a later version than 1.8. \_(..)_/

#define VERSION "V1.13.19"
#define VERSION "V1.13.20"
10 changes: 5 additions & 5 deletions src/DayTime.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,11 +238,11 @@ const char *DayTime::ToString() const
*p++ = '0' + (secs / 10);
}

*p++ = '0' + (secs % 10);
*p++ = ' ';
*p++ = '(';
strcpy(p, String(this->getTotalHours(), 5).c_str());
strcat(p, ")");
*p++ = '0' + (secs % 10);
size_t used = p - achBuf;
size_t remaining = sizeof(achBuf) - used;
String floatStr = String(this->getTotalHours(), 5);
snprintf(p, remaining, " (%s)", floatStr.c_str());
return achBuf;
}
void DayTime::printTwoDigits(char *achDegs, int num) const
Expand Down
14 changes: 6 additions & 8 deletions src/Declination.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,14 +84,12 @@ const char *Declination::ToString() const
{
ToDisplayString('*', ':');

char *p = achBufDeg + strlen(achBufDeg);

*p++ = ' ';
*p++ = '(';
strcpy(p, String(inNorthernHemisphere ? 90 - fabsf(getTotalHours()) : -90 + fabsf(getTotalHours()), 4).c_str());
strcat(p, ", ");
strcat(p, String(getTotalHours(), 4).c_str());
strcat(p, ")");
size_t used = strlen(achBufDeg);
size_t remaining = sizeof(achBufDeg) - used;
float displayVal = inNorthernHemisphere ? 90 - fabsf(getTotalHours()) : -90 + fabsf(getTotalHours());
String valStr = String(displayVal, 4);
String hoursStr = String(getTotalHours(), 4);
snprintf(achBufDeg + used, remaining, " (%s, %s)", valStr.c_str(), hoursStr.c_str());

return achBufDeg;
}
Expand Down
2 changes: 1 addition & 1 deletion src/EPROMStore.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -168,7 +168,7 @@ class EEPROMStore
LATITUDE_ADDR = 12,
_LATITUDE_ADDR_1 = 13, // Int16
LONGITUDE_ADDR = 14,
_LONGITUDE_ADDR_1 = 13, // Int16
_LONGITUDE_ADDR_1 = 15, // Int16
LCD_BRIGHTNESS_ADDR = 16, // Uint8
PITCH_OFFSET_ADDR = 17,
_PITCH_OFFSET_ADDR_1 = 18, // Uint16
Expand Down
4 changes: 2 additions & 2 deletions src/EndSwitches.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,10 @@ enum EndSwitchState
class EndSwitch
{
private:
EndSwitchState _state;
volatile EndSwitchState _state;
Mount *_pMount;
StepperAxis _axis;
long _posWhenTriggered;
volatile long _posWhenTriggered;
int _activeState;
int _inactiveState;
int _dir;
Expand Down
89 changes: 64 additions & 25 deletions src/Gyro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,11 @@ POP_NO_WARNINGS
* */

bool Gyro::isPresent(false);
float Gyro::_pitchSamples[WINDOW_SIZE] = {};
float Gyro::_rollSamples[WINDOW_SIZE] = {};
int Gyro::_ringIndex(0);
int Gyro::_samplesCollected(0);
unsigned long Gyro::_lastSampleTime(0);

void Gyro::startup()
/* Starts up the MPU-6050 device.
Expand Down Expand Up @@ -54,6 +59,16 @@ void Gyro::startup()
Wire.write(6); // 5Hz bandwidth (lowest) for smoothing
Wire.endTransmission(true);

// Reset moving average state
for (int i = 0; i < WINDOW_SIZE; i++)
{
_pitchSamples[i] = 0;
_rollSamples[i] = 0;
}
_ringIndex = 0;
_samplesCollected = 0;
_lastSampleTime = 0;

LOG(DEBUG_INFO, "[GYRO]:: Started");
}

Expand All @@ -66,45 +81,69 @@ void Gyro::shutdown()
// Nothing to do
}

void Gyro::collectSample()
/* Reads one accelerometer sample and stores it in the circular buffer.
*/
{
// Execute 6 byte read from MPU6050_REG_ACCEL_XOUT_H
Wire.beginTransmission(MPU6050_I2C_ADDR);
Wire.write(MPU6050_REG_ACCEL_XOUT_H);
Wire.endTransmission(false);
Wire.requestFrom(MPU6050_I2C_ADDR, 6, 1); // Read 6 registers total, each axis value is stored in 2 registers
int16_t AcX = Wire.read() << 8 | Wire.read(); // X-axis value
int16_t AcY = Wire.read() << 8 | Wire.read(); // Y-axis value
int16_t AcZ = Wire.read() << 8 | Wire.read(); // Z-axis value

// Calculating the Pitch angle (rotation around Y-axis)
_pitchSamples[_ringIndex] = atan2f(-1.0f * AcX, sqrtf((float) AcY * AcY + (float) AcZ * AcZ)) * 180.0f / static_cast<float>(PI);
// Calculating the Roll angle (rotation around X-axis)
_rollSamples[_ringIndex] = atan2f(-1.0f * AcY, sqrtf((float) AcX * AcX + (float) AcZ * AcZ)) * 180.0f / static_cast<float>(PI);

_ringIndex = (_ringIndex + 1) % WINDOW_SIZE;
if (_samplesCollected < WINDOW_SIZE)
{
_samplesCollected++;
}
}

angle_t Gyro::getCurrentAngles()
/* Returns roll & tilt angles from MPU-6050 device in angle_t object in degrees.
If MPU-6050 is not found then returns {0,0}.
Non-blocking: collects one sample per call if at least SAMPLE_INTERVAL ms
have elapsed since the last sample. Returns the moving average over the
last WINDOW_SIZE samples.
*/
{
const int windowSize = 16;
// Read the accelerometer data
struct angle_t result;
result.pitchAngle = 0;
result.rollAngle = 0;
angle_t result;

if (!isPresent)
return result; // Gyro is not available
return result;

unsigned long now = millis();
if (now - _lastSampleTime >= SAMPLE_INTERVAL)
{
_lastSampleTime = now;
collectSample();
}

for (int i = 0; i < windowSize; i++)
if (_samplesCollected == 0)
return result;

float pitchSum = 0;
float rollSum = 0;
for (int i = 0; i < _samplesCollected; i++)
{
// Execute 6 byte read from MPU6050_REG_WHO_AM_I
Wire.beginTransmission(MPU6050_I2C_ADDR);
Wire.write(MPU6050_REG_ACCEL_XOUT_H);
Wire.endTransmission(false);
Wire.requestFrom(MPU6050_I2C_ADDR, 6, 1); // Read 6 registers total, each axis value is stored in 2 registers
int16_t AcX = Wire.read() << 8 | Wire.read(); // X-axis value
int16_t AcY = Wire.read() << 8 | Wire.read(); // Y-axis value
int16_t AcZ = Wire.read() << 8 | Wire.read(); // Z-axis value

// Calculating the Pitch angle (rotation around Y-axis)
result.pitchAngle += ((atanf(-1 * AcX / sqrtf(powf(AcY, 2) + powf(AcZ, 2))) * 180.0f / static_cast<float>(PI)) * 2.0f) / 2.0f;
// Calculating the Roll angle (rotation around X-axis)
result.rollAngle += ((atanf(-1 * AcY / sqrtf(powf(AcX, 2) + powf(AcZ, 2))) * 180.0f / static_cast<float>(PI)) * 2.0f) / 2.0f;

delay(10); // Decorrelate measurements
pitchSum += _pitchSamples[i];
rollSum += _rollSamples[i];
}
result.pitchAngle = pitchSum / _samplesCollected;
result.rollAngle = rollSum / _samplesCollected;

result.pitchAngle /= windowSize;
result.rollAngle /= windowSize;
#if GYRO_AXIS_SWAP == 1
float temp = result.pitchAngle;
result.pitchAngle = result.rollAngle;
result.rollAngle = temp;
#endif

return result;
}

Expand Down
13 changes: 12 additions & 1 deletion src/Gyro.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@ class Gyro
static float getCurrentTemperature();

private:
static void collectSample();

// MPU6050 constants
enum
{
Expand All @@ -28,6 +30,15 @@ class Gyro
MPU6050_REG_WHO_AM_I = 0x75
};

static bool isPresent; // True if gyro correctly detected on startup
// Use about 72 bytes of RAM for the moving average buffer
static const int WINDOW_SIZE = 8; // Number of samples to keep for moving average
static const unsigned long SAMPLE_INTERVAL = 5; // ms between samples

static bool isPresent;
static float _pitchSamples[WINDOW_SIZE];
static float _rollSamples[WINDOW_SIZE];
static int _ringIndex;
static int _samplesCollected; // Counts up to WINDOW_SIZE, then stays there
static unsigned long _lastSampleTime;
};
#endif
Loading
Loading