Hardware#

Actuators#

  • 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

class opensourceleg.hardware.actuators.ActpackControlModes(device: opensourceleg.hardware.actuators.DephyActpack)#

Actpack modes

Parameters
class opensourceleg.hardware.actuators.ActpackMode(control_mode: ctypes.c_int, device: opensourceleg.hardware.actuators.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: ctypes.c_int#

Control mode

Returns

Control mode

Return type

c_int

transition(to_state: opensourceleg.hardware.actuators.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.hardware.actuators.ControlModes(voltage: ctypes.c_int = c_int(1), current: ctypes.c_int = c_int(2), position: ctypes.c_int = c_int(0), impedance: ctypes.c_int = c_int(3))#

Control modes for the Dephy Actpack.

Available modes are Voltage, Current, Position, Impedance.

class opensourceleg.hardware.actuators.CurrentMode(device: opensourceleg.hardware.actuators.DephyActpack)#
class opensourceleg.hardware.actuators.DephyActpack(name: str = 'DephyActpack', port: str = '/dev/ttyACM0', baud_rate: int = 230400, frequency: int = 500, logger: opensourceleg.tools.logger.Logger = Logger, 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_

property accelx: float#

Acceleration in x direction in m/s^2. Measured using actpack’s onboard IMU.

property accely: float#

Acceleration in y direction in m/s^2. Measured using actpack’s onboard IMU.

property accelz: float#

Acceleration in z direction in m/s^2. Measured using actpack’s onboard IMU.

property battery_current: float#

Battery current in mA.

property battery_voltage: float#

Battery voltage in mV.

property case_temperature: float#

Case temperature in celsius.

property genvars#

Dephy’s ‘genvars’ object.

property gyrox: float#

Angular velocity in x direction in rad/s. Measured using actpack’s onboard IMU.

property gyroy: float#

Angular velocity in y direction in rad/s. Measured using actpack’s onboard IMU.

property gyroz: float#

Angular velocity in z direction in rad/s. Measured using actpack’s onboard IMU.

property joint_encoder_counts: int#

Raw reading from joint encoder in counts.

property joint_position: float#

Measured angle from the joint encoder in radians.

property joint_velocity: float#

Measured velocity from the joint encoder in rad/s.

property joint_zero_position: float#

Joint encoder offset in radians.

property motor_acceleration: float#

Motor acceleration in rad/s^2.

property motor_current: float#

Q-axis motor current in mA.

property motor_encoder_counts: int#

Raw reading from motor encoder in counts.

property motor_position: float#

Angle of the motor in radians.

property motor_torque: float#

Torque at motor output in Nm. This is calculated using the motor current and torque constant.

property motor_velocity: float#

Motor velocity in rad/s.

property motor_voltage: float#

Q-axis motor voltage in mV.

property motor_zero_position: float#

Motor encoder offset in radians.

set_current(value: float) None#

Sets the q axis current in mA

Parameters

value (float) – The current to set in mA

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

Sets the current gains in arbitrary Dephy units.

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 in arbitrary actpack units. See Dephy’s webpage for conversions or use other library methods that handle conversion for you.

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_joint_zero_position(position: float) None#

Sets joint zero position in counts

set_motor_position(position: float) None#

Sets the motor position in radians. If in impedance mode, this sets the equilibrium angle in radians.

Parameters

position (float) – The position to set

set_motor_torque(torque: float) None#

Sets the motor torque in Nm.

Parameters

torque (float) – The torque to set in Nm.

set_motor_zero_position(position: float) None#

Sets motor zero position in counts

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

Sets the position gains in arbitrary Dephy units.

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 in mV

Parameters

value (float) – The voltage to set in mv

property thermal_scaling_factor: float#

Scale factor to use in torque control, in [0,1]. If you scale the torque command by this factor, the motor temperature will never exceed max allowable temperature. For a proof, see paper referenced in thermal model.

update() None#

Queries the latest values from the actpack. Also updates thermal model.

property winding_temperature: float#

ESTIMATED temperature of the windings in celsius. This is calculated based on the thermal model using motor current.

class opensourceleg.hardware.actuators.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

class opensourceleg.hardware.actuators.ImpedanceMode(device: opensourceleg.hardware.actuators.DephyActpack)#
class opensourceleg.hardware.actuators.MockDephyActpack(name: str = 'MockDephyActpack', port: str = '/dev/ttyACM0', baud_rate: int = 230400, frequency: int = 500, logger: opensourceleg.tools.logger.Logger = Logger, debug_level: int = 0, dephy_log: bool = False)#

MockDephyActpack class definition for testing.

This class inherits everything from the DephyActpack class but deletes the super().__init__() call in the constructor so the constructor does not try to connect to a device. It also overrides some of the methods to allow for testing without a device, and adds attributes used to determine if the methods were called properly.

close()#

Disconnect from a FlexSEA device.

Raises

ValueError: – If the device ID is invalid.

open(freq, log_level, log_enabled)#

Establish a connection with a FlexSEA device.

Parameters
  • freq (int) – The desired frequency of communication.

  • log_level (int) – The logging level for this device. 0 is most verbose and 6 is the least verbose. Values greater than 6 are floored to 6.

  • log_enabled (bool) – If True, all received data is logged to a file.

Raises
  • IOError: – If we fail to open the device.

  • RuntimeError: – If the stream failed.

read()#

Read the most recent data from a streaming FlexSEA device stream.

Raises
  • ValueError: – If invalid device ID.

  • RuntimeError: – If no read data.

  • IOError: – Command failed.

Returns

deviceState – Contains the most recent data from the device.

Return type

List

send_motor_command(ctrl_mode, value)#

Send a command to the device.

Parameters
  • ctrl_mode (c_int) – The control mode we will use to send this command. Possible values are: FxPosition, FxCurrent, FxVoltage, FxImpedence

  • value (int) – The value to use for the ctrl_mode. FxPosition - encoder value FxCurrent - current in mA FxVoltage - voltage in mV FxImpedence - current in mA

Raises
  • ValueError: – If invalid device ID or invalid control type.

  • IOError: – Command failed.

set_gains(kp, ki, kd, k, b, ff)#

Sets the gains used by PID controllers on the FlexSEA device.

Parameters
  • kp (int) – Proportional gain.

  • ki (int) – Integral gain.

  • kd (int) – Differential gain.

  • k (int) – Stiffness (used in impedence control only).

  • b (int) – Damping (used in impedance control only).

  • ff (int) – Feed forward gain.

Raises
  • ValueError: – If the device ID is invalid.

  • IOError: – Command failed.

class opensourceleg.hardware.actuators.PositionMode(device: opensourceleg.hardware.actuators.DephyActpack)#
class opensourceleg.hardware.actuators.VoltageMode(device: opensourceleg.hardware.actuators.DephyActpack)#

Joints#

class opensourceleg.hardware.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.tools.logger.Logger = Logger, debug_level: int = 0, dephy_log: bool = False)#

Bases: opensourceleg.hardware.actuators.DephyActpack

property encoder_map#

Polynomial coefficients defining the joint encoder map from counts to radians.

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

property is_homed: bool#

Indicates if the homing routine has been called yet.

property joint_torque: float#

Torque at the joint output in Nm. This is calculated using motor current, k_t, and the gear ratio.

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

U-M Locolab | Neurobionics Lab Gitub: tkevinbest, tkevinbest

property max_temperature: float#

Max allowed temperature of the actuator case in celsius.

property output_position: float#

Position of the output in radians. This is calculated by scaling the motor angle with the gear ratio. Note that this method does not consider compliance from an SEA.

property output_velocity: float#

Velocity of the output in radians. This is calculated by scaling the motor angle with the gear ratio. Note that this method does not consider compliance from an SEA.

set_joint_impedance(kp: int = 40, ki: int = 400, K: float = 100.0, B: float = 3.0, ff: int = 128) None#

Set the impedance gains of the joint in real units: Nm/rad and Nm/rad/s. This sets the impedance at the output and automatically scales based on gear raitos.

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 100 Nm/rad.

  • B (float) – Damping constant. Defaults to 3.0 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. This method automatically handles scaling by the gear raito.

Parameters

position (float) – position in radians

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 N_m

class opensourceleg.hardware.joints.MockJoint(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.tools.logger.Logger = Logger, debug_level: int = 0, dephy_log: bool = False)#

Bases: opensourceleg.hardware.joints.Joint, opensourceleg.hardware.actuators.MockDephyActpack

Mock Joint class for testing the Joint class

Inherits everything from the Joint class and the MockDephyActpack class except for the Joint constructor.

Sensors#

class opensourceleg.hardware.sensors.IMUDataClass(angle_x: float = 0, angle_y: float = 0, angle_z: float = 0, velocity_x: float = 0, velocity_y: float = 0, velocity_z: float = 0, accel_x: float = 0, accel_y: float = 0, accel_z: float = 0, imu_time_sta: float = 0, imu_filter_gps_time_week_num: float = 0)#

Dataclass for IMU data. Data is returned in the IMU frame. Angles are in rad. Velocities are in rad/s. Acceleration is in g.

Author: Kevin Best tkevinbest

accel_x: float = 0#

x direction acceleration in g

accel_y: float = 0#

y direction acceleration in g

accel_z: float = 0#

z direction acceleration in g

angle_x: float = 0#

x direction Euler angle in rad

angle_y: float = 0#

y direction Euler angle in rad

angle_z: float = 0#

z direction Euler angle in rad

velocity_x: float = 0#

x direction rotational velocity in rad/s

velocity_y: float = 0#

y direction rotational velocity in rad/s

velocity_z: float = 0#

z direction rotational velocity in rad/s

class opensourceleg.hardware.sensors.IMULordMicrostrain(port='/dev/ttyUSB0', baud_rate=921600, timeout=500, sample_rate=100)#

Sensor class for the Lord Microstrain IMU. Requires the MSCL library from Lord Microstrain (see below for install instructions).

As configured, this class returns euler angles (rad), angular rates (rad/s), and accelerations (g).

Example

imu = IMULordMicrostrain() imu.start_streaming() while in loop:

imu.get_data()

imu.stop_streaming()

Resources:
get_data()#

Get IMU data from the Lord Microstrain IMU

class opensourceleg.hardware.sensors.MockLoadcell(dephy_mode: bool = False, joint: Optional[opensourceleg.hardware.joints.Joint] = None, amp_gain: float = 125.0, exc: float = 5.0, loadcell_matrix: Optional[numpy.ndarray[Any, numpy.dtype[numpy.float64]]] = None, logger: Optional[opensourceleg.tools.logger.Logger] = None)#

Create a mock Loadcell class to test the StrainAmp and Loadcell classes

This class inherits from the Loadcell class but overrides the _lc atttribute with a MockStrainAmp object.

class opensourceleg.hardware.sensors.MockSMBus(bus: int = 1)#

Mocked SMBus class to test the StrainAmp class

This class has attributes and methods that mimic the SMBus class but are implemented in a way to allow for testing.

class opensourceleg.hardware.sensors.MockStrainAmp(bus: int = 1, I2C_addr=102)#

Create a mock StrainAmp class to test the StrainAmp and Loadcell classes

This class inherits from the StrainAmp class but overrides the _SMBus atttribute with a MockSMBus object.

class opensourceleg.hardware.sensors.StrainAmp(bus, I2C_addr=102)#

A class to directly manage the 6ch strain gauge amplifier over I2C. An instance of this class is created by the loadcell class. Author: Mitry Anderson

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

update()#

Called to update data of strain amp. Also returns data. Data is median filtered (max one sample delay) to avoid i2c issues.

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

Thermal#

class opensourceleg.hardware.thermal.ThermalModel(ambient: float = 21, params: dict[Any, Any] = {}, 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) – Motor 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: float = 1.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) – Motor 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