Practical case: PWM servo on RP2040 + iCE40UP5K (Pico-ICE)

Practical case: PWM servo on RP2040 + iCE40UP5K (Pico-ICE) — hero

Objective and use case

What you’ll build: A low-jitter PWM servo controller on the Raspberry Pi Pico-ICE (RP2040 + iCE40UP5K) that accurately controls servo angles via USB commands.

Why it matters / Use cases

  • Control hobby servos in robotics projects, ensuring precise movement for tasks like robotic arms or automated camera gimbals.
  • Implement in educational kits for teaching students about PWM signals and servo mechanics in electronics courses.
  • Utilize in remote-controlled vehicles where accurate steering and movement are critical for performance.
  • Integrate with IoT devices to allow remote control of physical systems, enhancing automation in smart homes.

Expected outcome

  • Achieve stable PWM signals at 50 Hz with less than 1 ms jitter, ensuring smooth servo operation.
  • Validate servo angle commands with a response time of under 100 ms from USB command to servo movement.
  • Measure power consumption of the servo under load, aiming for less than 500 mA at 5 V during operation.
  • Record successful angle adjustments with a precision of ±1 degree across a range of 0 to 180 degrees.

Audience: Intermediate electronics enthusiasts; Level: Medium

Architecture/flow: Raspberry Pi Pico-ICE controls servo via PWM signals generated from C program, interfaced through USB CDC commands.

This medium‑level practical walks you through building a reliable, low‑jitter PWM servo controller on the Raspberry Pi Pico‑form‑factor board Pico‑ICE (RP2040 + iCE40UP5K), using a Raspberry Pi as the development host. You’ll compile a C program with the Raspberry Pi Pico SDK to generate 50 Hz PWM signals suitable for hobby servos, flash the firmware to the board, send angle commands over USB CDC, and validate the results both functionally (servo motion) and instrumentally (timing checks).

The project focuses strictly on pwm-servo-control: stable, accurate pulse timing, proper power wiring for the servo, and a simple USB serial protocol for commanding angles.

The host system is Raspberry Pi OS Bookworm 64‑bit with Python 3.11, as requested.


Prerequisites

  • A Raspberry Pi 4/400/5 running Raspberry Pi OS Bookworm 64‑bit, fully updated.
  • Python 3.11 (default on Bookworm) and basic familiarity with virtual environments.
  • Comfortable with terminal/CLI operations.
  • Basic knowledge of C and CMake (to build the RP2040 firmware).
  • A micro servo (e.g., SG90 or MG90S) and a stable 5 V power source for the servo.

Notes:
– The servo must not be powered from the RP2040 3V3 pin. Use a dedicated 5 V supply for the servo. The grounds of the servo supply and the Pico‑ICE must be common.


Materials

  • Pico‑ICE (RP2040 + iCE40UP5K)
  • Raspberry Pi 4/400/5 with Raspberry Pi OS Bookworm 64‑bit
  • Micro servo (e.g., TowerPro SG90 or MG90S)
  • External 5 V servo power supply (≥ 1 A recommended for small servos; higher if under load)
  • Male‑to‑female jumper wires
  • Micro‑USB cable (data‑capable) to connect Pico‑ICE to Raspberry Pi
  • Optional: USB logic analyzer or oscilloscope for signal validation

Setup/Connection

1) Raspberry Pi OS configuration

Update the Pi and install required tools:

sudo apt update
sudo apt full-upgrade -y
sudo apt install -y git cmake build-essential gcc-arm-none-eabi libnewlib-arm-none-eabi picotool minicom

Enable common interfaces via raspi-config (useful defaults, even though this project uses USB CDC):

sudo raspi-config
# Interface Options:
#   - I2C: Enable
#   - SPI: Enable
#   - Serial: Disable login shell over serial, but keep serial hardware enabled if you want it available.
# Finish and reboot when prompted.

Alternatively, edit /boot/firmware/config.txt directly:

sudo nano /boot/firmware/config.txt

Add or ensure these lines (optional but recommended defaults):

dtparam=i2c_arm=on
dtparam=spi=on
enable_uart=1

Save and reboot:

sudo reboot

Add your user to the dialout group to access serial devices:

sudo usermod -aG dialout $USER
# Log out and log back in (or reboot) for group change to take effect.

2) Python 3.11 virtual environment and packages

Create and activate a venv for host‑side tooling and tests:

python3 -m venv ~/venvs/pico
source ~/venvs/pico/bin/activate
python -V
# Expect Python 3.11.x
pip install --upgrade pip wheel
pip install pyserial gpiozero smbus2 spidev
  • We’ll use pyserial for commanding the RP2040 over USB CDC.
  • gpiozero, smbus2, spidev are installed as common defaults; they are not strictly required for this tutorial but match the family defaults used across Raspberry Pi projects.

Deactivate later with deactivate when done.

3) Physical wiring

Use the external 5 V supply to power the servo. Connect grounds together:

  • Servo V+ (usually red) to 5 V external supply +
  • Servo GND (usually brown/black) to external supply −
  • Servo Signal (usually yellow/orange) to RP2040 GPIO pin (we’ll use GP15)
  • Common ground: connect Pi/board ground to servo ground. The easiest is to connect a GND pin on the Pico‑ICE to the servo ground (and servo PSU ground) so all share the same reference.

Pico‑ICE is in the Raspberry Pi Pico form factor, so its edge pins match the Pico pinout. We’ll use GP15 which is convenient and PWM‑capable.

Connection summary:

Function Pico‑ICE (RP2040) Pin Servo Lead Notes
PWM signal output GP15 (physical pin 20) Signal (yellow/orange) 3.3 V logic OK for most hobby servos
Ground reference GND (e.g., pin 3/8/13) GND (brown/black) Must be common with 5 V servo PSU and Pi
5 V power to servo External 5 V PSU V+ (red) Do not power servo from 3V3 on the board

Important:
– Do NOT connect the servo V+ to the Pico‑ICE 3.3 V rail.
– Most small servos accept a 3.3 V logic signal; if your servo requires 5 V logic, use a level shifter for the signal line.
– Keep wiring short to reduce noise; noisy servo current can induce glitches if grounds are poorly connected.


Full Code

We will build a C program using the Raspberry Pi Pico SDK that:
– Configures a PWM slice at exactly 50 Hz (20 ms period) with 1 µs resolution.
– Maps angle commands (0–180 degrees) to pulse widths (500–2500 µs).
– Exposes a simple USB CDC interface: send angle in degrees (integer or float) as a line, and the firmware updates the servo pulse width and prints confirmation.

1) CMake configuration (CMakeLists.txt)

Create a project directory, e.g., ~/pico-servo, and place this CMakeLists.txt file inside:

cmake_minimum_required(VERSION 3.13)

set(PICO_BOARD pico)  # Pico-ICE follows Pico form factor; RP2040 target is standard
set(PICO_SDK_FETCH_FROM_GIT OFF)

project(pico_servo C CXX ASM)
set(CMAKE_C_STANDARD 11)
set(CMAKE_CXX_STANDARD 17)

# Adjust this path if you keep pico-sdk somewhere else:
if(NOT DEFINED PICO_SDK_PATH)
    set(PICO_SDK_PATH "$ENV{PICO_SDK_PATH}")
endif()

if(NOT EXISTS "${PICO_SDK_PATH}/pico_sdk_init.cmake")
    message(FATAL_ERROR "PICO_SDK_PATH is not set correctly. Expected pico_sdk_init.cmake under ${PICO_SDK_PATH}")
endif()

include(${PICO_SDK_PATH}/pico_sdk_init.cmake)
pico_sdk_init()

add_executable(servo_pwm
    src/servo_pwm.c
)

target_link_libraries(servo_pwm
    pico_stdlib
    hardware_pwm
)

# USB CDC stdio enabled; UART stdio disabled
pico_enable_stdio_usb(servo_pwm 1)
pico_enable_stdio_uart(servo_pwm 0)

pico_add_extra_outputs(servo_pwm)

2) RP2040 firmware (src/servo_pwm.c)

Create src/servo_pwm.c with the following content:

#include <stdio.h>
#include <string.h>
#include "pico/stdlib.h"
#include "hardware/pwm.h"
#include "hardware/gpio.h"

#define SERVO_PIN 15

// 50 Hz PWM => 20 ms period. We'll set PWM clock to 1 MHz => 1 tick = 1 us.
// Then top = 20000 - 1, and duty (level) equals desired pulse width in microseconds.
static void pwm_servo_init(uint gpio_pin) {
    gpio_set_function(gpio_pin, GPIO_FUNC_PWM);
    uint slice_num = pwm_gpio_to_slice_num(gpio_pin);
    // Set clock divider to get 1 MHz from default 125 MHz system clock
    pwm_set_clkdiv(slice_num, 125.0f); // 125 MHz / 125 = 1 MHz
    // 20,000 ticks per 20 ms (50 Hz)
    pwm_set_wrap(slice_num, 20000 - 1);
    // Start with neutral 1500 us
    uint channel = pwm_gpio_to_channel(gpio_pin);
    pwm_set_chan_level(slice_num, channel, 1500);
    pwm_set_enabled(slice_num, true);
}

static uint16_t microseconds_from_degrees(float deg) {
    // Clamp 0..180 degrees
    if (deg < 0.0f) deg = 0.0f;
    if (deg > 180.0f) deg = 180.0f;
    // Map 0..180 deg to 500..2500 us
    float us = 500.0f + (deg * (2000.0f / 180.0f));
    // Final clamp
    if (us < 500.0f) us = 500.0f;
    if (us > 2500.0f) us = 2500.0f;
    return (uint16_t)(us + 0.5f);
}

static void pwm_servo_write_deg(uint gpio_pin, float deg) {
    uint slice_num = pwm_gpio_to_slice_num(gpio_pin);
    uint channel = pwm_gpio_to_channel(gpio_pin);
    uint16_t us = microseconds_from_degrees(deg);
    pwm_set_chan_level(slice_num, channel, us);
}

static void sweep_demo(uint gpio_pin) {
    // Simple sweep for validation when no USB commands are sent yet
    for (float d = 0; d <= 180; d += 5.0f) {
        pwm_servo_write_deg(gpio_pin, d);
        sleep_ms(30);
    }
    for (float d = 180; d >= 0; d -= 5.0f) {
        pwm_servo_write_deg(gpio_pin, d);
        sleep_ms(30);
    }
}

int main() {
    stdio_init_all();
    sleep_ms(1000); // give USB time to enumerate

    pwm_servo_init(SERVO_PIN);
    printf("servo_pwm: ready. Send angle in degrees (0-180) or 'SWEEP'.\r\n");

    // Non-blocking check for input; if nothing, run a gentle sweep occasionally.
    absolute_time_t last_sweep = get_absolute_time();

    char buf[64] = {0};
    size_t idx = 0;

    while (true) {
        int ch = getchar_timeout_us(1000); // poll every 1 ms
        if (ch != PICO_ERROR_TIMEOUT) {
            if (ch == '\r' || ch == '\n') {
                buf[idx] = '\0';
                if (idx > 0) {
                    // Parse command
                    if (strcasecmp(buf, "SWEEP") == 0) {
                        printf("CMD: SWEEP\r\n");
                        sweep_demo(SERVO_PIN);
                        printf("SWEEP: done\r\n");
                    } else {
                        // Try to parse float degrees
                        float degrees = -1.0f;
                        if (sscanf(buf, "%f", &degrees) == 1) {
                            if (degrees < 0.0f) degrees = 0.0f;
                            if (degrees > 180.0f) degrees = 180.0f;
                            pwm_servo_write_deg(SERVO_PIN, degrees);
                            printf("SET: %.1f deg\r\n", degrees);
                        } else {
                            printf("ERR: expected number or SWEEP, got '%s'\r\n", buf);
                        }
                    }
                }
                idx = 0; // reset buffer
            } else if (idx < sizeof(buf) - 1) {
                buf[idx++] = (char)ch;
            } else {
                // overflow, reset
                idx = 0;
            }
        }

        // If no command received for a while, show an occasional sweep (optional)
        if (absolute_time_diff_us(last_sweep, get_absolute_time()) > 5 * 1000 * 1000) {
            sweep_demo(SERVO_PIN);
            last_sweep = get_absolute_time();
        }
    }

    return 0;
}

Key choices:
– PWM clock divider = 125 so 125 MHz / 125 = 1 MHz. That yields 1 µs resolution.
– PWM wrap = 20,000 − 1 for a 20 ms period (50 Hz).
– Pulse width = microseconds equals PWM channel level directly.
– Command protocol: send “SWEEP” to perform a sweep; send a number like “90” to set 90 degrees. Firmware echos status on USB CDC.


Build/Flash/Run Commands

1) Fetch the Pico SDK (v2.0.0) and set environment

cd ~
git clone --branch 2.0.0 --depth 1 https://github.com/raspberrypi/pico-sdk.git
echo 'export PICO_SDK_PATH=$HOME/pico-sdk' >> ~/.bashrc
source ~/.bashrc

Verify:

test -f $PICO_SDK_PATH/pico_sdk_init.cmake && echo "PICO_SDK_PATH OK"

2) Create project and build

mkdir -p ~/pico-servo/src
cd ~/pico-servo
# Create CMakeLists.txt and src/servo_pwm.c as shown above
mkdir build
cd build
cmake -DPICO_SDK_PATH=$PICO_SDK_PATH ..
make -j4

If successful, you’ll get servo_pwm.uf2 in ~/pico-servo/build/.

3) Flash the firmware to Pico‑ICE

Method A (BOOTSEL mass storage, simplest):

  1. Unplug the Pico‑ICE from USB.
  2. Hold the BOOTSEL button on the board.
  3. While holding, plug the board into the Raspberry Pi via USB.
  4. A volume named RPI-RP2 should appear at /media/pi/RPI-RP2 (or similar).
  5. Copy the UF2:
cp ~/pico-servo/build/servo_pwm.uf2 /media/$USER/RPI-RP2/

The board will reboot and enumerate as a USB serial device (ttyACM).

Method B (picotool, once USB CDC is running):

  • With the board connected and enumerated, identify:
picotool info -a
  • If the device is bootloader‑ready (e.g., previous boot into BOOTSEL), you can load via:
picotool load -x ~/pico-servo/build/servo_pwm.uf2

Most first‑time flashes are easiest with Method A.

4) Open the USB serial console

Find the device (usually /dev/ttyACM0):

ls -l /dev/ttyACM*

Use minicom:

sudo minicom -b 115200 -o -D /dev/ttyACM0

Or use Python/pyserial (see next section) to send commands and read responses without minicom.


Host Test Script (send commands from Raspberry Pi)

Create a simple Python tool that can set an angle or run a sweep:

#!/usr/bin/env python3
import argparse
import sys
import time
import serial

def main():
    parser = argparse.ArgumentParser(description="Send angle/sweep commands to Pico-ICE servo controller over USB CDC.")
    parser.add_argument("--port", default="/dev/ttyACM0", help="Serial port (default: /dev/ttyACM0)")
    parser.add_argument("--baud", type=int, default=115200, help="Baud rate (default: 115200)")
    sub = parser.add_subparsers(dest="cmd", required=True)
    p_set = sub.add_parser("set", help="Set angle in degrees (0..180)")
    p_set.add_argument("angle", type=float)
    sub.add_parser("sweep", help="Run a sweep demo on the board")
    args = parser.parse_args()

    try:
        with serial.Serial(args.port, args.baud, timeout=1) as ser:
            time.sleep(0.5)  # give CDC time
            if args.cmd == "set":
                line = f"{args.angle:.1f}\n"
                ser.write(line.encode("ascii"))
                reply = ser.readline().decode(errors="ignore").strip()
                print("Board:", reply)
            elif args.cmd == "sweep":
                ser.write(b"SWEEP\n")
                # Read multiple lines during sweep
                t0 = time.time()
                while time.time() - t0 < 6.0:
                    line = ser.readline().decode(errors="ignore").strip()
                    if line:
                        print("Board:", line)
    except serial.SerialException as e:
        print(f"Serial error: {e}", file=sys.stderr)
        sys.exit(1)

if __name__ == "__main__":
    main()

Save as ~/pico-servo/tools/servo_cli.py and make it executable:

mkdir -p ~/pico-servo/tools
nano ~/pico-servo/tools/servo_cli.py
chmod +x ~/pico-servo/tools/servo_cli.py

Run examples:

source ~/venvs/pico/bin/activate
python ~/pico-servo/tools/servo_cli.py --port /dev/ttyACM0 set 90
python ~/pico-servo/tools/servo_cli.py --port /dev/ttyACM0 set 0
python ~/pico-servo/tools/servo_cli.py --port /dev/ttyACM0 set 180
python ~/pico-servo/tools/servo_cli.py --port /dev/ttyACM0 sweep

Expected responses include lines like:
– “SET: 90.0 deg”
– “CMD: SWEEP”
– “SWEEP: done”


Step‑by‑step Validation

1) Power and enumeration
– Ensure servo’s 5 V supply is on and the ground is common to the Pico‑ICE ground.
– Connect the Pico‑ICE via USB to the Raspberry Pi.
– Check device enumeration:

lsusb | grep -i "Raspberry Pi"
ls -l /dev/ttyACM*

You should see /dev/ttyACM0 (or ACM1 if multiple devices).

2) Firmware stdout greeting
– Run minicom or the Python script to read the greeting message:

sudo minicom -b 115200 -o -D /dev/ttyACM0
# Expected: "servo_pwm: ready. Send angle in degrees (0-180) or 'SWEEP'."
  • Or with Python:
source ~/venvs/pico/bin/activate
python - << 'PY'
import serial, time
ser = serial.Serial('/dev/ttyACM0',115200,timeout=2)
time.sleep(0.5)
print(ser.readline().decode(errors='ignore').strip())
ser.close()
PY

3) Functional servo test
– Command mid position:

python ~/pico-servo/tools/servo_cli.py --port /dev/ttyACM0 set 90

Observe the horn move to the midpoint. Adjust to 0 and 180:

python ~/pico-servo/tools/servo_cli.py --port /dev/ttyACM0 set 0
python ~/pico-servo/tools/servo_cli.py --port /dev/ttyACM0 set 180

If your servo binds at mechanical endpoints, prefer 10..170 instead of exact 0..180.

4) Sweep test
– Trigger a sweep for visual verification:

python ~/pico-servo/tools/servo_cli.py --port /dev/ttyACM0 sweep

The servo should move smoothly back and forth. If motion is jerky, check power and mechanical load.

5) Timing validation (optional but recommended)
– Use a logic analyzer/oscilloscope to probe the signal at GP15 with respect to ground.
– You should see:
– Period ~ 20 ms (50 Hz).
– High pulse width varies with command:
– ~500 µs at 0°
– ~1500 µs at 90°
– ~2500 µs at 180°
– A software alternative (rough check) is to loop back GP15 to another RP2040 input and timestamp edges; however, a scope/LA is more reliable for absolute timing.

6) Consistency over time
– Let the system run for several minutes with random angle updates:

for a in 0 45 90 135 180 135 90 45 0; do \
  python ~/pico-servo/tools/servo_cli.py --port /dev/ttyACM0 set $a; sleep 1; \
done
  • Observe that the servo holds position with no audible buzzing (minor holding noise is normal) and without thermal runaway. If it buzzes excessively at stationary angles, check pulse timing on a scope; ensure stable 50 Hz with correct pulse widths.

Troubleshooting

  • Servo twitches or resets the board when moving:
  • Almost always power related. Use a separate 5 V supply for the servo. Do not draw servo current from the Raspberry Pi USB port via the board. Ensure grounds are tied together.
  • Add a bulk capacitor (e.g., 470 µF) across the servo PSU near the servo connector to absorb transients.

  • No /dev/ttyACM0 appears:

  • Reflash via BOOTSEL method to ensure the board has valid USB CDC firmware.
  • Try another cable (ensure it is data‑capable).
  • Check dmesg -w when plugging the board to see enumeration messages.
  • Ensure sudo usermod -aG dialout $USER and re‑login.

  • Minicom shows gibberish or nothing:

  • Confirm 115200 8N1.
  • Wait ~1 s after opening the port to let the USB CDC set up.
  • Use Python/pyserial which auto‑flushes line endings.

  • Servo doesn’t respond but serial replies are OK:

  • Verify the signal wire is on GP15 and not VBUS/3V3 by mistake.
  • Confirm the servo’s ground is common with the board’s ground.
  • Some servos prefer 1000–2000 µs. Adjust limits in code (microseconds_from_degrees) or try 10..170 degrees.

  • Angle 0 or 180 causes binding:

  • Mechanical end‑stop limitations vary. Restrict to 10–170 or manufacturer‑specified safe range.

  • PWM jitter visible on scope:

  • Ensure no heavy compute in the main loop that would starve the PWM config (shouldn’t happen because the PWM peripheral runs independently once configured).
  • Avoid frequent pwm_set_chan_level at a high rate; update levels at human‑rate (tens of Hz). The provided code updates only on command or during sweeps.

  • Build fails (pico_sdk_init.cmake not found):

  • Ensure export PICO_SDK_PATH=$HOME/pico-sdk is present and sourced (source ~/.bashrc), or pass -DPICO_SDK_PATH=$HOME/pico-sdk to cmake (as shown).
  • Check you cloned the 2.0.0 tag.

  • Using the wrong pin:

  • Pico‑ICE follows the Pico pinout; GP15 is physical pin 20 on the Pico header. Double‑check mapping if you use a different pin; all RP2040 GPIOs are PWM‑capable, but verify your wiring.

Improvements

  • Multiple servo channels:
  • RP2040 PWM has 8 slices × 2 channels = up to 16 outputs, though with shared wrap per slice. For 50 Hz at 1 µs resolution, all channels can share the same wrap/clock. Assign different GPIOs to different channels and set per‑channel levels.
  • Ensure your 5 V supply current scales with the number of servos.

  • Acceleration and jerk limiting:

  • Implement smooth transitions (trapezoidal or S‑curve) to reduce mechanical stress and power spikes. Instead of jumping to a new duty immediately, step it over tens of milliseconds.

  • Calibrated endpoints:

  • Allow user calibration to map 0..180 degrees to servo‑specific µs limits (e.g., 600..2400 µs) stored in flash.

  • Offload generator to iCE40UP5K:

  • For advanced timing robustness, implement a multi‑channel 50 Hz pulse generator in the iCE40UP5K fabric and let RP2040 write target pulse widths via SPI or PIO. This guarantees cycle‑exact timing under any CPU load.

  • Host GUI:

  • Use Python (Tkinter or PyQt) to create a simple control UI to set angles, sweeps, and calibrations. Keep the serial protocol simple (“
    ”, “SWEEP”).

  • Feedback loop:

  • For servos with feedback (or using external potentiometers/encoders), read back position via ADC or I2C sensors and close the loop in firmware.

Final Checklist

  • Raspberry Pi OS Bookworm 64‑bit up to date; toolchain installed:
  • git, cmake, gcc‑arm‑none‑eabi, libnewlib‑arm‑none‑eabi, picotool
  • Interfaces configured:
  • Optional but common: I2C on, SPI on, UART enabled (console disabled), via raspi‑config or /boot/firmware/config.txt
  • Python environment:
  • venv created and activated; pyserial installed (gpiozero, smbus2, spidev also installed per family defaults)
  • Hardware wiring:
  • Servo V+ to external 5 V; servo GND to PSU ground; Pico‑ICE GND connected to same ground; servo signal to GP15 (physical pin 20)
  • Build:
  • pico-sdk v2.0.0 cloned; PICO_SDK_PATH set; project built with cmake/make; UF2 generated
  • Flash:
  • BOOTSEL method used to copy servo_pwm.uf2 to RPI-RP2; device enumerates as /dev/ttyACM0
  • Run and validate:
  • USB CDC serial greeting observed
  • Angle commands issued via Python CLI; servo moves to 0, 90, 180 as expected
  • Optional scope/LA verifies 50 Hz period and 500–2500 µs pulses
  • Stable operation:
  • No brown‑outs; minimal jitter; no mechanical binding at extremes
  • Next steps:
  • Add multiple channels, smoothing, calibration, or FPGA‑based PWM engine

This completes the pwm-servo-control project on the Pico‑ICE (RP2040 + iCE40UP5K) using a Raspberry Pi host.

Find this product and/or books on this topic on Amazon

Go to Amazon

As an Amazon Associate, I earn from qualifying purchases. If you buy through this link, you help keep this project running.

Quick Quiz

Question 1: What type of board is used for the PWM servo controller in this project?




Question 2: Which programming language is primarily used to compile the firmware for the RP2040?




Question 3: What is the recommended frequency for the PWM signals generated in this project?




Question 4: What power supply is recommended for the servo in this project?




Question 5: Which version of Raspberry Pi OS is used for this project?




Question 6: What type of servo is mentioned as an example in the project?




Question 7: What is a prerequisite for this project regarding Python?




Question 8: What type of cable is required to connect Pico-ICE to Raspberry Pi?




Question 9: What is the purpose of the USB logic analyzer or oscilloscope in this project?




Question 10: What is the maximum voltage that should be supplied to the servo?




Carlos Núñez Zorrilla
Carlos Núñez Zorrilla
Electronics & Computer Engineer

Telecommunications Electronics Engineer and Computer Engineer (official degrees in Spain).

Follow me:
error: Contenido Protegido / Content is protected !!
Scroll to Top