Taking our AMD R120 Mower to the next level

New Member here, but not new to things Radio Controlled, Pixhawk and autonomous flying machines.
Hoping for advice along the way and as a build log as this project progresses.
I’m working on developing an autonomous RTK GNSS system for our Flail Mower. We bought this for our RC Flying Field and it works great as an RC Mower/Flail Bushwhacker (“maiden flight” video attached).
Equipment Purchased for the automation project thus far:

SiK Telemetry Radio V3
H-RTK NEO-F9P w/ Base Station Antenna
H-RTK NEO-F9P w/ Vertical Array Patch Antenna
Pixhawk 6C Mini
Weatherproof enclosure
Tripod
Dell 7280 Laptop
USB Hub
20ft USB Heavy Duty Extension

All Tests in my lab will be done on a tracked vehicle that I have in my Arduino arsenal. I have configured this prototype to respond exactly as does our AMD R120.
As mentioned, new to this forum, and trying to access as much info as possible, so looking forward to responses.
Thanks in advance, Cletus

2 Likes

Cool project. But I think you’re missing a key ingredient: ArduPilot has long since abandoned the Arduino in favor of (mostly) STM32 based autopilot hardware. So if you want to take advantage of this community, you should familiarize with this ecosystem. Here’s where to start:

Thanks for the response, Agreed!
Well, I have a ton of Arduino stuff here at my lab and vast experience designing in Arduino. Not much Arduino stuff will be utilized in this project since it will just about be control from the Pixhawk 6c. The Arduino stuff is only related to making the prototype vehicle mimic the AMD R120.

Apologies - I missed the Pixhawk 6C in your BOM. It’s a fine choice.

Testing will be near useless unless you use the autopilot on the smaller test vehicle as well.

Yes, absolutely! Test vehicle will be outfitted with everything i plan to use on the mower.

1 Like

Some pics of our testing yesterday. Went quite well, a few bugs and challenges to work out, but here are a few pics:



We established our reference location at the field
Lat 10.66110117 Lon -61.4014045

1 Like

Any assistance finding the pinouts for these two connectors, would be greatly appreciated. I suspect it’s a typical e-bike BLDC controller, but all the pinouts I can find show the harness end, not the connector pinouts.

The chinese translation for the markings on the box says very little:


Did some basic waypoints and RTL on our runway yesterday. Went well, but as expected a few bugs to iron out.

Chinese Salesperson and factory engineer came through and I got all the pinout and board layout info I need to proceed. Going with native Pixhawk skid-steer control, a 4PDT slide switch will be implemented to easily revert the mower to original configuration. A bunch of safety features will be implemented as well, including a dedicated 433Mhz “kill-switch” transmission link.

1 Like

After Google Chinese to English Translation:

AMD_R120 ESC Pinout.pdf (96.7 KB)

Schematic as supplied with the AMD R120 Flail Mower

A serious concern is the automation hardware needs to be readily removable/deployable as we have had issues of theft/vandalism over the years. That being a given everything is being built as a quick disconnect plug-n-play system and a simple switch and connector is being considered for interfacing the automation/FPV rig and reverting it to normal RC operation.
So I think this solves my plug-n-play situation. A 4PDT switch toggles the system between Original configuration and Autonomous and a multi-contact aircraft style connector makes the system Plug n play. The hardware easily aligns and affixes mechanically to the roll-cage on the machine.:
AMD R120 Interface.PDF (907.9 KB)

Their BLDC motor controller:
AMD_R120 ESC Pinout.pdf (96.7 KB)

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:

  1. The digital outputs go LOW only when sticks are below 1500μs (typical throttle/left position)
  2. Center stick gives 0V on analog outputs, while maximum deflection in either direction gives 5V
  3. Uses Timer1 for PWM outputs (pins 9/10) at 31.25kHz for minimal ripple
  4. 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.

Not sure if you saw this but I made a very simple DAC to create 0-5v from the FC. No processor or coding needed and it’s isolated. Ideas for 0-5vdc motor control - #48 by johnharlow

1 Like

Strongly recommend @johnharlow’s hardware solution.

Looked at it, but I also need a logic LOW happening on a pin to enable reverse on these ESCs, hence the processor.

We have GPIO triggers for that in the Brushed/Relay configuration. Based on what your code seems to do, it looks like that would work well in place of all that code.

It’s formatted poorly, and I’m not really doing any significant review here, but what happens on signal loss? Failsafe? Edge cases? The native driver handles this elegantly.

I don’t get it. The BLDC ESC I’m using needs 0 - 5V with center as 0V, it also needs a Logic LOW sent to a pin, when the stick is “pulled back” in order to initiate reverse.
Please clarify?
Only way I know to do that is write some code. There’s no mixing, the tracks run independently (seperate channels) and the mixing is native to pixhawk/mission planner, not in my code.