From 83b568373d997806f1a19fb59be4c6ae9518d334 Mon Sep 17 00:00:00 2001 From: Daniel Ritchie Date: Thu, 30 Oct 2025 19:17:24 -0600 Subject: [PATCH 1/2] adds ability to modify motor pid values arbitrarily --- tools/modify_motor_pid.py | 247 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 247 insertions(+) create mode 100644 tools/modify_motor_pid.py diff --git a/tools/modify_motor_pid.py b/tools/modify_motor_pid.py new file mode 100644 index 00000000..e7aa0e69 --- /dev/null +++ b/tools/modify_motor_pid.py @@ -0,0 +1,247 @@ +# modify_motor_pid.py +""" +Reachy Mini Motor PID Configuration Tool + +A utility for reading and modifying PID (Proportional-Integral-Derivative) gains +on Reachy Mini robot motors. Supports auto-detection of serial ports and includes +validation to ensure sane PID values. + +Author: Daniel Ritchie +GitHub: @brainwavecoder9 +Discord: LeDaniel (quantumpoet) + +Usage: + python modify_motor_pid.py # Print current values Only (No Changes) + python modify_motor_pid.py -d 200 # Set D gain + python modify_motor_pid.py -p 400 -i 0 -d 200 # Set multiple gains + python modify_motor_pid.py --motor-id 11 -d 150 # Configure different motor + python modify_motor_pid.py --serialport COM6 # Specify serial port + python modify_motor_pid.py --help # Show detailed help + +For more detailed parameter information, run with --help flag. +""" + +from reachy_mini_motor_controller import ReachyMiniPyControlLoop +from reachy_mini.daemon.utils import find_serial_port +from datetime import timedelta +import struct +import time +import argparse + +__version__ = "1.0.0" +__author__ = "Daniel Ritchie" +__github__ = "@brainwavecoder9" + +# PID value ranges (based on typical motor controller limits) +PID_RANGES = { + 'p': (0, 16383), # P gain: 0 to 16383 (typical max for 14-bit) + 'i': (0, 16383), # I gain: 0 to 16383 + 'd': (0, 16383), # D gain: 0 to 16383 +} + +# Register addresses for PID gains +PID_REGISTERS = { + 'p': 84, # P gain register (Kpp) + 'i': 82, # I gain register (Kpi) + 'd': 80, # D gain register (Kpd) +} + +# Conversion factors for display +PID_CONVERSION = { + 'p': 128, # Kpp = P / 128 + 'i': 2048, # Kpi = I / 2048 + 'd': 16, # Kpd = D / 16 +} + +def validate_pid_value(gain_type, value): + """Validate that a PID value is within acceptable range.""" + min_val, max_val = PID_RANGES[gain_type] + if not (min_val <= value <= max_val): + raise ValueError( + f"{gain_type.upper()} gain must be between {min_val} and {max_val}, got {value}" + ) + return value + +def read_pid_values(controller, motor_id): + """Read current P, I, D values from the motor.""" + p_val = struct.unpack(' 1: + raise RuntimeError( + f"Multiple Reachy Mini serial ports found: {ports}. " + f"Please specify port with --serialport COM6" + ) + + serialport = ports[0] + print(f"✅ Found Reachy Mini serial port: {serialport}\n") + + motor_id = args.motor_id + print(f"Connecting to motor ID {motor_id}...") + + c = ReachyMiniPyControlLoop( + serialport, + read_position_loop_period=timedelta(seconds=0.02), + allowed_retries=5, + stats_pub_period=None, + ) + + try: + # Read current values + print("\n" + "="*50) + print("CURRENT PID VALUES:") + print("="*50) + p_before, i_before, d_before = read_pid_values(c, motor_id) + print_pid_values(p_before, i_before, d_before) + + # If no changes requested, just exit + if not changes: + print("\n✅ No changes requested. Done!") + return + + # Apply changes + print("\n" + "="*50) + print("APPLYING CHANGES:") + print("="*50) + + c.disable_torque() + time.sleep(0.2) + + for gain_type, new_value in changes.items(): + register = PID_REGISTERS[gain_type] + print(f"Setting {gain_type.upper()} = {new_value}...") + c.async_write_raw_bytes(motor_id, register, list(struct.pack(' Date: Thu, 30 Oct 2025 19:27:31 -0600 Subject: [PATCH 2/2] light cleanup on help comments --- tools/modify_motor_pid.py | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) diff --git a/tools/modify_motor_pid.py b/tools/modify_motor_pid.py index e7aa0e69..5fdb21c8 100644 --- a/tools/modify_motor_pid.py +++ b/tools/modify_motor_pid.py @@ -6,8 +6,7 @@ on Reachy Mini robot motors. Supports auto-detection of serial ports and includes validation to ensure sane PID values. -Author: Daniel Ritchie -GitHub: @brainwavecoder9 +Author: Daniel Ritchie (@brainwavecoder9) Discord: LeDaniel (quantumpoet) Usage: @@ -85,9 +84,9 @@ def main(): and clear before/after reporting. PID Parameters: - P (Proportional): Determines response to current error (typical: 400) - I (Integral): Determines response to accumulated error (typical: 0) - D (Derivative): Determines response to rate of error change (typical: 0-200) + P (Proportional): Determines response to current error (e.g.: 400) + I (Integral): Determines response to accumulated error (e.g.: 0) + D (Derivative): Determines response to rate of error change (e.g.: 200) Register Addresses: P Gain: Address 84 (Kpp = P / 128) @@ -131,9 +130,6 @@ def main(): - Changes are verified after writing - Torque is re-enabled after successful changes -For issues or questions: - GitHub: https://github.com/brainwavecollective/reachy_mini - Discord: LeDaniel (quantumpoet) """ )