Documentation Index
Fetch the complete documentation index at: https://mintlify.com/autorope/donkeycar/llms.txt
Use this file to discover all available pages before exploring further.
Actuator parts control motors and servos to translate pilot commands into physical motion.
PWM Controllers
PulseController
Generic PWM pulse controller using pin providers.
Constructor:
PulseController(pwm_pin, pwm_scale=1.0, pwm_inverted=False)
PWM pin provider (see donkeycar.parts.pins)
Scaling factor for 12-bit pulse values to compensate for non-standard PWM frequencies
Methods:
Set PWM pulse width using 12-bit value (0-4095)
Donkeycar part interface - sets pulse width
Usage Example:
from donkeycar.parts.pins import PCA9685PwmPin
from donkeycar.parts.actuator import PulseController
# Create PWM pin
pwm_pin = PCA9685PwmPin(channel=1, frequency=60)
# Create pulse controller
controller = PulseController(pwm_pin)
# Set pulse
controller.set_pulse(370) # neutral position
PCA9685 (Deprecated)
Legacy PCA9685 PWM controller. Use PulseController instead.
Constructor:
PCA9685(channel, address=0x40, frequency=60, busnum=None, init_delay=0.1)
Steering Controllers
PWMSteering
Converts steering angles to PWM pulses.
Constructor:
PWMSteering(controller, left_pulse, right_pulse)
Pulse controller with set_pulse() method
PWM pulse for full left steering
PWM pulse for full right steering
Methods:
Convert angle (-1 to 1) to PWM pulse and apply
Set pulse for threaded operation
Usage Example:
from donkeycar.parts.actuator import PWMSteering, PulseController
steering_controller = PulseController(pwm_pin)
steering = PWMSteering(controller=steering_controller,
left_pulse=cfg.STEERING_LEFT_PWM,
right_pulse=cfg.STEERING_RIGHT_PWM)
V.add(steering, inputs=['pilot/angle'])
Throttle Controllers
PWMThrottle
Converts throttle values to PWM pulses for ESC control.
Constructor:
PWMThrottle(controller, max_pulse, min_pulse, zero_pulse)
Pulse controller with set_pulse() method
PWM pulse for full forward throttle
PWM pulse for full reverse throttle
PWM pulse for stopped/neutral
Methods:
run
(throttle: float) -> None
Convert throttle (-1 to 1) to PWM pulse and apply
run_threaded
(throttle: float) -> None
Set pulse for threaded operation
Stop throttle and release
Usage Example:
from donkeycar.parts.actuator import PWMThrottle, PulseController
throttle_controller = PulseController(pwm_pin)
throttle = PWMThrottle(controller=throttle_controller,
max_pulse=cfg.THROTTLE_FORWARD_PWM,
min_pulse=cfg.THROTTLE_REVERSE_PWM,
zero_pulse=cfg.THROTTLE_STOPPED_PWM)
V.add(throttle, inputs=['pilot/throttle'])
Differential Drive
TwoWheelSteeringThrottle
Converts steering and throttle to individual wheel motor speeds.
Methods:
run
(throttle: float, steering: float) -> (float, float)
Returns (left_motor_speed, right_motor_speed) tuple
Usage Example:
from donkeycar.parts.actuator import TwoWheelSteeringThrottle
mixer = TwoWheelSteeringThrottle()
V.add(mixer,
inputs=['pilot/throttle', 'pilot/angle'],
outputs=['left_motor_speed', 'right_motor_speed'])
L298N_HBridge_3pin
DC motor controller using L298N H-bridge with 3-pin configuration.
Constructor:
L298N_HBridge_3pin(pin_forward, pin_backward, pwm_pin, zero_throttle=0, max_duty=0.9)
GPIO pin for forward direction
GPIO pin for backward direction
PWM pin for motor speed control
Throttle deadzone threshold
Maximum duty cycle (0 to 1)
Methods:
run
(throttle: float) -> None
Set motor speed and direction from throttle (-1 to 1)
L298N_HBridge_2pin
DC motor controller using L298N H-bridge with 2-pin PWM configuration.
Constructor:
L298N_HBridge_2pin(pin_forward, pin_backward, zero_throttle=0, max_duty=0.9)
PWM pin for forward control
PWM pin for backward control
Throttle deadzone threshold
Maximum duty cycle (0 to 1)
Methods:
run
(throttle: float) -> None
Set motor speed and direction from throttle (-1 to 1)
Specialized Controllers
VESC
VESC motor controller for electric skateboards.
Constructor:
VESC(serial_port, percent=0.2, has_sensor=False, start_heartbeat=True,
baudrate=115200, timeout=0.05, steering_scale=1.0, steering_offset=0.0)
Serial port path (e.g., /dev/ttyACM1)
Maximum duty cycle percentage (-1 to 1)
Steering servo scaling factor
Installation:
pip install git+https://github.com/LiamBindle/PyVESC.git@master
Methods:
run
(angle: float, throttle: float) -> None
Set servo angle and motor duty cycle
Configuration
Typical actuator configuration in myconfig.py:
# PWM Configuration
STEERING_CHANNEL = 1
STEERING_LEFT_PWM = 460
STEERING_RIGHT_PWM = 290
THROTTLE_CHANNEL = 0
THROTTLE_FORWARD_PWM = 500
THROTTLE_STOPPED_PWM = 370
THROTTLE_REVERSE_PWM = 220
# PCA9685
PCA9685_I2C_ADDR = 0x40
PCA9685_I2C_BUSNUM = 1
Integration Example
From templates like complete.py:
from donkeycar.parts.actuator import PulseController, PWMSteering, PWMThrottle
from donkeycar.parts.pins import PCA9685PwmPin
# Create PWM pins
steering_pin = PCA9685PwmPin(channel=cfg.STEERING_CHANNEL, frequency=60)
throttle_pin = PCA9685PwmPin(channel=cfg.THROTTLE_CHANNEL, frequency=60)
# Create controllers
steering_controller = PulseController(steering_pin)
throttle_controller = PulseController(throttle_pin)
# Create steering and throttle parts
steering = PWMSteering(controller=steering_controller,
left_pulse=cfg.STEERING_LEFT_PWM,
right_pulse=cfg.STEERING_RIGHT_PWM)
throttle = PWMThrottle(controller=throttle_controller,
max_pulse=cfg.THROTTLE_FORWARD_PWM,
min_pulse=cfg.THROTTLE_REVERSE_PWM,
zero_pulse=cfg.THROTTLE_STOPPED_PWM)
V.add(steering, inputs=['pilot/angle'])
V.add(throttle, inputs=['pilot/throttle'])