Skip to content
Open
Show file tree
Hide file tree
Changes from 2 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"
8 changes: 3 additions & 5 deletions src/DayTime.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,11 +238,9 @@ 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;
snprintf(p, sizeof(achBuf) - used, " (%.5f)", this->getTotalHours());
return achBuf;
}
void DayTime::printTwoDigits(char *achDegs, int num) const
Expand Down
11 changes: 3 additions & 8 deletions src/Declination.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,14 +84,9 @@ 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);
float displayVal = inNorthernHemisphere ? 90 - fabsf(getTotalHours()) : -90 + fabsf(getTotalHours());
snprintf(achBufDeg + used, sizeof(achBufDeg) - used, " (%.4f, %.4f)", displayVal, getTotalHours());

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
12 changes: 10 additions & 2 deletions src/Gyro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,9 +91,17 @@ angle_t Gyro::getCurrentAngles()
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;
float denomPitch = sqrtf((float) AcY * AcY + (float) AcZ * AcZ);
if (denomPitch > 0.0f)
{
result.pitchAngle += atanf(-1.0f * AcX / denomPitch) * 180.0f / static_cast<float>(PI);
}
// 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;
float denomRoll = sqrtf((float) AcX * AcX + (float) AcZ * AcZ);
if (denomRoll > 0.0f)
{
result.rollAngle += atanf(-1.0f * AcY / denomRoll) * 180.0f / static_cast<float>(PI);
}

delay(10); // Decorrelate measurements
}
Expand Down
64 changes: 54 additions & 10 deletions src/MeadeCommandProcessor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1258,6 +1258,10 @@ String MeadeCommandProcessor::handleMeadeInit(String inCmd)
/////////////////////////////
String MeadeCommandProcessor::handleMeadeGetInfo(String inCmd)
{
if (inCmd.length() < 1)
{
return "";
}
char cmdOne = inCmd[0];
char cmdTwo = (inCmd.length() > 1) ? inCmd[1] : '\0';
char achBuffer[20];
Expand Down Expand Up @@ -1330,7 +1334,7 @@ String MeadeCommandProcessor::handleMeadeGetInfo(String inCmd)
case 'G': // :GG
{
int offset = _mount->getLocalUtcOffset();
sprintf(achBuffer, "%+03d#", -offset);
snprintf(achBuffer, sizeof(achBuffer), "%+03d#", -offset);
return String(achBuffer);
}
case 'a': // :Ga
Expand All @@ -1352,7 +1356,7 @@ String MeadeCommandProcessor::handleMeadeGetInfo(String inCmd)
case 'C': // :GC
{
LocalDate date = _mount->getLocalDate();
sprintf(achBuffer, "%02d/%02d/%02d#", date.month, date.day, date.year % 100);
snprintf(achBuffer, sizeof(achBuffer), "%02d/%02d/%02d#", date.month, date.day, date.year % 100);
return String(achBuffer);
}
case 'M': // :GM
Expand Down Expand Up @@ -1385,6 +1389,10 @@ String MeadeCommandProcessor::handleMeadeGetInfo(String inCmd)
/////////////////////////////
String MeadeCommandProcessor::handleMeadeGPSCommands(String inCmd)
{
if (inCmd.length() < 1)
{
return "0";
}
#if USE_GPS == 1
if (inCmd[0] == 'T')
{
Expand Down Expand Up @@ -1415,6 +1423,10 @@ String MeadeCommandProcessor::handleMeadeGPSCommands(String inCmd)
/////////////////////////////
String MeadeCommandProcessor::handleMeadeSyncControl(String inCmd)
{
if (inCmd.length() < 1)
{
return "FAIL#";
}
if (inCmd[0] == 'M') // :CM
{
_mount->syncPosition(_mount->targetRA(), _mount->targetDEC());
Expand All @@ -1429,6 +1441,10 @@ String MeadeCommandProcessor::handleMeadeSyncControl(String inCmd)
/////////////////////////////
String MeadeCommandProcessor::handleMeadeSetInfo(String inCmd)
{
if (inCmd.length() < 1)
{
return "0";
}
if ((inCmd[0] == 'd') && (inCmd.length() == 10))
{
// Set DEC
Expand Down Expand Up @@ -1561,6 +1577,10 @@ String MeadeCommandProcessor::handleMeadeSetInfo(String inCmd)
/////////////////////////////
String MeadeCommandProcessor::handleMeadeMovement(String inCmd)
{
if (inCmd.length() < 1)
{
return "";
}
LOG(DEBUG_MEADE, "[MEADE]: Process Move command: [%s]", inCmd.c_str());
if (inCmd[0] == 'S') // :MS#
{
Expand Down Expand Up @@ -1605,12 +1625,12 @@ String MeadeCommandProcessor::handleMeadeMovement(String inCmd)
direction = EAST;
else if (inCmd[1] == 'w')
direction = WEST;
int duration = (inCmd[2] - '0') * 1000 + (inCmd[3] - '0') * 100 + (inCmd[4] - '0') * 10 + (inCmd[5] - '0');
int duration = inCmd.substring(2, 6).toInt();
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This does a heap allocation, it's probably better to do

if (inCmd.length() == 6 && isdigit(inCmd[2]) && isdigit(inCmd[3]) && isdigit(inCmd[4]) && isdigit(inCmd[5]))
...
    int duration = (inCmd[2]-'0')*1000 +
                   (inCmd[3]-'0')*100 +
                   (inCmd[4]-'0')*10 +
                   (inCmd[5]-'0');

_mount->guidePulse(direction, duration);
return "";
}
}
else if (inCmd[0] == 'A')
else if (inCmd[0] == 'A' && inCmd.length() > 1)
{
LOG(DEBUG_MEADE, "[MEADE]: Move Az/Alt");

Expand Down Expand Up @@ -1730,6 +1750,10 @@ String MeadeCommandProcessor::handleMeadeMovement(String inCmd)
/////////////////////////////
String MeadeCommandProcessor::handleMeadeHome(String inCmd)
{
if (inCmd.length() < 1)
{
return "";
}
if (inCmd[0] == 'P') // :hP
{ // Park
_mount->park();
Expand Down Expand Up @@ -1765,6 +1789,10 @@ String MeadeCommandProcessor::handleMeadeDistance(String inCmd)
/////////////////////////////
String MeadeCommandProcessor::handleMeadeExtraCommands(String inCmd)
{
if (inCmd.length() < 1)
{
return "";
}
#if SUPPORT_DRIFT_ALIGNMENT == 1
// :XDmmm
if (inCmd[0] == 'D') // :XD
Expand Down Expand Up @@ -1874,8 +1902,8 @@ String MeadeCommandProcessor::handleMeadeExtraCommands(String inCmd)
{
long azPos, altPos;
_mount->getAZALTPositions(azPos, altPos);
char scratchBuffer[20];
sprintf(scratchBuffer, "%ld|%ld#", azPos, altPos);
char scratchBuffer[24];
snprintf(scratchBuffer, sizeof(scratchBuffer), "%ld|%ld#", azPos, altPos);
return String(scratchBuffer);
}
else if (inCmd[1] == 'C') // :XGCn.nn*m.mm#
Expand All @@ -1888,8 +1916,8 @@ String MeadeCommandProcessor::handleMeadeExtraCommands(String inCmd)
float raCoord = coords.substring(0, star).toFloat();
float decCoord = coords.substring(star + 1).toFloat();
_mount->calculateStepperPositions(raCoord, decCoord, raPos, decPos);
char scratchBuffer[20];
sprintf(scratchBuffer, "%ld|%ld#", raPos, decPos);
char scratchBuffer[24];
snprintf(scratchBuffer, sizeof(scratchBuffer), "%ld|%ld#", raPos, decPos);
return String(scratchBuffer);
}
}
Expand Down Expand Up @@ -1933,15 +1961,15 @@ String MeadeCommandProcessor::handleMeadeExtraCommands(String inCmd)
{
char scratchBuffer[10];
DayTime ha = _mount->calculateHa();
sprintf(scratchBuffer, "%02d%02d%02d#", ha.getHours(), ha.getMinutes(), ha.getSeconds());
snprintf(scratchBuffer, sizeof(scratchBuffer), "%02d%02d%02d#", ha.getHours(), ha.getMinutes(), ha.getSeconds());
return String(scratchBuffer);
}
}
else if (inCmd[1] == 'L') // :XGL#
{
char scratchBuffer[10];
DayTime lst = _mount->calculateLst();
sprintf(scratchBuffer, "%02d%02d%02d#", lst.getHours(), lst.getMinutes(), lst.getSeconds());
snprintf(scratchBuffer, sizeof(scratchBuffer), "%02d%02d%02d#", lst.getHours(), lst.getMinutes(), lst.getSeconds());
return String(scratchBuffer);
}
else if (inCmd[1] == 'N') // :XGN#
Expand Down Expand Up @@ -2164,6 +2192,10 @@ String MeadeCommandProcessor::handleMeadeQuit(String inCmd)
/////////////////////////////
String MeadeCommandProcessor::handleMeadeSetSlewRate(String inCmd)
{
if (inCmd.length() < 1)
{
return "";
}
switch (inCmd[0])
{
case 'S':
Expand All @@ -2189,6 +2221,10 @@ String MeadeCommandProcessor::handleMeadeSetSlewRate(String inCmd)
/////////////////////////////
String MeadeCommandProcessor::handleMeadeFocusCommands(String inCmd)
{
if (inCmd.length() < 1)
{
return "";
}
#if (FOCUS_STEPPER_TYPE != STEPPER_TYPE_NONE)
if (inCmd[0] == '+') // :F+
{
Expand Down Expand Up @@ -2261,6 +2297,10 @@ String MeadeCommandProcessor::handleMeadeFocusCommands(String inCmd)

String MeadeCommandProcessor::processCommand(String inCmd)
{
if (inCmd.length() < 2)
{
return "";
}
if (inCmd[0] == ':')
{
LOG(DEBUG_MEADE, "[MEADE]: Received command '%s'", inCmd.c_str());
Expand All @@ -2272,6 +2312,10 @@ String MeadeCommandProcessor::processCommand(String inCmd)
inCmd.remove(spacePos, 1);
}

if (inCmd.length() < 2)
{
return "";
}
LOG(DEBUG_MEADE, "[MEADE]: Processing command '%s'", inCmd.c_str());
char command = inCmd[1];
inCmd = inCmd.substring(2);
Expand Down
Loading
Loading