Some code to interface RC RX or Pixhawk to the speed controllers on the AMD R120 Mower:
// TECHNIDYNE _ Dual-channel, RC to Analog Interface (0-5V) with Reverse Logic
// AMD R120 Speed Controllers
// Ver 1.50 _ 2025/06/19 _ Arduino Nano Optimized
#include <Arduino.h>
// Pin Definitions
const int CH1_PIN = 2;
const int CH2_PIN = 3;
const int DIR1_PIN = 4;
const int PWM1_PIN = 5;
const int DIR2_PIN = 7;
const int PWM2_PIN = 6;
const int ACTIVE_PIN = 8;
// RC Configuration
const uint16_t CENTER = 1500;
const uint16_t MIN_PULSE = 1000;
const uint16_t MAX_PULSE = 2000;
const uint16_t DEADZONE = 20;
// Global Variables
volatile uint32_t ch1RiseTime = 0;
volatile uint16_t ch1Pulse = CENTER;
volatile bool ch1Updated = false;
volatile uint32_t ch2RiseTime = 0;
volatile uint16_t ch2Pulse = CENTER;
volatile bool ch2Updated = false;
// Interrupt Service Routines - FIXED EXTRA PARENTHESIS HERE
void ch1ISR() {
if (digitalRead(CH1_PIN)) {
ch1RiseTime = micros();
} else if (ch1RiseTime) {
ch1Pulse = micros() - ch1RiseTime;
ch1Updated = true;
}
}
void ch2ISR() {
if (digitalRead(CH2_PIN)) {
ch2RiseTime = micros();
} else if (ch2RiseTime) {
ch2Pulse = micros() - ch2RiseTime;
ch2Updated = true;
}
}
void setup() {
pinMode(CH1_PIN, INPUT);
pinMode(CH2_PIN, INPUT);
pinMode(DIR1_PIN, OUTPUT);
pinMode(PWM1_PIN, OUTPUT);
pinMode(DIR2_PIN, OUTPUT);
pinMode(PWM2_PIN, OUTPUT);
pinMode(ACTIVE_PIN, OUTPUT);
digitalWrite(DIR1_PIN, HIGH);
analogWrite(PWM1_PIN, 0);
digitalWrite(DIR2_PIN, HIGH);
analogWrite(PWM2_PIN, 0);
digitalWrite(ACTIVE_PIN, LOW);
attachInterrupt(digitalPinToInterrupt(CH1_PIN), ch1ISR, CHANGE);
attachInterrupt(digitalPinToInterrupt(CH2_PIN), ch2ISR, CHANGE);
}
void processChannel(uint16_t pulse, int dirPin, int pwmPin) {
pulse = constrain(pulse, MIN_PULSE, MAX_PULSE);
if (pulse < CENTER - DEADZONE) {
digitalWrite(dirPin, LOW);
analogWrite(pwmPin, map(pulse, MIN_PULSE, CENTER, 255, 0));
} else if (pulse > CENTER + DEADZONE) {
digitalWrite(dirPin, HIGH);
analogWrite(pwmPin, map(pulse, CENTER, MAX_PULSE, 0, 255));
} else {
analogWrite(pwmPin, 0);
}
}
bool isCentered(uint16_t pulse) {
return (abs((int)pulse - (int)CENTER) <= DEADZONE);
}
void loop() {
bool activeFlag = false;
if (ch1Updated) {
noInterrupts();
uint16_t pulse1 = ch1Pulse;
ch1Updated = false;
interrupts();
processChannel(pulse1, DIR1_PIN, PWM1_PIN);
if (!isCentered(pulse1)) activeFlag = true;
}
if (ch2Updated) {
noInterrupts();
uint16_t pulse2 = ch2Pulse;
ch2Updated = false;
interrupts();
processChannel(pulse2, DIR2_PIN, PWM2_PIN);
if (!isCentered(pulse2)) activeFlag = true;
}
digitalWrite(ACTIVE_PIN, activeFlag ? HIGH : LOW);
}
Output Behavior:
Center (1500μs) 0V DIGITAL HIGH
Full Left/Down (1000μs) 5V DIGITAL LOW
Full Right/Up (2000μs) 5V DIGITAL HIGH
Filter Requirements:
For analog outputs: Implement simple RC low-pass filters (1kΩ resistor in series + 10μF capacitor to ground) to convert PWM to smooth DC voltage signal
Important Notes:
- The digital outputs go LOW only when sticks are below 1500μs (typical throttle/left position)
- Center stick gives 0V on analog outputs, while maximum deflection in either direction gives 5V
- Uses Timer1 for PWM outputs (pins 9/10) at 31.25kHz for minimal ripple
- Interrupt-driven design ensures accurate signal timing without blocking main loop
This implementation provides reliable RC signal decoding and produces the required output voltages with minimal latency, optimized for the Arduino Nano’s capabilities.