ActuatorConfig¶
- class AxisPosition¶
Axis position
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.AxisPosition
- Parameters
position (float) – Axis position (degrees)
- class AxisOffsets¶
Axis offsets
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.AxisOffsets
- Parameters
absolute_offset (float) – Absolute offset value (degrees)
relative_offset (float) – Relative offset value (degrees)
- class TorqueCalibration¶
Torque calibration settings
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.TorqueCalibration
- Parameters
global_gain (float) – Global gain value
global_offset (float) – Global offset value
gain (float [ ]) – Gain (index 0 to 3)
offset (float [ ]) – Offset (index 0 to 3)
- class TorqueOffset¶
Defines torque offset
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.TorqueOffset
- Parameters
torque_offset (float) – Torque offset value
- class ControlModeInformation¶
Control mode information
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.ControlModeInformation
- Parameters
control_mode (ControlMode) – Control mode
- class ControlLoop¶
Control loop
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.ControlLoop
- Parameters
control_loop (int) – Use ControlLoopSelection enum values to form bitmask
- class LoopSelection¶
Defines the loop selection
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.LoopSelection
- Parameters
loop_selection (ControlLoopSelection) – ControlLoopSelection enum
- class VectorDriveParameters¶
Field-oriented control PI controller gain values
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.VectorDriveParameters
- Parameters
kpq (float) – Quadrature axis current proportional gain
kiq (float) – Quadrature axis current integral gain
kpd (float) – Direct axis current proportional gain
kid (float) – Direct axis current integral gain
- class EncoderDerivativeParameters¶
Variable window derivative parameters
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.EncoderDerivativeParameters
- Parameters
max_window_width (int) – Maximum window width
min_angle (float) – Minimum angle for derivative (degrees)
- class ControlLoopParameters¶
Control loop parameters (discrete transfer function)
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.ControlLoopParameters
- Parameters
loop_selection (ControlLoopSelection) – ControlLoopSelection enum
error_saturation (float) – Error saturation value
output_saturation (float) – Output saturation value
kAz (float [ ]) – KAz (index 0 to 4): denominator gains A1 to A5
kBz (float [ ]) – KBz (index 0 to 5): numerator gains B0 to B5
error_dead_band (float) – Error dead band value
k_p (float) – Proportional gain
k_i (float) – Integral gain
k_d (float) – Derivative gain
- class FrequencyResponse¶
Frequency response
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.FrequencyResponse
- Parameters
loop_selection (ControlLoopSelection) – ControlLoopSelection enum
min_frequency (float) – Minimum frequency value
max_frequency (float) – Maximum frequency value
amplitude (float) – Amplitude value
duration (float) – Duration (in seconds)
- class StepResponse¶
Step response
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.StepResponse
- Parameters
loop_selection (ControlLoopSelection) – ControlLoopSelection enum
amplitude (float) – Amplitude value
step_delay (float) – Step delay value
duration (float) – Duration (in seconds)
- class RampResponse¶
Ramp response
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.RampResponse
- Parameters
loop_selection (ControlLoopSelection) – ControlLoopSelection enum
slope (float) – Slope value
ramp_delay (float) – Ramp delay value
duration (float) – Duration (in seconds)
- class CustomDataSelection¶
Selected custom data channels content
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.CustomDataSelection
- Parameters
channel (CustomDataIndex [ ]) – 16 channels maximum
- class CommandModeInformation¶
Command mode
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.CommandModeInformation
- Parameters
command_mode (CommandMode) – Command mode
- class Servoing¶
Enables/disables servoing
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.Servoing
- Parameters
enabled (bool) – Servoing enabled
- class PositionCommand¶
Angular position command for an actuator
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.PositionCommand
- Parameters
position (float) – Position value (degrees)
velocity (float) – Velocity value (degrees per second)
acceleration (float) – Acceleration value (degrees per second^2)
- class CoggingFeedforwardModeInformation¶
Cogging feedforward mode
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.CoggingFeedforwardModeInformation
- Parameters
cogging_feedforward_mode (CoggingFeedforwardMode) – Cogging feedforward mode
- class LookupTableReadData¶
Lookup table parameters to read with
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.LookupTableReadData
- Parameters
table_selection (LookupTableSelection) – Lookup table selection
table_offset (int) – Offset of data in table
table_length (int) – Length of calibration data
data_selection (LookupTableDataSelection) – Lookup table data selection
- class LookupTableWriteData¶
Lookup table data to write and parameters
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.LookupTableWriteData
- Parameters
table_selection (LookupTableSelection) – Lookup table selection
table_offset (int) – Offset of data in table
table_length (int) – Length of calibration data
data (LookupTableData) – Lookup table data
data_selection (LookupTableDataSelection) – Lookup table data selection
- class LookupTableData¶
Lookup table data
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.LookupTableData
- Parameters
data (bytes) – Lookup data array (max 128)
size (int) – Lookup data array size
- class LookupTableSelectionForNVM¶
Lookup table selection to access NVM
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.LookupTableSelectionForNVM
- Parameters
table_selection (LookupTableSelection) – Lookup table selection
- class FourierModelData¶
Fourier model data
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.FourierModelData
- Parameters
frequencies (float [ ]) – Frequencies
offsets (float [ ]) – Offsets
amplitudes (float [ ]) – Amplitudes
- class FourierModelReadSelection¶
Fourier model parameters to read with
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.FourierModelReadSelection
- Parameters
model_selection (FourierModelSelection) – Fourier model selection
- class FourierModelWriteData¶
Fourier model to write
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.FourierModelWriteData
- Parameters
model_selection (FourierModelSelection) – Fourier model selection
model_data (FourierModelData) – Fourier model data
- class GearboxHysteresisCalibrationData¶
Gearbox hysteresis calibration data
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.GearboxHysteresisCalibrationData
- Parameters
friction_coulomb (float) – Friction
spring_ratio (float) – Spring ratio
- class JointPositionSensorOffset¶
Joint position sensor offset
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.JointPositionSensorOffset
- Parameters
offset (float) – Sensor offset
- class MotorPositionToJointPositionSensorOffset¶
Offset between motor and joint position sensors
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.MotorPositionToJointPositionSensorOffset
- Parameters
offset (float) – Sensor to sensor offset
- class MotorPowerFilterPeriod¶
Motor power measurement filter period
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.MotorPowerFilterPeriod
- Parameters
period (int) – Filter period (milliseconds)
- class CurrentOffset¶
Current offset of a current sensor
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.CurrentOffset
- Parameters
phase (int) – Phase of the current sensor to set offset for (index 0 to 2)
offset (float) – Current sensor offset (Amps)
- class JointEncoderFaults¶
Joint encoder faults
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.JointEncoderFaults
- Parameters
warnings (int) – Warnings (bitmask)
errors (int) – Errors (bitmask)
- class MotorParameters¶
Motor parameters
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.MotorParameters
- Parameters
rotor_inertia (float) – Rotor inertia (kilograms meters^squared)
- class GearboxParameters¶
Gearbox parameters
- Canonical
kortex_api.autogen.messages.ActuatorConfig_pb2.GearboxParameters
- Parameters
gear_ratio (float) – Gear ratio