PlatformIO Modular Skeleton - SergeGit/rc-tank-platform GitHub Wiki
This document contains the full modular skeleton for the Arduino Nano-based Hull Controller, formatted for PlatformIO (C++ .cpp + .h modules). Drop the contents into src/ in a PlatformIO project.
[env:nanoatmega328]
platform = atmelavr
board = nanoatmega328
framework = arduino
lib_deps =
build_flags = -DARDUINO_AVR_NANO
; Serial monitor settings (optional)
monitor_speed = 115200#include "main.h"
void setup() {
Serial.begin(115200);
delay(100);
Serial.println("Hull Controller starting...");
setupConfig();
setupI2C();
setupBatteryManagement();
setupMotorControl();
setupTracks();
setupTurret();
setupWeapons();
setupLights();
setupEncoder();
lastMotorUpdate = millis();
}
void loop() {
unsigned long now = millis();
// I2C handling is interrupt driven; processCommand() is called from callbacks
// Periodic updates
if (now - lastMotorUpdate >= MOTOR_UPDATE_INTERVAL_MS) {
updateMotors();
lastMotorUpdate = now;
}
// Update lights and weapons
updateLights();
updateWeapons();
updateBatteryManagement();
// simple watchdog: ensure loop runs frequently
// wdt_reset(); // Uncomment if watchdog is enabled
}#pragma once
#include <Arduino.h>
#include "config.h"
// Subsystem headers
#include "i2c_comm.h"
#include "Battery_supervision.h"
#include "motor_control.h"
#include "tracks.h"
#include "turret.h"
#include "weapons.h"
#include "lights.h"
#include "encoder_config.h"
// Globals used by main loop
extern unsigned long lastMotorUpdate;
// Convenience setup wrappers
void setupConfig();
void setupI2C();#pragma once
#include <Arduino.h>
// I2C
#define I2C_ADDRESS 0x08
// Command codes (from documentation)
#define CMD_TURRET_ROTATE 0x10
#define CMD_TURRET_ELEVATE 0x11
#define CMD_TRACKS_MOVE 0x20
#define CMD_TRACKS_TURN 0x21
#define CMD_LASER_TOGGLE 0x30
#define CMD_IR_TOGGLE 0x31
#define CMD_CANNON_FIRE 0x32
#define CMD_FRONT_LIGHTS 0x40
#define CMD_REAR_LIGHTS 0x41
#define CMD_GET_BATTERY 0xE0
#define CMD_GET_POSITION 0xE1
#define CMD_GET_CANNON_STATUS 0xE2
#define CMD_GET_GPS 0xE3
#define CMD_GET_ALL_SENSORS 0xEF
#define CMD_GET_STATUS 0xF0
#define CMD_EMERGENCY_STOP 0xFF
// Pins (match documentation)
// Battery
#define PIN_BATT_VOLTAGE A0
#define PIN_BATT_RELAY A1
// Lights
#define PIN_FRONT_LIGHTS A2
#define PIN_LASER A3
#define PIN_REAR_LIGHTS A7
// Weapons
#define PIN_CANNON 13
#define PIN_CANNON_INTERRUPT 2
#define PIN_IR 6
// Tracks (Cytron)
#define PIN_LEFT_TRACK_PWM1 3
#define PIN_LEFT_TRACK_PWM2 9
#define PIN_RIGHT_TRACK_PWM1 10
#define PIN_RIGHT_TRACK_PWM2 11
// Turret (L293D)
#define PIN_TURRET_ROT_EN 5
#define PIN_TURRET_ROT_IN1 8
#define PIN_TURRET_ROT_IN2 7
#define PIN_TURRET_ELEV_EN 6
#define PIN_TURRET_ELEV_IN1 4
#define PIN_TURRET_ELEV_IN2 12
// Timing / config
#define MOTOR_UPDATE_INTERVAL_MS 20
#define BATTERY_CHECK_INTERVAL_MS 2000
#define LIGHT_BLINK_INTERVAL_MS 500
#define CANNON_COOLDOWN_MS 2000
// Motor parameters
#define DEFAULT_RAMP_STEP 5
#define TRACK_MIN_THRESHOLD 20
#define TURRET_MIN_THRESHOLD 25
// I2C response sizes (for reference)
#define RESP_BATTERY_SIZE 5
#define RESP_POSITION_SIZE 4
#define RESP_CANNON_STATUS_SIZE 1
#define RESP_GPS_SIZE 8
#define RESP_ALL_SENSORS_SIZE 16
#define RESP_STATUS_SIZE 1#pragma once
#include <Arduino.h>
void setupI2C();
void processCommand(uint8_t command, uint8_t data);
void prepareResponseData(uint8_t command);
// Called by I2C event handlers
void onI2CReceive(int byteCount);
void onI2CRequest();#include "i2c_comm.h"
#include <Wire.h>
#include "config.h"
#include "Battery_supervision.h"
#include "tracks.h"
#include "turret.h"
#include "weapons.h"
#include "lights.h"
static uint8_t responseBuffer[32];
static uint8_t responseLength = 0;
void setupI2C() {
Wire.begin(I2C_ADDRESS); // join I2C bus as slave
Wire.onReceive(onI2CReceive);
Wire.onRequest(onI2CRequest);
Serial.print("I2C slave started at address 0x");
Serial.println(I2C_ADDRESS, HEX);
}
void onI2CReceive(int byteCount) {
if (byteCount < 1) return;
uint8_t command = Wire.read();
uint8_t data = 0;
if (Wire.available()) data = Wire.read();
processCommand(command, data);
}
void onI2CRequest() {
// When master requests data, send prepared buffer
Wire.write(responseBuffer, responseLength);
// clear length
responseLength = 0;
}
void processCommand(uint8_t command, uint8_t data) {
switch (command) {
case CMD_TURRET_ROTATE:
handleTurretRotate(data);
break;
case CMD_TURRET_ELEVATE:
handleTurretElevate(data);
break;
case CMD_TRACKS_MOVE:
handleTracksMove(data);
break;
case CMD_TRACKS_TURN:
handleTracksTurn(data);
break;
case CMD_LASER_TOGGLE:
handleLaserToggle(data);
break;
case CMD_IR_TOGGLE:
handleIrToggle(data);
break;
case CMD_CANNON_FIRE:
handleCannonFire(data);
break;
case CMD_FRONT_LIGHTS:
handleFrontLights(data);
break;
case CMD_REAR_LIGHTS:
handleRearLights(data);
break;
case CMD_GET_BATTERY:
prepareResponseData(CMD_GET_BATTERY);
break;
case CMD_GET_STATUS:
prepareResponseData(CMD_GET_STATUS);
break;
case CMD_EMERGENCY_STOP:
if (data == 0) {
emergencyStop();
} else {
resumeFromEmergencyStop();
}
break;
default:
// unknown command - ignore or set error flag
Serial.print("Unknown I2C cmd: ");
Serial.println(command, HEX);
break;
}
}
void prepareResponseData(uint8_t command) {
responseLength = 0;
memset(responseBuffer, 0, sizeof(responseBuffer));
switch (command) {
case CMD_GET_BATTERY: {
// Fill 5 bytes: voltage (uint16 little-endian, hundredths), type, relay state, reserved
uint16_t raw = (uint16_t)(getBatteryVoltage() * 100.0);
responseBuffer[0] = raw & 0xFF;
responseBuffer[1] = (raw >> 8) & 0xFF;
responseBuffer[2] = (uint8_t)getBatteryType();
responseBuffer[3] = isRelayEnabled() ? 1 : 0;
responseBuffer[4] = 0; // reserved / status
responseLength = RESP_BATTERY_SIZE;
} break;
case CMD_GET_STATUS: {
uint8_t flags = 0;
flags |= getIsCannonReady() ? (1<<0) : 0;
flags |= getIsLaserOn() ? (1<<1) : 0;
flags |= getIsIrOn() ? (1<<2) : 0;
flags |= (getFrontLightState() != 0) ? (1<<3) : 0;
flags |= (getRearLightState() != 0) ? (1<<4) : 0;
flags |= isRelayEnabled() ? (1<<5) : 0;
// Bit 6 = error; bit 7 = emergency stop (not implemented here)
responseBuffer[0] = flags;
responseLength = RESP_STATUS_SIZE;
} break;
default:
// nothing
break;
}
}#pragma once
#include <Arduino.h>
void setupMotorControl();
void updateMotors();
// Register motors helpers (stubs)
uint8_t registerL293DMotor(uint8_t enablePin, uint8_t in1Pin, uint8_t in2Pin, const char* name, uint8_t minThreshold);
uint8_t registerCytronMotor(uint8_t pwmPinA, uint8_t pwmPinB, const char* name, uint8_t minThreshold);
void setMotorSpeed(uint8_t motorIndex, int speed);
void stopMotor(uint8_t motorIndex);
void stopAllMotors();
int getMotorSpeed(uint8_t motorIndex);
int getMotorTargetSpeed(uint8_t motorIndex);
int getMotorState(uint8_t motorIndex);
#include "motor_control.h"
#include "config.h"
// Minimal implementation: store speeds for up to 8 motors
static const uint8_t MAX_MOTORS = 8;
static int motorCurrentSpeed[MAX_MOTORS];
static int motorTargetSpeed[MAX_MOTORS];
static uint8_t motorMinThreshold[MAX_MOTORS];
static uint8_t motorCount = 0;
void setupMotorControl() {
for (uint8_t i = 0; i < MAX_MOTORS; ++i) {
motorCurrentSpeed[i] = 0;
motorTargetSpeed[i] = 0;
motorMinThreshold[i] = 0;
}
}
uint8_t registerL293DMotor(uint8_t enablePin, uint8_t in1Pin, uint8_t in2Pin, const char* name, uint8_t minThreshold) {
// Keep pinMode setup in specific module registration to avoid duplication
if (motorCount >= MAX_MOTORS) return 255;
motorMinThreshold[motorCount] = minThreshold;
return motorCount++;
}
uint8_t registerCytronMotor(uint8_t pwmPinA, uint8_t pwmPinB, const char* name, uint8_t minThreshold) {
if (motorCount >= MAX_MOTORS) return 255;
motorMinThreshold[motorCount] = minThreshold;
return motorCount++;
}
void setMotorSpeed(uint8_t motorIndex, int speed) {
if (motorIndex >= motorCount) return;
motorTargetSpeed[motorIndex] = constrain(speed, -100, 100);
}
void stopMotor(uint8_t motorIndex) {
if (motorIndex >= motorCount) return;
motorTargetSpeed[motorIndex] = 0;
motorCurrentSpeed[motorIndex] = 0;
}
void stopAllMotors() {
for (uint8_t i = 0; i < motorCount; ++i) {
stopMotor(i);
}
}
void updateMotors() {
for (uint8_t i = 0; i < motorCount; ++i) {
int target = motorTargetSpeed[i];
int current = motorCurrentSpeed[i];
if (current == target) continue;
int step = DEFAULT_RAMP_STEP;
if (abs(target - current) < step) current = target;
else if (target > current) current += step;
else current -= step;
motorCurrentSpeed[i] = current;
// TODO: map to PWM and write to hardware pins in concrete motor modules
}
}
int getMotorSpeed(uint8_t motorIndex) { return (motorIndex < motorCount) ? motorCurrentSpeed[motorIndex] : 0; }
int getMotorTargetSpeed(uint8_t motorIndex) { return (motorIndex < motorCount) ? motorTargetSpeed[motorIndex] : 0; }
int getMotorState(uint8_t motorIndex) { return 0; }
#pragma once
#include <Arduino.h>
void setupTracks();
void handleTracksMove(uint8_t data);
void handleTracksTurn(uint8_t data);
void setArcadeDriveInput(int forwardBackward, int leftRight);
void trackdrive(int leftSpeed, int rightSpeed);
void emergencyStopTracks();
int getLeftTrackSpeed();
int getRightTrackSpeed();#include "tracks.h"
#include "motor_control.h"
#include "config.h"
static int leftMotorIndex = 0;
static int rightMotorIndex = 1;
static int leftSpeed = 0;
static int rightSpeed = 0;
void setupTracks() {
// Initialize pins
pinMode(PIN_LEFT_TRACK_PWM1, OUTPUT);
pinMode(PIN_LEFT_TRACK_PWM2, OUTPUT);
pinMode(PIN_RIGHT_TRACK_PWM1, OUTPUT);
pinMode(PIN_RIGHT_TRACK_PWM2, OUTPUT);
setupMotorControl();
// Register motors (indices only; mapping to pins done here)
leftMotorIndex = registerCytronMotor(PIN_LEFT_TRACK_PWM1, PIN_LEFT_TRACK_PWM2, "LeftTrack", TRACK_MIN_THRESHOLD);
rightMotorIndex = registerCytronMotor(PIN_RIGHT_TRACK_PWM1, PIN_RIGHT_TRACK_PWM2, "RightTrack", TRACK_MIN_THRESHOLD);
}
static int convertDataToSpeed(uint8_t data) {
// data 0-200 maps to -100..+100 where 100 is neutral
int s = (int)data - 100;
return constrain(s, -100, 100);
}
void handleTracksMove(uint8_t data) {
int s = convertDataToSpeed(data);
// both tracks same for forward/back
setMotorSpeed(leftMotorIndex, s);
setMotorSpeed(rightMotorIndex, s);
}
void handleTracksTurn(uint8_t data) {
int s = convertDataToSpeed(data);
// positive s -> turn right: left forward, right backward
setMotorSpeed(leftMotorIndex, s);
setMotorSpeed(rightMotorIndex, -s);
}
void setArcadeDriveInput(int forwardBackward, int leftRight) {
int l = forwardBackward + leftRight;
int r = forwardBackward - leftRight;
l = constrain(l, -100, 100);
r = constrain(r, -100, 100);
setMotorSpeed(leftMotorIndex, l);
setMotorSpeed(rightMotorIndex, r);
}
void trackdrive(int leftSpd, int rightSpd) {
setMotorSpeed(leftMotorIndex, leftSpd);
setMotorSpeed(rightMotorIndex, rightSpd);
}
void emergencyStopTracks() {
stopMotor(leftMotorIndex);
stopMotor(rightMotorIndex);
}
int getLeftTrackSpeed() { return getMotorSpeed(leftMotorIndex); }
int getRightTrackSpeed() { return getMotorSpeed(rightMotorIndex); }
#pragma once
#include <Arduino.h>
void setupTurret();
void handleTurretRotate(uint8_t data);
void handleTurretElevate(uint8_t data);
void stopTurret();
int getTurretRotationSpeed();
int getTurretElevationSpeed();#include "turret.h"
#include "config.h"
#include "motor_control.h"
static int rotMotorIndex = 2;
static int elevMotorIndex = 3;
void setupTurret() {
pinMode(PIN_TURRET_ROT_EN, OUTPUT);
pinMode(PIN_TURRET_ROT_IN1, OUTPUT);
pinMode(PIN_TURRET_ROT_IN2, OUTPUT);
pinMode(PIN_TURRET_ELEV_EN, OUTPUT);
pinMode(PIN_TURRET_ELEV_IN1, OUTPUT);
pinMode(PIN_TURRET_ELEV_IN2, OUTPUT);
// Register motors (indices) — mapping to pins is kept here
rotMotorIndex = registerL293DMotor(PIN_TURRET_ROT_EN, PIN_TURRET_ROT_IN1, PIN_TURRET_ROT_IN2, "TurretRot", TURRET_MIN_THRESHOLD);
elevMotorIndex = registerL293DMotor(PIN_TURRET_ELEV_EN, PIN_TURRET_ELEV_IN1, PIN_TURRET_ELEV_IN2, "TurretElev", TURRET_MIN_THRESHOLD);
}
static int convertDataToSpeed(uint8_t data) {
return (int)data - 100; // -100..+100
}
void handleTurretRotate(uint8_t data) {
int s = convertDataToSpeed(data);
setMotorSpeed(rotMotorIndex, s);
}
void handleTurretElevate(uint8_t data) {
int s = convertDataToSpeed(data);
setMotorSpeed(elevMotorIndex, s);
}
void stopTurret() {
stopMotor(rotMotorIndex);
stopMotor(elevMotorIndex);
}
int getTurretRotationSpeed() { return getMotorSpeed(rotMotorIndex); }
int getTurretElevationSpeed() { return getMotorSpeed(elevMotorIndex); }
#pragma once
#include <Arduino.h>
void setupWeapons();
void updateWeapons();
void handleCannonFire(uint8_t duration);
bool getIsCannonReady();
void handleLaserToggle(uint8_t data);
void handleIrToggle(uint8_t data);
bool getIsLaserOn();
bool getIsIrOn();#include "weapons.h"
#include "config.h"
static unsigned long lastCannonFire = 0;
static bool cannonReady = true;
static bool laserOn = false;
static bool irOn = false;
static unsigned long laserLastToggle = 0;
void setupWeapons() {
pinMode(PIN_CANNON, OUTPUT);
pinMode(PIN_LASER, OUTPUT);
pinMode(PIN_IR, OUTPUT);
digitalWrite(PIN_CANNON, LOW);
digitalWrite(PIN_LASER, LOW);
digitalWrite(PIN_IR, LOW);
}
void updateWeapons() {
// Manage cooldown
if (!cannonReady && (millis() - lastCannonFire) >= CANNON_COOLDOWN_MS) {
cannonReady = true;
}
}
void handleCannonFire(uint8_t duration) {
if (!cannonReady) return;
cannonReady = false;
lastCannonFire = millis();
// duration is an abstract unit. Map to ms e.g. duration/255.0 * 1000ms
unsigned long ms = map(duration, 0, 255, 50, 1000);
digitalWrite(PIN_CANNON, HIGH);
delay(ms);
digitalWrite(PIN_CANNON, LOW);
}
bool getIsCannonReady() { return cannonReady; }
void handleLaserToggle(uint8_t data) {
laserOn = data != 0;
digitalWrite(PIN_LASER, laserOn ? HIGH : LOW);
}
void handleIrToggle(uint8_t data) {
irOn = data != 0;
digitalWrite(PIN_IR, irOn ? HIGH : LOW);
}
bool getIsLaserOn() { return laserOn; }
bool getIsIrOn() { return irOn; }
#pragma once
#include <Arduino.h>
void setupLights();
void updateLights();
void handleFrontLights(uint8_t data);
void handleRearLights(uint8_t data);
uint8_t getFrontLightState();
uint8_t getRearLightState();#include "lights.h"
#include "config.h"
static uint8_t frontState = 0; // 0-off,1-on,2-blink
static uint8_t rearState = 0;
static unsigned long lastBlinkToggle = 0;
static bool blinkOn = false;
void setupLights() {
pinMode(PIN_FRONT_LIGHTS, OUTPUT);
pinMode(PIN_REAR_LIGHTS, OUTPUT);
digitalWrite(PIN_FRONT_LIGHTS, LOW);
digitalWrite(PIN_REAR_LIGHTS, LOW);
}
void updateLights() {
if (frontState == 1) digitalWrite(PIN_FRONT_LIGHTS, HIGH);
else if (frontState == 0) digitalWrite(PIN_FRONT_LIGHTS, LOW);
else if (frontState == 2) {
if (millis() - lastBlinkToggle >= LIGHT_BLINK_INTERVAL_MS) {
blinkOn = !blinkOn;
lastBlinkToggle = millis();
digitalWrite(PIN_FRONT_LIGHTS, blinkOn ? HIGH : LOW);
}
}
if (rearState == 1) digitalWrite(PIN_REAR_LIGHTS, HIGH);
else if (rearState == 0) digitalWrite(PIN_REAR_LIGHTS, LOW);
else if (rearState == 2) {
// rear blinking uses same blink state
digitalWrite(PIN_REAR_LIGHTS, blinkOn ? HIGH : LOW);
}
}
void handleFrontLights(uint8_t data) {
frontState = data;
}
void handleRearLights(uint8_t data) {
rearState = data;
}
uint8_t getFrontLightState() { return frontState; }
uint8_t getRearLightState() { return rearState; }
#pragma once
#include <Arduino.h>
void setupEncoder();
int getTurretAngle();
#include "Encoder_config.h"
void setupEncoder() {
// stub: encoder not yet used
}
int getTurretAngle() {
// return dummy 0..359
return 0;
}
#pragma once
#include <Arduino.h>
void setupBatteryManagement();
void updateBatteryManagement();
float getBatteryVoltage();
int getBatteryType();
bool isRelayEnabled();
void enableRelay(bool enable);
void updateBatteryResponseData(uint8_t* responseData);
#include "Battery_supervision.h"
#include "config.h"
static unsigned long lastBatteryCheck = 0;
static float batteryVoltage = 0.0;
static int batteryType = 0;
static bool relayEnabled = false;
void setupBatteryManagement() {
pinMode(PIN_BATT_RELAY, OUTPUT);
digitalWrite(PIN_BATT_RELAY, LOW);
updateBatteryVoltage();
}
void updateBatteryManagement() {
if (millis() - lastBatteryCheck >= BATTERY_CHECK_INTERVAL_MS) {
updateBatteryVoltage();
lastBatteryCheck = millis();
}
}
void updateBatteryVoltage() {
int raw = analogRead(PIN_BATT_VOLTAGE);
// Using default Arduino ADC reference (0..1023 -> 0..5V)
float v = ((float)raw / 1023.0) * 5.0;
// compensate for divider: Vout = Vin * R2/(R1+R2) with R1=100k, R2=22k => factor ~ (R1+R2)/R2 = (122/22)=5.545
batteryVoltage = v * 5.545;
}
float getBatteryVoltage() { return batteryVoltage; }
int getBatteryType() { return batteryType; }
bool isRelayEnabled() { return relayEnabled; }
void enableRelay(bool enable) {
relayEnabled = enable;
digitalWrite(PIN_BATT_RELAY, enable ? HIGH : LOW);
}
void updateBatteryResponseData(uint8_t* responseData) {
uint16_t raw = (uint16_t)(batteryVoltage * 100.0);
responseData[0] = raw & 0xFF;
responseData[1] = (raw >> 8) & 0xFF;
responseData[2] = (uint8_t)batteryType;
responseData[3] = relayEnabled ? 1 : 0;
responseData[4] = 0;
}
Project skeleton for Arduino Nano Hull Controller. Files are separated into .h/.cpp modules for PlatformIO.
To build:
1. Create a PlatformIO project with `platformio.ini` shown above.
2. Put the `src/` files into the project `src/` directory.
3. `pio run` to compile.
This skeleton provides stubbed implementations and is intended as a foundation to add hardware-specific code (pin PWM mapping, motor driver libraries, safety checks, etc.).- All subsystems are intentionally stubs or minimal implementations that match the API described in your documentation. Update hardware-specific PWM control in
tracks.cpp,turret.cpp, andmotor_control.cppto write PWM values and direction to your drivers. - I did not include third-party libraries; PlatformIO/Arduino built-ins are sufficient for the skeleton.
End of skeleton.