Actuators

class opensourceleg.actuators.ActpackMode(control_mode: c_int, device: DephyActpack)

Base class for Actpack modes

Parameters:
  • control_mode (c_int) – Control mode

  • device (DephyActpack) – Dephy Actpack

enter() None

Calls the entry callback

exit() None

Calls the exit callback

property has_gains: bool

Whether the mode has gains

Returns:

True if the mode has gains, False otherwise

Return type:

bool

property mode: c_int

Control mode

Returns:

Control mode

Return type:

c_int

transition(to_state: ActpackMode) None

Transition to another mode. Calls the exit callback of the current mode and the entry callback of the new mode.

Parameters:

to_state (ActpackMode) – Mode to transition to

class opensourceleg.actuators.ControlModes(voltage: c_int = c_int(1), current: c_int = c_int(2), position: c_int = c_int(0), impedance: c_int = c_int(3))

Control modes for the Dephy Actpack.

Available modes are Voltage, Current, Position, Impedance.

class opensourceleg.actuators.CurrentMode(device: DephyActpack)
class opensourceleg.actuators.DephyActpack(port: str = '/dev/ttyACM0', baud_rate: int = 230400, frequency: int = 500, logger: ~opensourceleg.logger.Logger = <Logger opensourceleg.logger (DEBUG)>, units: ~opensourceleg.units.UnitsDefinition = {'acceleration': 'rad/s^2', 'current': 'mA', 'damping': 'N/(rad/s)', 'force': 'N', 'gravity': 'm/s^2', 'length': 'm', 'mass': 'kg', 'position': 'rad', 'stiffness': 'N/rad', 'temperature': 'C', 'time': 's', 'torque': 'N-m', 'velocity': 'rad/s', 'voltage': 'mV'}, debug_level: int = 0, dephy_log: bool = False)

Class for the Dephy Actpack

Parameters:

Device (_type_) – _description_

Raises:
  • KeyError – _description_

  • ValueError – _description_

  • KeyError – _description_

Returns:

_description_

Return type:

_type_

set_current(value: float) None

Sets the q axis current

Parameters:

value (float) – The current to set

set_current_gains(kp: int = 40, ki: int = 400, ff: int = 128) None

Sets the current gains

Parameters:
  • kp (int) – The proportional gain

  • ki (int) – The integral gain

  • ff (int) – The feedforward gain

set_impedance_gains(kp: int = 40, ki: int = 400, K: int = 200, B: int = 400, ff: int = 128) None

Sets the impedance gains

Parameters:
  • kp (int) – The proportional gain

  • ki (int) – The integral gain

  • K (int) – The spring constant

  • B (int) – The damping constant

  • ff (int) – The feedforward gain

set_motor_position(position: float) None

Sets the motor position

Parameters:

position (float) – The position to set

set_motor_torque(torque: float) None

Sets the motor torque

Parameters:

torque (float) – The torque to set

set_position_gains(kp: int = 50, ki: int = 0, kd: int = 0) None

Sets the position gains

Parameters:
  • kp (int) – The proportional gain

  • ki (int) – The integral gain

  • kd (int) – The derivative gain

set_voltage(value: float) None

Sets the q axis voltage

Parameters:

value (float) – The voltage to set

class opensourceleg.actuators.ImpedanceMode(device: DephyActpack)
class opensourceleg.actuators.PositionMode(device: DephyActpack)
class opensourceleg.actuators.VoltageMode(device: DephyActpack)

Constants

  • PI float = 3.14159

  • MOTOR_COUNT_PER_REV float = 16384

  • NM_PER_AMP float = 0.1133

  • NM_PER_MILLIAMP float = NM_PER_AMP / 1000

  • RAD_PER_COUNT float = 2 * PI / MOTOR_COUNT_PER_REV

  • RAD_PER_DEG float = PI / 180

  • RAD_PER_SEC_GYROLSB float = PI / 180 / 32.8

  • M_PER_SEC_SQUARED_ACCLSB float = 9.80665 / 8192

  • IMPEDANCE_A float = 0.00028444

  • IMPEDANCE_C float = 0.0007812

  • NM_PER_RAD_TO_K float = RAD_PER_COUNT / IMPEDANCE_C * 1e3 / NM_PER_AMP

  • NM_S_PER_RAD_TO_B float = RAD_PER_DEG / IMPEDANCE_A * 1e3 / NM_PER_AMP

  • MAX_CASE_TEMPERATURE float = 80.0

Control

class opensourceleg.control.Gains(kp: int = 0, ki: int = 0, kd: int = 0, K: int = 0, B: int = 0, ff: int = 0)

Dataclass for controller gains

Parameters:
  • kp (int) – Proportional gain

  • ki (int) – Integral gain

  • kd (int) – Derivative gain

  • K (int) – Stiffness of the impedance controller

  • B (int) – Damping of the impedance controller

  • ff (int) – Feedforward gain

Joints

class opensourceleg.joints.Joint(name: str = 'knee', port: str = '/dev/ttyACM0', baud_rate: int = 230400, frequency: int = 500, gear_ratio: float = 41.4999, has_loadcell: bool = False, logger: ~opensourceleg.logger.Logger = <Logger opensourceleg.logger (DEBUG)>, units: ~opensourceleg.units.UnitsDefinition = {'acceleration': 'rad/s^2', 'current': 'mA', 'damping': 'N/(rad/s)', 'force': 'N', 'gravity': 'm/s^2', 'length': 'm', 'mass': 'kg', 'position': 'rad', 'stiffness': 'N/rad', 'temperature': 'C', 'time': 's', 'torque': 'N-m', 'velocity': 'rad/s', 'voltage': 'mV'}, debug_level: int = 0, dephy_log: bool = False)

Bases: DephyActpack

home(homing_voltage: int = 2000, homing_frequency: int = 100) None

This method homes the joint by moving it to the zero position. The zero position is defined as the position where the joint is fully extended. This method will also make an encoder map if one does not exist.

Parameters:
  • homing_voltage (int) – voltage in mV to use for homing

  • homing_frequency (int) – frequency in Hz to use for homing

make_encoder_map() None

This method makes a lookup table to calculate the position measured by the joint encoder. This is necessary because the magnetic output encoders are nonlinear. By making the map while the joint is unloaded, joint position calculated by motor position * gear ratio should be the same as the true joint position.

Output from this function is a file containing a_i values parameterizing the map

Eqn: position = sum from i=0^5 (a_i*counts^i)

Author: Kevin Best, PhD

U-M Neurobionics Lab Gitub: tkevinbest, https://github.com/tkevinbest

set_joint_impedance(kp: int = 40, ki: int = 400, K: float = 0.08922, B: float = 0.003807, ff: int = 128) None

Set the impedance gains of the joint in real units: Nm/rad and Nm/rad/s.

Conversion:

K_motor = K_joint / (gear_ratio ** 2) B_motor = B_joint / (gear_ratio ** 2)

Parameters:
  • kp (int) – Proportional gain. Defaults to 40.

  • ki (int) – Integral gain. Defaults to 400.

  • K (float) – Spring constant. Defaults to 0.08922 Nm/rad.

  • B (float) – Damping constant. Defaults to 0.0038070 Nm/rad/s.

  • ff (int) – Feedforward gain. Defaults to 128.

set_max_temperature(temperature: float) None

Set the maximum temperature of the motor.

Parameters:

temperature (float) – temperature in degrees Celsius

set_motor_impedance(kp: int = 40, ki: int = 400, K: float = 0.08922, B: float = 0.003807, ff: int = 128) None

Set the impedance gains of the motor in real units: Nm/rad and Nm/rad/s.

Parameters:
  • kp (int) – Proportional gain. Defaults to 40.

  • ki (int) – Integral gain. Defaults to 400.

  • K (float) – Spring constant. Defaults to 0.08922 Nm/rad.

  • B (float) – Damping constant. Defaults to 0.0038070 Nm/rad/s.

  • ff (int) – Feedforward gain. Defaults to 128.

set_output_position(position: float) None

Set the output position of the joint. This is the desired position of the joint, not the motor.

Parameters:

position (float) – position in user-defined units

set_output_torque(torque: float) None

Set the output torque of the joint. This is the torque that is applied to the joint, not the motor.

Parameters:

torque (float) – torque in user-defined units

Loadcell

class opensourceleg.loadcell.StrainAmp(bus, I2C_addr=102)

A class to directly manage the 6ch strain gauge amplifier over I2C. Author: Mitry Anderson

read_compressed_strain()

Used for more recent versions of strain amp firmware

read_uncompressed_strain()

Used for an older version of the strain amp firmware (at least pre-2017)

static strain_data_to_wrench(unpacked_strain, loadcell_matrix, loadcell_zero, exc=5, gain=125)

Converts strain values between 0 and 4095 to a wrench in N and Nm

static unpack_compressed_strain(data)

Used for more recent versions of strainamp firmware

static unpack_uncompressed_strain(data)

Used for an older version of the strain amp firmware (at least pre-2017)

update()

Called to update data of strain amp. Also returns data.

static wrench_to_strain_data(measurement, loadcell_matrix, exc=5, gain=125)

Wrench in N and Nm to the strain values that would give that wrench

Logger

class opensourceleg.logger.Logger(file_path: str = './osl', log_format: str = '[%(asctime)s] %(levelname)s: %(message)s')

Bases: Logger

Logger class is a class that logs attributes from a class to a csv file

__init__(self, class_instance

object, file_path: str, logger: logging.Logger = None) -> None

log(self) None
add_attributes(class_instance: object, attributes_str: list[str]) None

Configures the logger to log the attributes of a class

Parameters:
  • class_instance (object) – Class instance to log the attributes of

  • attributes_str (list[str]) – List of attributes to log

close() None

Closes the csv file

data() None

Logs the attributes of the class instance to the csv file

set_file_level(level: str = 'DEBUG') None

Sets the level of the logger

Parameters:

level (str) – Level of the logger

set_stream_level(level: str = 'INFO') None

Sets the level of the logger

Parameters:

level (str) – Level of the logger

Open-Source Leg

class opensourceleg.osl.OpenSourceLeg(frequency: int = 200, file_name: str = 'osl')

Bases: object

OSL class: This class is the main class for the Open Source Leg project. It contains all the necessary functions to control the leg.

Returns:

none

Return type:

none

add_joint(name: str = 'knee', port: str | None = None, baud_rate: int = 230400, gear_ratio: float = 1.0, has_loadcell: bool = False, debug_level: int = 0, dephy_log: bool = False) None

Add a joint to the OSL object.

Parameters:
  • name (str, optional) – The name of the joint, by default “knee”

  • port (str, optional) – The serial port that the joint is connected to, by default None. If None, the first active port will be used.

  • baud_rate (int, optional) – The baud rate of the serial communication, by default 230400

  • gear_ratio (float, optional) – The gear ratio of the joint, by default 1.0

  • has_loadcell (bool, optional) – Whether the joint has a loadcell, by default False

  • debug_level (int, optional) – The debug level of the joint, by default 0

  • dephy_log (bool, optional) – Whether to log the joint data to the dephy log, by default False

add_loadcell(dephy_mode: bool = False, joint: Joint | None = None, amp_gain: float = 125.0, exc: float = 5.0, loadcell_matrix=array([[-3.872600e+01, -1.817747e+03, 9.849000e+00, 4.337400e+01, -4.454000e+01, 1.824670e+03], [-8.616000e+00, 1.041149e+03, 1.886100e+01, -2.098822e+03, 3.179400e+01, 1.058623e+03], [-1.047168e+03, 8.639000e+00, -1.047282e+03, -2.070000e+01, -1.073088e+03, -8.923000e+00], [2.057600e+01, -4.000000e-02, -2.460000e-01, 5.540000e-01, -2.140800e+01, -4.760000e-01], [-1.213400e+01, -1.108000e+00, 2.436100e+01, 2.300000e-02, -1.214100e+01, 7.920000e-01], [-6.510000e-01, -2.828700e+01, 2.200000e-02, -2.523000e+01, 4.730000e-01, -2.730700e+01]])) None

Add a loadcell to the OSL object.

Parameters:
  • dephy_mode (bool, optional) – Whether the loadcell is in dephy mode ie. connected to the dephy actpack with an FFC cable, by default False

  • joint (Joint, optional) – The joint that the loadcell is attached to, by default None

  • amp_gain (float, optional) – The amplifier gain of the loadcell, by default 125.0

  • exc (float, optional) – The excitation voltage of the loadcell, by default 5.0

  • loadcell_matrix (np.ndarray, optional) – The loadcell calibration matrix, by default None

add_state_machine(spoof: bool = False) None

Add a state machine to the OSL object.

Parameters:

spoof (bool, optional) – If True, the state machine will spoof the state transitions–ie, it will not check the criteria for transitioning but will instead transition after the minimum time spent in state has elapsed. This is useful for testing. Defaults to False.

add_tui(configuration: str = 'state_machine', layout: str = 'vertical') None

Add a Terminal User Interface (TUI) to the OSL object. The TUI is used to visualize the data from the OSL and to send commands to the OSL. Additionally, the TUI also has a timer built-in to govern the frequency of the control loop, which is less accurate than the “osl.clock” (SoftRealTimeLoop) object but is more convenient.

Note

The timer/interface runs in a separate thread, so it does not affect the control loop. This causes the code to not respond to keyboard interrupts (Ctrl+C) when the TUI is running.

Parameters:
  • configuration (str, optional) – The configuration of the TUI, by default “state_machine”

  • layout (str, optional) – The layout of the TUI, by default “vertical”

run(set_state_machine_parameters: bool = False, log_data: bool = False) None

Run the OpenSourceLeg instance: update the joints, loadcell, and state machine. If the instance has a TUI, run the TUI. If the instance has a state machine and if set_state_machine_parameters is True, set the joint impedance gains and equilibrium angles to the current state’s values.

Parameters:

set_state_machine_parameters (bool, optional) – Whether to set the joint impedance gains and equilibrium angles to the current state’s values, by default False

State Machine

class opensourceleg.state_machine.Event(name)

Event class

class opensourceleg.state_machine.FromToTransition(event: Event, source: State, destination: State, callback: Callable[[Any], bool] | None = None)
class opensourceleg.state_machine.Idle
class opensourceleg.state_machine.State(name: str = 'state', is_knee_active: bool = False, knee_stiffness: float = 0.0, knee_damping: float = 0.0, knee_equilibrium_angle: float = 0.0, is_ankle_active: bool = False, ankle_stiffness: float = 0.0, ankle_damping: float = 0.0, ankle_equilibrium_angle: float = 0.0, minimum_time_in_state: float = 2.0)

A class to represent a state in a finite state machine.

Parameters:
  • name (str) – Name of the state

  • is_knee_active (bool) – Whether the knee is active. Default: False

  • knee_stiffness (float) – Knee stiffness in Nm/rad

  • knee_damping (float) – Knee damping in Nm/rad/sec

  • knee_equilibrium_angle (float) – Knee equilibrium angle

  • is_ankle_active (bool) – Whether the ankle is active. Default: False

  • ankle_stiffness (float) – Ankle stiffness in Nm/rad

  • ankle_damping (float) – Ankle damping in Nm/rad/sec

  • ankle_equilibrium_angle (float) – Ankle equilibrium angle

  • minimum_time_in_state (float) – Minimum time spent in the state in seconds. Default: 2.0

Note

The knee and ankle impedance parameters are only used if the corresponding joint is active. You can also set custom data using the set_custom_data method.

get_custom_data(key: str) Any

Get custom data for the state. The custom data is a dictionary that can be used to store any data you want to associate with the state.

Parameters:

key (str) – Key of the data

Returns:

Value of the data

Return type:

Any

make_ankle_active()

Make the ankle active

Note

The ankle impedance parameters are only used if the ankle is active.

make_knee_active()

Make the knee active

Note

The knee impedance parameters are only used if the knee is active.

set_ankle_impedance_paramters(theta, k, b) None

Set the ankle impedance parameters

Parameters:
  • theta (float) – Equilibrium angle of the ankle joint

  • k (float) – Stiffness of the ankle joint

  • b (float) – Damping of the ankle joint

Note

The ankle impedance parameters are only used if the ankle is active. You can make the ankle active by calling the make_ankle_active method.

set_custom_data(key: str, value: Any) None

Set custom data for the state. The custom data is a dictionary that can be used to store any data you want to associate with the state.

Parameters:
  • key (str) – Key of the data

  • value (Any) – Value of the data

set_knee_impedance_paramters(theta, k, b) None

Set the knee impedance parameters

Parameters:
  • theta (float) – Equilibrium angle of the knee joint

  • k (float) – Stiffness of the knee joint

  • b (float) – Damping of the knee joint

Note

The knee impedance parameters are only used if the knee is active. You can make the knee active by calling the make_knee_active method.

set_minimum_time_spent_in_state(time: float) None

Set the minimum time spent in the state

Parameters:

time (float) – Minimum time spent in the state in seconds

class opensourceleg.state_machine.StateMachine(osl=None, spoof: bool = False)

State Machine class

Parameters:
  • osl (Any) – The OpenSourceLeg object.

  • spoof (bool) – If True, the state machine will spoof the state transitions–ie, it will not check the criteria for transitioning but will instead transition after the minimum time spent in state has elapsed. This is useful for testing. Defaults to False.

current_state

The current state of the state machine.

Type:

State

current_state_name

The name of the current state of the state machine.

Type:

str

states

The list of states in the state machine.

Type:

list[State]

is_spoofing

Whether or not the state machine is spoofing the state transitions.

Type:

bool

add_state(state: State, initial_state: bool = False) None

Add a state to the state machine.

Parameters:
  • state (State) – The state to be added.

  • initial_state (bool, optional) – Whether the state is the initial state, by default False

add_transition(source: State, destination: State, event: Event, callback: Callable[[Any], bool] | None = None) Transition | None

Add a transition to the state machine.

Parameters:
  • source (State) – The source state.

  • destination (State) – The destination state.

  • event (Event) – The event that triggers the transition.

  • callback (Callable[[Any], bool], optional) – A callback function that returns a boolean value, which determines whether the transition is valid, by default None

class opensourceleg.state_machine.Transition(event: Event, source: State, destination: State, callback: Callable[[Any], bool] | None = None)

Transition class

Thermal

class opensourceleg.thermal.ThermalModel(ambient: float = 21, params: dict = {}, temp_limit_windings: float = 115, soft_border_C_windings: float = 15, temp_limit_case: float = 80, soft_border_C_case: float = 5)

Thermal model of a motor developed by Jianping Lin and Gray C. Thomas @U-M Locomotion Lab, directed by Dr. Robert Gregg

Assumptions:

1: The motor is a lumped system with two thermal nodes: the winding and the case. 2: The winding and the case are assumed to be in thermal equilibrium with the ambient. 3: The winding and the case are assumed to be in thermal equilibrium with each other.

Equations:

1: C_w * dT_w/dt = (I^2)R + (T_c-T_w)/R_WC 2: C_c * dT_c/dt = (T_w-T_c)/R_WC + (T_w-T_a)/R_CA

where:

C_w: Thermal capacitance of the winding C_c: Thermal capacitance of the case R_WC: Thermal resistance between the winding and the case R_CA: Thermal resistance between the case and the ambient T_w: Temperature of the winding T_c: Temperature of the case T_a: Temperature of the ambient I: Current R: Resistance

Implementation:

1: The model is updated at every time step with the current and the ambient temperature. 2: The model can be used to predict the temperature of the winding and the case at any time step. 3: The model can also be used to scale the torque based on the temperature of the winding and the case.

Parameters:
  • ambient (float) – Ambient temperature in Celsius. Defaults to 21.

  • params (dict) – Dictionary of parameters. Defaults to dict().

  • temp_limit_windings (float) – Maximum temperature of the windings in Celsius. Defaults to 115.

  • soft_border_C_windings (float) – Soft border of the windings in Celsius. Defaults to 15.

  • temp_limit_case (float) – Maximum temperature of the case in Celsius. Defaults to 80.

  • soft_border_C_case (float) – Soft border of the case in Celsius. Defaults to 5.

update(dt: float = 0.005, motor_current: float = 0) None

Updates the temperature of the winding and the case based on the current and the ambient temperature.

Parameters:
  • dt (float) – Time step in seconds. Defaults to 1/200.

  • motor_current (float) – Current in mA. Defaults to 0.

Dynamics:

1: self.C_w * d self.T_w /dt = (I^2)R + (self.T_c-self.T_w)/self.R_WC 2: self.C_c * d self.T_c /dt = (self.T_w-self.T_c)/self.R_WC + (self.T_w-self.T_a)/self.R_CA

update_and_get_scale(dt, motor_current: float = 0, FOS=3.0)

Updates the temperature of the winding and the case based on the current and the ambient temperature and returns the scale factor for the torque.

Parameters:
  • dt (float) – Time step in seconds.

  • motor_current (float) – Current in mA. Defaults to 0.

  • FOS (float) – Factor of safety. Defaults to 3.0.

Returns:

Scale factor for the torque.

Return type:

float

Dynamics:

1: self.C_w * d self.T_w /dt = (I^2)R + (self.T_c-self.T_w)/self.R_WC 2: self.C_c * d self.T_c /dt = (self.T_w-self.T_c)/self.R_WC + (self.T_w-self.T_a)/self.R_CA

TUI

Units

class opensourceleg.units.UnitsDefinition

UnitsDefinition class is a dictionary with set and get methods that checks if the keys are valid

__setitem__(key

str, value: dict) -> None

__getitem__(key

str) -> dict

convert(value

float, attribute: str) -> None

convert_from_default_units(value: float, attribute: str) float

convert a value from the default unit to another unit

Parameters:
  • value (float) – Value to be converted

  • attribute (str) – Attribute to be converted

Returns:

Converted value in the default unit

Return type:

float

convert_to_default_units(value: float, attribute: str) float

convert a value from one unit to the default unit

Parameters:
  • value (float) – Value to be converted

  • attribute (str) – Attribute to be converted

Returns:

Converted value in the default unit

Return type:

float

Utilities

class opensourceleg.utilities.CSVLog(file_name, variable_name, container_names)

Logging class to make writing to a CSV file easier. See if __name__ == “__main__” for an example. At instantiation, pass a list of lists corresponding to the variable names you wish to log, as well as the name of their containers. The container name is prepended in the log so you know which object the variable came from. These variables should live as attributes within some object accessible to the main loop. To update the log, simply call log.update((obj1, obj2, …)).

Author: Kevin Best https://github.com/tkevinbest

class opensourceleg.utilities.EdgeDetector(bool_in)

Used to calculate rising and falling edges of a digital signal in real time. Call edgeDetector.update(digitalSignal) to update the detector. Then read edgeDetector.rising_edge or falling edge to know if the event occurred.

Author: Kevin Best https://github.com/tkevinbest

class opensourceleg.utilities.LoopKiller(fade_time=0.0)

Soft Realtime Loop—a class designed to allow clean exits from infinite loops with the potential for post-loop cleanup operations executing.

The Loop Killer object watches for the key shutdown signals on the UNIX operating system (which runs on the PI) when it detects a shutdown signal, it sets a flag, which is used by the Soft Realtime Loop to stop iterating. Typically, it detects the CTRL-C from your keyboard, which sends a SIGTERM signal.

the function_in_loop argument to the Soft Realtime Loop’s blocking_loop method is the function to be run every loop. A typical usage would set function_in_loop to be a method of an object, so that the object could store program state. See the ‘ifmain’ for two examples.

# This library will soon be hosted as a PIP module and added as a python dependency. # https://github.com/UM-LoCoLab/NeuroLocoMiddleware/blob/main/SoftRealtimeLoop.py

Author: Gray C. Thomas, Ph.D https://github.com/GrayThomas, https://graythomas.github.io

class opensourceleg.utilities.SaturatingRamp(loop_frequency=100, ramp_time=1.0)

Creates a signal that ramps between 0 and 1 at the specified rate. Looks like a trapezoid in the time domain Used to slowly enable joint torque for smooth switching at startup. Call saturatingRamp.update() to update the value of the ramp and return the value. Can also access saturatingRamp.value without updating.

Example usage:

ramp = saturatingRamp(100, 1.0)

# In loop

torque = torque * ramp.update(enable_ramp)

Author: Kevin Best https://github.com/tkevinbest

update(enable_ramp=False)

Updates the ramp value and returns it as a float. If enable_ramp is true, ramp value increases Otherwise decreases.

Example usage:

torque = torque * ramp.update(enable_ramp)

Parameters:

enable_ramp (bool, optional) – If enable_ramp is true, ramp value increases. Defaults to False.

Returns:

Scalar between 0 and 1.

Return type:

value (float)

class opensourceleg.utilities.SoftRealtimeLoop(dt=0.001, report=False, fade=0.0)

Soft Realtime Loop—a class designed to allow clean exits from infinite loops with the potential for post-loop cleanup operations executing.

The Loop Killer object watches for the key shutdown signals on the UNIX operating system (which runs on the PI) when it detects a shutdown signal, it sets a flag, which is used by the Soft Realtime Loop to stop iterating. Typically, it detects the CTRL-C from your keyboard, which sends a SIGTERM signal.

the function_in_loop argument to the Soft Realtime Loop’s blocking_loop method is the function to be run every loop. A typical usage would set function_in_loop to be a method of an object, so that the object could store program state. See the ‘ifmain’ for two examples.

This library will soon be hosted as a PIP module and added as a python dependency. https://github.com/UM-LoCoLab/NeuroLocoMiddleware/blob/main/SoftRealtimeLoop.py

# Author: Gray C. Thomas, Ph.D # https://github.com/GrayThomas, https://graythomas.github.io

opensourceleg.utilities.get_active_ports()

Lists active serial ports.