Avoiding calibration upon startup

It would seem that I should be able to save the motor calibration so that when the system is powered up I can simply command each axis to the AXIS_STATE_CLOSED_LOOP_CONTROL state.

I tried setting up the Encoder with Index configuration, did the odrv0.save_configuratio() command, but when I restart I am forced to issue the following commands from the odrive tool every time:

odrv0.axis0.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE

odrv0.axis1.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE

Followed by:

odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL

odrv0.axis1.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL

Then I can issue position commands. What am I missing?

You can set it to go do a index pulse search and go into closed loop control on startup

Did you set motor and encoder precaibrated then save after calibration? You may need to set pre calibration to false prior to running detection, and always make sure to set all axes to idle before saving

Thank you. Is there link to some kind of documentation that explains this?

I have been through the Getting Started Link.

There was also a link for Encoders, which I will revisit and see what I might have missed.

The documentation is pretty scattered but it’s all there, just make sure you have the right version of the page

Alternatively follow my code, it seems to work

Here is the revised version of that code, VSM motors (6354 190kv) run trapezoidal trajectory position control and belt motors (63100 190kv) run ramped velocity control for reference, both use AMT102-v 8192 CPR encoders with index, the VSM code works flawlessly but I haven’t been able to test the belt code since the encoders are not mounted yet (switching from halls to encoders)

This is a long one

‘’’
‘’’

VSTA002.py written by Zachary The’ on October 11th, 2022 for HORC Lab VST 2.0
Contact at +1 (302) 753-3570 or thezach@udel.edu

For odrive info visit Getting Started — ODrive Documentation 0.5.5 documentation
Using ODrive v3.6-56V

To install/update odrivetool run … in command window
pip install --upgrade odrive
Running ODrive control utility v0.6.3

To install missing modules run … or … in command window
conda install -c conda-forge
pip install

Ro resolve USB issues visit https://zadig.akeo.ie/
Run application, Options > List All Devices, ODrive 3.6 Native Interface (Interface 2), libusb-win32 (v.1.2.6.0), Install Driver

To update odrive firmware run … in command window, use Zadig utility to set STM32 BOOTLOADER to libusb-win32
odrivetool dfu
Running v0.5.5.0

To open plotter run …
odrivetool
import matplotlib
matplotlib.use(‘TkAgg’)
cancellation_token = start_liveplotter(lambda: [])

odrv0 → ODrive 316D335C3030 (patient left)
odrv1 → ODrive 3359365B3539 (patient right)

axis0 → VSM
axis1 → Belt

‘’’

import os
import sys
import time
from cmath import pi
from logging import exception

import odrive
from odrive.utils import *

def countdown(t, note):

print()

for i in range(t):
    if (t - i) > 1:
        print(f"\033[A{note}:  Please wait {t - i:.0f} seconds ")
    else:
        print(f"\033[A{note}:  Please wait 1 second   ")

    time.sleep(1)

os.system('cls')

def update_odrives(odrv0, odrv0_ID, odrv1, odrv1_ID, mode):

# Mode 0 --> save
# Mode 1 --> erase
# Mode 2 --> reboot

t = 3

odrv0.axis0.requested_state = 1
odrv0.axis1.requested_state = 1
odrv1.axis0.requested_state = 1
odrv1.axis1.requested_state = 1

try:
    if mode == 0:
        odrv0.save_configuration()
    elif mode == 1:
        odrv0.erase_configuration()
    else:
        odrv0.reboot()
except:
    pass

try:
    if mode == 0:
        odrv1.save_configuration()
    elif mode == 1:
        odrv1.erase_configuration()
    else:
        odrv1.reboot()
except:
    pass

if mode == 0:
    countdown(t, f"Saving ODrives")
elif mode == 1:
    countdown(t, f"Erasing ODrives")
else:
    countdown(t, f"Rebooting ODrives")

odrv0 = odrive.find_any(serial_number=odrv0_ID)
odrv1 = odrive.find_any(serial_number=odrv1_ID)

odrv0.axis0.requested_state = 1
odrv0.axis1.requested_state = 1
odrv1.axis0.requested_state = 1
odrv1.axis1.requested_state = 1

check_errors(odrv0, odrv1)

return odrv0, odrv1

def check_errors(odrv0, odrv1):

if odrv0.error or odrv1.error:
    odrv0.axis0.requested_state = 1
    odrv0.axis1.requested_state = 1

    odrv1.axis0.requested_state = 1
    odrv1.axis1.requested_state = 1

    os.system('cls')

    print(dump_errors(odrv0))
    print()
    input(dump_errors(odrv1))

    sys.exit()

def autocal_VSM(odrv0, odrv0_ID, odrv1, odrv1_ID):

# Write configurations
odrv0.axis0.config.startup_closed_loop_control = True  # {False}
odrv0.axis0.config.startup_encoder_index_search = True  # {False}
odrv0.axis0.controller.config.control_mode = 3  # position control {3}
odrv0.axis0.controller.config.input_mode = 5  # trap traj {1}
odrv0.axis0.controller.config.pos_gain = 15  # {20}
odrv0.axis0.controller.config.vel_gain = 0.1667  # {0.1667}
odrv0.axis0.controller.config.vel_integrator_gain = 10.3333  # {0.3333}
odrv0.axis0.controller.config.vel_limit = 66  # {2}
odrv0.axis0.encoder.config.use_index = True  # {False}
odrv0.axis0.motor.config.calibration_current = 20  # {10}
odrv0.axis0.motor.config.current_lim = 65  # {10}
odrv0.axis0.motor.config.current_lim_margin = 52  # {8}
odrv0.axis0.motor.config.requested_current_range = 130  # {60}
odrv0.axis0.motor.config.torque_constant = 8.27/190  # {0.04}
odrv0.axis0.trap_traj.config.accel_limit = 100  # {0.5}
odrv0.axis0.trap_traj.config.decel_limit = 100  # {0.5}
odrv0.axis0.trap_traj.config.vel_limit = 60  # {2}
odrv0.config.dc_max_positive_current = 20  # {inf}
odrv0.config.enable_brake_resistor = True  # {False}

odrv1.axis0.config.startup_closed_loop_control = True  # {False}
odrv1.axis0.config.startup_encoder_index_search = True  # {False}
odrv1.axis0.controller.config.control_mode = 3  # position control {3}
odrv1.axis0.controller.config.input_mode = 5  # trap traj {1}
odrv1.axis0.controller.config.pos_gain = 15  # {20}
odrv1.axis0.controller.config.vel_gain = 0.1667  # {0.1667}
odrv1.axis0.controller.config.vel_integrator_gain = 0.3333  # {0.3333}
odrv1.axis0.controller.config.vel_limit = 66  # {2}
odrv1.axis0.encoder.config.use_index = True  # {False}
odrv1.axis0.motor.config.calibration_current = 20  # {10}
odrv1.axis0.motor.config.current_lim = 65  # {10}
odrv1.axis0.motor.config.current_lim_margin = 52  # {8}
odrv1.axis0.motor.config.requested_current_range = 130  # {60}
odrv1.axis0.motor.config.torque_constant = 8.27/190  # {0.04}
odrv1.axis0.trap_traj.config.accel_limit = 100  # {0.5}
odrv1.axis0.trap_traj.config.decel_limit = 100  # {0.5}
odrv1.axis0.trap_traj.config.vel_limit = 60  # {2}
odrv1.config.dc_max_positive_current = 20  # {inf}
odrv1.config.enable_brake_resistor = True  # {False}

# Save configurations
odrv0, odrv1 = update_odrives(odrv0, odrv0_ID, odrv1, odrv1_ID, 0)

# Calibrate motors
str_in = input("Press ENTER to start VSM motor detection or X to skip\n")
os.system('cls')

if str_in in ['x', 'X']:
    pass
else:
    odrv0, odrv1 = calib_VSM(odrv0, odrv0_ID, odrv1, odrv1_ID)

# Anticog motors
str_in = input("Press ENTER to start VSM anticogging or X to skip\n")
os.system('cls')

if str_in in ['x', 'X']:
    pass
else:
    odrv0, odrv1 = anticog_VSM(odrv0, odrv0_ID, odrv1, odrv1_ID)

# Home motors
str_in = input("Press ENTER to start VSM homing or X to skip\n")
os.system('cls')

if str_in in ['x', 'X']:
    pass
else:
    odrv0, odrv1 = home_VSM(odrv0, odrv0_ID, odrv1, odrv1_ID)

return odrv0, odrv1

def calib_VSM(odrv0, odrv0_ID, odrv1, odrv1_ID):

# Write configurations
odrv0.axis0.encoder.config.pre_calibrated = False  # {False}
odrv0.axis0.motor.config.pre_calibrated = False  # {False}

odrv1.axis0.encoder.config.pre_calibrated = False  # {False}
odrv1.axis0.motor.config.pre_calibrated = False  # {False}

# Calibrate motors
odrv0.axis0.requested_state = 3
odrv1.axis0.requested_state = 3

countdown(18, f"Calibrating VSM motors")
os.system('cls')

# Check errors
check_errors(odrv0, odrv1)

# Write configurations
odrv0.axis0.encoder.config.pre_calibrated = True  # {False}
odrv0.axis0.motor.config.pre_calibrated = True  # {False}

odrv1.axis0.encoder.config.pre_calibrated = True  # {False}
odrv1.axis0.motor.config.pre_calibrated = True  # {False}

# Save configurations
odrv0, odrv1 = update_odrives(odrv0, odrv0_ID, odrv1, odrv1_ID, 0)

return odrv0, odrv1

def anticog_VSM(odrv0, odrv0_ID, odrv1, odrv1_ID):

# Index search
if (not odrv0.axis0.encoder.index_found) or (not odrv1.axis0.encoder.index_found):
    odrv0.axis0.requested_state = 6
    odrv1.axis0.requested_state = 6
    time.sleep(1)

# Check errors
check_errors(odrv0, odrv1)

# Write parameters
odrv0.axis0.controller.config.anticogging.pre_calibrated = False  # {False}
odrv0.axis0.controller.config.control_mode = 2  # velocity control {3}
odrv0.axis0.controller.config.input_mode = 1  # passthrough {1}
odrv0.axis0.controller.config.pos_gain = 10 * 20  # {20}
odrv0.axis0.controller.config.vel_gain = 0.1667  # {0.1667}
odrv0.axis0.controller.config.vel_integrator_gain = 10 * 0.3333  # {0.3333}
odrv0.axis0.controller.config.vel_limit = 2  # {2}

odrv1.axis0.controller.config.anticogging.pre_calibrated = False  # {False}
odrv1.axis0.controller.config.control_mode = 2  # velocity control {3}
odrv1.axis0.controller.config.input_mode = 1  # passthrough {1}
odrv1.axis0.controller.config.pos_gain = 10 * 20  # {20}
odrv1.axis0.controller.config.vel_gain = 0.1667  # {0.1667}
odrv1.axis0.controller.config.vel_integrator_gain = 10 * 0.3333  # {0.3333}
odrv1.axis0.controller.config.vel_limit = 2  # {2}

# Save configurations
odrv0, odrv1 = update_odrives(odrv0, odrv0_ID, odrv1, odrv1_ID, 0)

# Anticog motors
odrv0.axis0.requested_state = 8
odrv0.axis0.controller.start_anticogging_calibration()

odrv1.axis0.requested_state = 8
odrv1.axis0.controller.start_anticogging_calibration()

anticog0 = True
anticog1 = True

i0 = odrv0.axis0.encoder.pos_estimate_counts
i1 = odrv1.axis0.encoder.pos_estimate_counts

t = time.time()

time.sleep(1)

print()

while anticog0 or anticog1:
    if anticog0 and odrv0.axis0.controller.config.anticogging.calib_anticogging:
        com0 = abs(odrv0.axis0.encoder.pos_estimate_counts - i0) / 8192
    elif anticog0:
        odrv0.axis0.requested_state = 1
        # odrv0.axis0.encoder.set_linear_count(0)
        anticog0 = False
        com0 = 1

    if anticog1 and odrv1.axis0.controller.config.anticogging.calib_anticogging:
        com1 = abs(odrv1.axis0.encoder.pos_estimate_counts - i1) / 8192
    elif anticog1:
        odrv1.axis0.requested_state = 1
        # odrv1.axis0.encoder.set_linear_count(0)
        anticog1 = False
        com1 = 1

    dt = time.time() - t
    print(
        f"\033[AAnticogging VSM motors:  Please wait approximatly {(dt / min(com0, com1) - dt) :.0f} seconds ({dt:.0f} seconds elapsed, VSM 0 {100 * com0:.0f}% complete, VSM 1 {100 * com1:.0f}% complete)     ")

    # Check errors
    check_errors(odrv0, odrv1)

# Write configurations
odrv0.axis0.controller.config.anticogging.pre_calibrated = True  # {False}
odrv0.axis0.controller.config.control_mode = 3  # position control {3}
odrv0.axis0.controller.config.input_mode = 5  # trapazoidal {1}
odrv0.axis0.controller.config.pos_gain = 15  # {20}
odrv0.axis0.controller.config.vel_gain = 0.1667  # {0.1667}
odrv0.axis0.controller.config.vel_integrator_gain = 0.3333  # {0.3333}
odrv0.axis0.controller.config.vel_limit = 66  # {2}

odrv1.axis0.controller.config.anticogging.pre_calibrated = True  # {False}
odrv1.axis0.controller.config.control_mode = 3  # position control {3}
odrv1.axis0.controller.config.input_mode = 5  # trapazoidal {1}
odrv1.axis0.controller.config.pos_gain = 15  # {20}
odrv1.axis0.controller.config.vel_gain = 0.1667  # {0.1667}
odrv1.axis0.controller.config.vel_integrator_gain = 0.3333  # {0.3333}
odrv1.axis0.controller.config.vel_limit = 66  # {2}

# Save configurations
odrv0, odrv1 = update_odrives(odrv0, odrv0_ID, odrv1, odrv1_ID, 0)

return odrv0, odrv1

def home_VSM(odrv0, odrv0_ID, odrv1, odrv1_ID):

print("Homing VSM motors:  Please wait up to 30 seconds")

# Index search
if (not odrv0.axis0.encoder.index_found) or (not odrv1.axis0.encoder.index_found):
    odrv0.axis0.requested_state = 6
    odrv1.axis0.requested_state = 6
    time.sleep(1)

# Check errors
check_errors(odrv0, odrv1)

# Update parameters
odrv0.axis0.controller.config.control_mode = 2  # velocity control {3}
odrv0.axis0.controller.config.input_mode = 1  # passthrough {3}

odrv1.axis0.controller.config.control_mode = 2  # velocity control {3}
odrv1.axis0.controller.config.input_mode = 1  # passthrough {3}

# Start homing search
odrv0.axis0.requested_state = 8  # closed loop control
odrv0.axis0.controller.input_vel = -1

odrv1.axis0.requested_state = 8  # closed loop control
odrv1.axis0.controller.input_vel = -1

home0 = True
home1 = True

while home0 or home1:
    if home0 and abs(odrv0.axis0.motor.current_control.Iq_measured) > 20:
        odrv0.axis0.requested_state = 1
        odrv0.axis0.controller.input_vel = 0
        odrv0.axis0.encoder.set_linear_count(-1932)
        home0 = False

    if home1 and abs(odrv1.axis0.motor.current_control.Iq_measured) > 20:
        odrv1.axis0.requested_state = 1
        odrv1.axis0.controller.input_vel = 0
        odrv1.axis0.encoder.set_linear_count(-2151)
        home1 = False

    # Check errors
    check_errors(odrv0, odrv1)

# Update parameters
odrv0.axis0.controller.config.control_mode = 3  # position control {3}
odrv0.axis0.controller.config.input_mode = 5  # trapazoidal {1}

odrv1.axis0.controller.config.control_mode = 3  # position control {3}
odrv1.axis0.controller.config.input_mode = 5  # trapazoidal {1}

# Move infinite stiffness
odrv0.axis0.requested_state = 8  # closed loop control
odrv0.axis0.controller.input_pos = 0

odrv1.axis0.requested_state = 8  # closed loop control
odrv1.axis0.controller.input_pos = 0

time.sleep(1)

os.system('cls')

# Check errors
check_errors(odrv0, odrv1)

return odrv0, odrv1

def autocal_belt(odrv0, odrv0_ID, odrv1, odrv1_ID):

# Write configurations
odrv0.axis1.config.startup_closed_loop_control = True  # {False}
odrv0.axis1.config.startup_encoder_index_search = True  # {False}
odrv0.axis1.controller.config.control_mode = 2  # velocity control {3}
odrv0.axis1.controller.config.input_mode = 2  # vel ramp {1}
odrv0.axis1.controller.config.pos_gain = 15  # {20}
odrv0.axis1.controller.config.vel_gain = 0.1667  # {0.1667}
odrv0.axis1.controller.config.vel_integrator_gain = 10.3333  # {0.3333}
odrv0.axis1.controller.config.vel_limit = 114  # {2}
odrv0.axis1.controller.config.vel_ramp_rate = 8  # {1}
odrv0.axis1.encoder.config.use_index = True  # {False}
odrv0.axis1.motor.config.calibration_current = 20  # {10}
odrv0.axis1.motor.config.current_lim = 100  # {10}
odrv0.axis1.motor.config.current_lim_margin = 80  # {8}
odrv0.axis1.motor.config.requested_current_range = 200  # {60}
odrv0.axis1.motor.config.torque_constant = 8.27/190  # {0.04}
odrv0.config.dc_max_positive_current = 20  # {inf}
odrv0.config.enable_brake_resistor = True  # {False}

odrv1.axis1.config.startup_closed_loop_control = True  # {False}
odrv1.axis1.config.startup_encoder_index_search = True  # {False}
odrv1.axis1.controller.config.control_mode = 2  # velocity control {3}
odrv1.axis1.controller.config.input_mode = 2  # vel ramp {1}
odrv1.axis1.controller.config.pos_gain = 15  # {20}
odrv1.axis1.controller.config.vel_gain = 0.1667  # {0.1667}
odrv1.axis1.controller.config.vel_integrator_gain = 0.3333  # {0.3333}
odrv1.axis1.controller.config.vel_limit = 114  # {2}
odrv1.axis1.controller.config.vel_ramp_rate = 8  # {1}
odrv1.axis1.encoder.config.use_index = True  # {False}
odrv1.axis1.motor.config.calibration_current = 20  # {10}
odrv1.axis1.motor.config.current_lim = 100  # {10}
odrv1.axis1.motor.config.current_lim_margin = 80  # {8}
odrv1.axis1.motor.config.requested_current_range = 200  # {60}
odrv1.axis1.motor.config.torque_constant = 8.27/190  # {0.04}
odrv1.config.dc_max_positive_current = 20  # {inf}
odrv1.config.enable_brake_resistor = True  # {False}

# Save configurations
odrv0, odrv1 = update_odrives(odrv0, odrv0_ID, odrv1, odrv1_ID, 0)

# Calibrate motors
str_in = input("Press ENTER to start belt motor detection or X to skip\n")
os.system('cls')

if str_in in ['x', 'X']:
    pass
else:
    odrv0, odrv1 = calib_belt(odrv0, odrv0_ID, odrv1, odrv1_ID)

# Anticog motors
str_in = input("Press ENTER to start belt anticogging or X to skip\n")
os.system('cls')

if str_in in ['x', 'X']:
    pass
else:
    odrv0, odrv1 = anticog_belt(odrv0, odrv0_ID, odrv1, odrv1_ID)

return odrv0, odrv1

def calib_belt(odrv0, odrv0_ID, odrv1, odrv1_ID):

# Write configurations
odrv0.axis1.encoder.config.pre_calibrated = False  # {False}
odrv0.axis1.motor.config.pre_calibrated = False  # {False}

odrv1.axis1.encoder.config.pre_calibrated = False  # {False}
odrv1.axis1.motor.config.pre_calibrated = False  # {False}

# Calibrate motors
odrv0.axis1.requested_state = 3
odrv1.axis1.requested_state = 3

countdown(18, f"Calibrating belt motors")
os.system('cls')

# Check errors
check_errors(odrv0, odrv1)

# Write configurations
odrv0.axis1.encoder.config.pre_calibrated = True  # {False}
odrv0.axis1.motor.config.pre_calibrated = True  # {False}

odrv1.axis1.encoder.config.pre_calibrated = True  # {False}
odrv1.axis1.motor.config.pre_calibrated = True  # {False}

# Save configurations
odrv0, odrv1 = update_odrives(odrv0, odrv0_ID, odrv1, odrv1_ID, 0)

return odrv0, odrv1

def anticog_belt(odrv0, odrv0_ID, odrv1, odrv1_ID):

# Index search
if (not odrv0.axis1.encoder.index_found) or (not odrv1.axis1.encoder.index_found):
    odrv0.axis1.requested_state = 6
    odrv1.axis1.requested_state = 6
    time.sleep(1)

# Check errors
check_errors(odrv0, odrv1)

# Write parameters
odrv0.axis1.controller.config.anticogging.pre_calibrated = False  # {False}
odrv0.axis1.controller.config.input_mode = 1  # passthrough {1}
odrv0.axis1.controller.config.pos_gain = 10 * 20  # {20}
odrv0.axis1.controller.config.vel_gain = 0.1667  # {0.1667}
odrv0.axis1.controller.config.vel_integrator_gain = 10 * 0.3333  # {0.3333}
odrv0.axis1.controller.config.vel_limit = 2  # {2}

odrv1.axis1.controller.config.anticogging.pre_calibrated = False  # {False}
odrv1.axis1.controller.config.input_mode = 1  # passthrough {1}
odrv1.axis1.controller.config.pos_gain = 10 * 20  # {20}
odrv1.axis1.controller.config.vel_gain = 0.1667  # {0.1667}
odrv1.axis1.controller.config.vel_integrator_gain = 10 * 0.3333  # {0.3333}
odrv1.axis1.controller.config.vel_limit = 2  # {2}

# Save configurations
odrv0, odrv1 = update_odrives(odrv0, odrv0_ID, odrv1, odrv1_ID, 0)

# Anticog motors
odrv0.axis1.requested_state = 8
odrv0.axis1.controller.start_anticogging_calibration()

odrv1.axis1.requested_state = 8
odrv1.axis1.controller.start_anticogging_calibration()

anticog0 = True
anticog1 = True

i0 = odrv0.axis1.encoder.pos_estimate_counts
i1 = odrv1.axis1.encoder.pos_estimate_counts

t = time.time()

time.sleep(1)

print()

while anticog0 or anticog1:
    if anticog0 and odrv0.axis1.controller.config.anticogging.calib_anticogging:
        com0 = abs(odrv0.axis1.encoder.pos_estimate_counts - i0) / 8192
    elif anticog0:
        odrv0.axis1.requested_state = 1
        anticog0 = False
        com0 = 1

    if anticog1 and odrv1.axis1.controller.config.anticogging.calib_anticogging:
        com1 = abs(odrv1.axis1.encoder.pos_estimate_counts - i1) / 8192
    elif anticog1:
        odrv1.axis1.requested_state = 1
        anticog1 = False
        com1 = 1

    dt = time.time() - t
    print(
        f"\033[AAnticogging belt motors:  Please wait approximatly {(dt / min(com0, com1) - dt) :.0f} seconds ({dt:.0f} seconds elapsed, belt 0 {100 * com0:.0f}% complete, belt 1 {100 * com1:.0f}% complete)     ")

    # Check errors
    check_errors(odrv0, odrv1)

# Write configurations
odrv0.axis1.controller.config.anticogging.pre_calibrated = True  # {False}
odrv0.axis1.controller.config.input_mode = 2  # vel ramp {1}
odrv0.axis1.controller.config.pos_gain = 15  # {20}
odrv0.axis1.controller.config.vel_gain = 0.1667  # {0.1667}
odrv0.axis1.controller.config.vel_integrator_gain = 0.3333  # {0.3333}
odrv0.axis1.controller.config.vel_limit = 114  # {2}

odrv1.axis1.controller.config.anticogging.pre_calibrated = True  # {False}
odrv1.axis1.controller.config.input_mode = 2  # vel ramp {1}
odrv1.axis1.controller.config.pos_gain = 15  # {20}
odrv1.axis1.controller.config.vel_gain = 0.1667  # {0.1667}
odrv1.axis1.controller.config.vel_integrator_gain = 0.3333  # {0.3333}
odrv1.axis1.controller.config.vel_limit = 114  # {2}

# Save configurations
odrv0, odrv1 = update_odrives(odrv0, odrv0_ID, odrv1, odrv1_ID, 0)

return odrv0, odrv1

def main():

os.system('cls')

print("Loading Variable Stiffness Treadmill Autocalibration v002")

odrv0_ID = '316D335C3030'
odrv1_ID = '3359365B3539'

odrv0 = odrive.find_any(serial_number=odrv0_ID)
odrv1 = odrive.find_any(serial_number=odrv1_ID)

odrv0.axis0.requested_state = 1
odrv0.axis1.requested_state = 1

odrv1.axis0.requested_state = 1
odrv1.axis1.requested_state = 1

os.system('cls')

# Clear, erase, or quit
str_in = input(
    "Press ENTER to clear errors, E to erase configurations, or X to quit\n")
os.system('cls')

if str_in in ['x', 'X']:
    sys.exit()
elif str_in in ['e', 'E']:
    odrv0, odrv1 = update_odrives(odrv0, odrv0_ID, odrv1, odrv1_ID, 1)
else:
    odrv0.clear_errors()
    odrv1.clear_errors()

# Autocal VSM motors
str_in = input(
    "Press ENTER to start VSM autocalibration or X to skip\nRemove platform and center carriage prior to calibration\n")
os.system('cls')

if str_in in ['x', 'X']:
    pass
else:
    odrv0, odrv1 = autocal_VSM(odrv0, odrv0_ID, odrv1, odrv1_ID)

# Autocal belt motors
str_in = input(
    "Press ENTER to start belt autocalibration or X to skip\nRemove roller gear prior to calibration\n")
os.system('cls')

if str_in in ['x', 'X']:
    pass
else:
    odrv0, odrv1 = autocal_belt(odrv0, odrv0_ID, odrv1, odrv1_ID)

main()

‘’’

Wow! Thank you for taking the time to provide this. It will better help me understand what I need to know.

Right now I have been testing using OdriveTool, but need to run the two motors from a microcontroller (NXP’s MK20DX256VLH7). That is why I need to pre-configure the starting position.

I’ve got two axis that each have strain gauges to measure forces applied by hand. The idea is pretty simple; the greater the force applied, the further the motor moves. Basically, replacing what a spring would do, but now I can add custom profiles for the spring rates. That’s something that is difficult or impossible to do with mechanical springs.

Running Odrive 3.6 with two D6374 motors and AMT10E2 encoders. First thing I discovered that these motors do not like to be mounted too close to each other! :slight_smile:

Your project sounds interesting!

Any command in the script can be copied and pasted into the odrivetool, but you can ignore all the stuff about errors and waits

If you set the motors to use torque (current) control, you have a constant force spring, and if you use position control you have a linear force spring, no need for an actual force transducer if you are okay with a bit of error. You can multiply the motor current by the motor torque constant to get the motor torque on the shaft

The force sensor is already in the mechanism’s shaft driven by the motors, so I figure I might as well use it.

However, it should be interesting to try what you are suggesting. The Odrive board makes for a good bit of versatility. Impressive work as well as the projects it has spawned.