PWM Input at Orange Cube+, Firmware mod

Hello,

I am still waiting for my Orange Cube+ but finally after 3 weeks it should arrive tomorrow.
So I am an absolute beginner in this topic - I hope that you do not mind :slight_smile:

That is my plan:
RC - Receiver —> Orange Cube (normal carrier board) → CAN BUS → CAN Transceiver → ESP 32 → (PWN) to motor controller (skid steering of 4 x 250W for my UGV - UGV - large mower, modular design)

I am using Holybro H-RTK Unicore UM982 (Dual Antenna) for autonomous mode and a standard PWM RC receiver (HotRC F-06A) with individual PWM outputs for each channel.

I learned so far that the standard way to connect RC receivers to modern ArduPilot boards like the CubeOrange is via the dedicated RCIN port, which expects serial protocols like SBUS or PPM-Sum. While converters exist to translate individual PWM to SBUS, I found the adapter I have to be too small and cumbersome to reliably connect.

To address this, I’ve been working on a firmware modification to allow reading multiple individual PWM signals directly on the CubeOrange+'s AUX ports . This avoids the need for an external converter or a receiver with serial output.

Implemented Modification Details:

This modification involves adding support for a new RC input protocol within ArduPilot Rover firmware.

  1. New RC Protocol Driver:
  • Created a new AP_RCProtocol_PWM class.

  • Implemented low-level pulse width measurement using the STM32 timers in Input Capture mode on the dedicated AUX pins. This is critical for accurate and reliable timing.

  • Uses interrupts to capture pulse timings without blocking other firmware tasks.

  1. Hardware Integration:
  • Modified the hardware-specific definition for the CubeOrange+ to properly configure the AUX ports (AUX1-AUX6) as timer inputs specifically for this purpose.

  • Ensured the necessary timer channels are set up to listen for the incoming PWM signals on these pins.

  1. ArduPilot Framework Integration:
  • Registered the new PWM protocol within ArduPilot’s RC input system (AP_RCInput).

  • Added a corresponding bit (needs to be a specific, unassigned bit, e.g., bit 17 or similar - this needs to be defined in the code) to the RC_PROTOCOLS parameter to enable the feature.

  • Integrated the driver output with the existing RC channel processing framework.

  1. Flexible Usage:
  • The implementation supports using any number of the configurable AUX ports (from 1 up to 6 channels).

  • The driver automatically detects which of the configured AUX ports are receiving a valid PWM signal.

  • This allows users to connect only the required channels (e.g., AUX1-AUX3 for basic control) and potentially use the remaining AUX ports for other purposes if not needed for RC.

How to Use (with the modified firmware):

  1. Hardware Connection: Connect the Signal pins from the desired individual PWM outputs of your RC receiver (e.g., CH1, CH2, CH3) directly to the Signal pins of the chosen AUX ports on your CubeOrange carrier board (e.g., AUX1, AUX2, AUX3). Ensure the receiver is powered (e.g., from a 5V output on the Cube’s servo rail) and grounded.

  2. Firmware: Load the modified ArduPilot Rover firmware onto your CubeOrange+.

  3. Parameter Setting: In ground station (Mission Planner) setting the RC_PROTOCOLS parameter to include the bit corresponding to the new PWM protocol (e.g., set RC_PROTOCOLS to (Current Value) | (1 << 17) if bit 17 is used).

  4. Calibration: Perform the standard Radio Calibration procedure via the ground station. The system should now detect the signals on the configured AUX ports as RC channels.

Benefits:

  • Allows using standard RC receivers with individual PWM outputs without needing an external converter.

  • Direct connection simplifies wiring for this type of receiver.

  • Offers flexibility in the number of channels used (1-6) on the AUX ports.

  • Leaves the dedicated RCIN port free for potential alternative uses (though its primary function is RC input).

Current Status & Feedback:

This is a working proof-of-concept / early implementation. It is not yet part of the main ArduPilot codebase. I still have no Cube here to test it.
I’m sharing this to get feedback from the community. Has anyone attempted something similar? Are there potential pitfalls I should be aware of? Would there be interest in potentially contributing this feature to the main ArduPilot project once it’s fully tested and robust?

I plan to test this implementation thoroughly on my UGV in the coming days.

Thanks for any input or advice!

Rather than wasting time with PPM, PWM, and SBUS, why not just use a serial connection like CRSF (Crossfire or ELRS), or MavLink? All via a serial port, like all the modern receivers.

2 Likes

Just to add a little more context on why I’m using this specific receiver: The HotRC F-06A comes with an extremely compact transmitter, which is ideal for my UGV application. I prefer not to stand in my park like a typical drone pilot with a large, bulky device. Therefore, I need a discreet way to manually control the vehicle, rather than relying on a traditional RC transmitter. This constraint is the main reason why I’m exploring direct PWM input via the Cube’s AUX ports

Fair enough. Personally, for all that equipment I’d look to a more robust radio system, but if that fit’s your situation then run with it.

The majority of users stopped using PWM/PPM radio protocols many years ago. The new systems have so much more to offer in terms of data throughput, signal reliability, and hardware choices. I wouldn’t expect a lot of uptake in the mod. But there are always edge cases. Good luck!

1 Like

They do an SBUS receiver for that radio. PWM RC input hasnt been supported in over 10 years as most people are using 8-16 channels.

https://www.aliexpress.com/item/1005006883983291.html

2 Likes

Hello
How did you achieve the Ardupilot CAN–>ESP32–>PWM conversion? Could you share your implementation process? Because I am also looking for a DroneCAN library that supports the ESP32.

wow that is super cool and what I was looking for - thank you! I just ordered it

Hi, good question and I have same problem and I am working on a rudimentary solution without that library.
processActuatorCommand() is still an empty placeholder here. will check for a full solution after I received my parts. Or anybody else has got a better idea?

/**
 * ESP32 DroneCAN zu PWM Konverter
 * 
 * Implementiert minimales DroneCAN-Parsing fĂŒr ArduPilot Motorkommandos.
 * Konvertiert diese in PWM-Signale fĂŒr Motorsteuerung.
 */

#include <Arduino.h>
#include <ESP32CAN.h>
#include <CAN_config.h>

// PWM Konfiguration
#define PWM_FREQUENCY 50         // Standard RC PWM Frequenz (50Hz)
#define PWM_RESOLUTION 16        // 16-bit Auflösung
#define PWM_MIN_US 1000          // Min. Pulsbreite in Mikrosekunden
#define PWM_MAX_US 2000          // Max. Pulsbreite in Mikrosekunden

// PWM Pin-Definitionen
const int motorPins[4] = {25, 26, 27, 33};  // Pins fĂŒr die 4 Motoren

// CAN-Bus Konfiguration
CAN_device_t CAN_cfg;

// DroneCAN Parameter
// ArduPilot Actuator Command Message Type ID (beispielhaft, muss angepasst werden)
#define DRONECAN_ACTUATOR_COMMAND_ID 311  // Beispiel fĂŒr uavcan.equipment.actuator.Command

// Failsafe-Timer
unsigned long lastCommandTime = 0;
const unsigned long FAILSAFE_TIMEOUT_MS = 500; // Failsafe nach 500ms ohne Kommandos

// Multi-Frame Transfer Handling
const int MAX_TRANSFER_SIZE = 256;  // Max. DroneCAN Transfer-GrĂ¶ĂŸe
uint8_t transferBuffer[MAX_TRANSFER_SIZE];
int transferBufferPos = 0;
uint32_t currentTransferID = 0;
bool transferInProgress = false;

// Letzte empfangene Motorwerte (0.0-1.0)
float motorValues[4] = {0.0, 0.0, 0.0, 0.0};

/**
 * DroneCAN CAN ID Struktur
 * 
 * CAN ID-Format fĂŒr DroneCAN (29-bit Extended):
 * 
 * PrioritÀt   Message Type ID   Service?   Source Node
 * [28:26]     [25:8]            [7]        [6:0]
 * 
 * FĂŒr anonyme Transfers: Source Node = 0
 */

// DroneCAN ID-Parsing Funktionen
struct DroneCANID {
  uint8_t priority;
  uint16_t messageTypeID;
  bool isServiceNotMessage;
  uint8_t sourceNodeID;
  bool isStartOfTransfer;
  bool isEndOfTransfer;
  bool isToggleBit;
  uint8_t transferID;
};

// DroneCAN ID aus CAN Frame extrahieren
DroneCANID parseCANID(uint32_t canID) {
  DroneCANID id;
  
  id.priority = (canID >> 26) & 0x7;
  id.messageTypeID = (canID >> 8) & 0x3FFFF;
  id.isServiceNotMessage = (canID >> 7) & 0x1;
  id.sourceNodeID = canID & 0x7F;
  
  return id;
}

// DroneCAN Transfer Metadata aus CAN Frame extrahieren
void parseTransferMetadata(const CAN_frame_t &frame, 
                          bool &isStartOfTransfer, 
                          bool &isEndOfTransfer, 
                          bool &isToggleBit, 
                          uint8_t &transferID) {
  // In DroneCAN 1.0 sind diese in den ersten Bytes der Payload
  // Die genaue Position kann variieren je nach Protokollversion
  
  // Annahme: DroneCAN 1.0 Format
  // Byte 0: SSTTTTTT (S=Start/End, T=Transfer ID)
  if (frame.FIR.B.DLC > 0) {
    isStartOfTransfer = (frame.data.u8[0] >> 7) & 0x1;
    isEndOfTransfer = (frame.data.u8[0] >> 6) & 0x1;
    isToggleBit = (frame.data.u8[0] >> 5) & 0x1;
    transferID = frame.data.u8[0] & 0x1F;
  } else {
    isStartOfTransfer = false;
    isEndOfTransfer = false;
    isToggleBit = false;
    transferID = 0;
  }
}

// Setup-Funktion
void setup() {
  Serial.begin(115200);
  Serial.println("ESP32 DroneCAN zu PWM Konverter");
  
  // PWM KanÀle konfigurieren
  for (int i = 0; i < 4; i++) {
    ledcSetup(i, PWM_FREQUENCY, PWM_RESOLUTION);
    ledcAttachPin(motorPins[i], i);
    
    // Initial alle Motoren auf Minimum setzen
    updateMotorPWM(i, 0.0);
  }
  
  // CAN-Bus konfigurieren
  CAN_cfg.speed = CAN_SPEED_1000KBPS;  // Orange Cube verwendet typisch 1Mbps
  CAN_cfg.tx_pin_id = GPIO_NUM_5;      // CAN TX Pin (anpassen an Ihre Hardware)
  CAN_cfg.rx_pin_id = GPIO_NUM_4;      // CAN RX Pin (anpassen an Ihre Hardware)
  CAN_cfg.rx_queue = xQueueCreate(10, sizeof(CAN_frame_t));
  
  // CAN-Bus initialisieren
  ESP32Can.CANInit();
  
  Serial.println("System bereit - Warte auf DroneCAN-Nachrichten");
}

// PWM fĂŒr einen Motor aktualisieren mit verbesserten Berechnungen
void updateMotorPWM(int motorIndex, float value) {
  value = constrain(value, 0.0, 1.0); // Wert auf 0-1 begrenzen
  
  // Lineare Umrechnung von 0-1 auf den Mikrosekundenbereich
  float pulseWidth_us = PWM_MIN_US + value * (PWM_MAX_US - PWM_MIN_US);
  
  // Umrechnung von Mikrosekunden in LEDC Duty Cycle Wert
  float period_us = 1000000.0 / PWM_FREQUENCY;
  float duty_cycle_fraction = pulseWidth_us / period_us; // Duty cycle als 0.0-1.0 Fraktion
  
  uint32_t duty = (uint32_t)(duty_cycle_fraction * ((1 << PWM_RESOLUTION) - 1)); // Skalieren auf LEDC Auflösung
  
  ledcWrite(motorIndex, duty);
  
  Serial.printf("Motor %d: Wert=%.2f, Pulsbreite=%.2f ”s, Duty=%u\n", 
                motorIndex, value, pulseWidth_us, duty);
}

// DroneCAN ActuatorCommand deserialisieren und verarbeiten
void processActuatorCommand() {
 // todo
}

// Hauptschleife
void loop() {
  CAN_frame_t rx_frame;
  
  // PrĂŒfen auf CAN-Nachrichten
  if (xQueueReceive(CAN_cfg.rx_queue, &rx_frame, pdMS_TO_TICKS(10)) == pdTRUE) {
    // Nur Extended Frames betrachten (DroneCAN nutzt 29-bit IDs)
    if (rx_frame.FIR.B.FF == CAN_frame_ext) {
      // DroneCAN ID parsen
      DroneCANID id = parseCANID(rx_frame.MsgID);
      
      // Nur Message-Transfers bearbeiten, keine Service-Anfragen
      if (!id.isServiceNotMessage) {
        // PrĂŒfen auf ArduPilot Actuator Command Message Type
        if (id.messageTypeID == DRONECAN_ACTUATOR_COMMAND_ID) {
          // Transfer Metadata extrahieren
          bool isStartOfTransfer, isEndOfTransfer, isToggleBit;
          uint8_t transferID;
          parseTransferMetadata(rx_frame, isStartOfTransfer, isEndOfTransfer, 
                                isToggleBit, transferID);
          
          // Neuen Transfer starten, wenn Startflag gesetzt
          if (isStartOfTransfer) {
            transferBufferPos = 0;
            transferInProgress = true;
            currentTransferID = transferID;
          }
          
          // PrĂŒfen, ob dieser Frame zum aktuellen Transfer gehört
          if (transferInProgress && transferID == currentTransferID) {
            // Payload in den Transfer-Buffer kopieren
            // Offset berechnen (1 Byte fĂŒr Metadata ĂŒberspringen)
            int payloadStart = 1;
            int payloadLength = rx_frame.FIR.B.DLC - payloadStart;
            
            // Vor Buffer-Überlauf schĂŒtzen
            if (transferBufferPos + payloadLength <= MAX_TRANSFER_SIZE) {
              // Payload kopieren
              for (int i = 0; i < payloadLength; i++) {
                transferBuffer[transferBufferPos + i] = rx_frame.data.u8[payloadStart + i];
              }
              transferBufferPos += payloadLength;
            }
            
            // Wenn Ende des Transfers erreicht, Nachricht verarbeiten
            if (isEndOfTransfer) {
              processActuatorCommand();
              transferInProgress = false;
            }
          }
        }
      }
    }
  }
  
  // Failsafe-PrĂŒfung: Wenn zu lange keine Kommandos empfangen wurden
  if (millis() - lastCommandTime > FAILSAFE_TIMEOUT_MS) {
    // Im Failsafe alle Motoren auf Minimum setzen
    for (int i = 0; i < 4; i++) {
      if (motorValues[i] > 0.1) {  // Nur wenn Motor nicht bereits am Minimum
        motorValues[i] = 0.0;
        updateMotorPWM(i, motorValues[i]);
        Serial.println("Failsafe aktiviert: Keine DroneCAN-Kommandos erhalten");
      }
    }
  }
}```
1 Like

I found this projecthttps://forum.opencyphal.org/t/107-arduino-cyphal-bringing-cyphal-to-arduino/1692, but I didn’t apply it successfully. Maybe it’s a good idea. I look forward to your ESP32 DroneCAN.