Skip to main content

API Reference

Firmware Version:

C/C++ API Reference

Actuator.Actuator()

Actuator::Actuator(uint32_t node_id, Interface *interface)
Description

Construct a new Actuator object.

Parameters
DatatypeVariableDescription
uint32_tnode_idCAN Node ID of the Actuator
Interface *interfaceInitialised CAN Interface object for the interface to which the Actuator is connected

Actuator.clearActuatorErrors()

ret_status_t Actuator::clearActuatorErrors()
Description

Clear actuator errors.

Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.disableMotorThermalLimit()

ret_status_t Actuator::disableMotorThermalLimit()
Description

Disable Motor based Thermal limit.

Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.emergencyStop()

ret_status_t Actuator::emergencyStop()
Description

Function to issue an emergency stop to the device which stops the actuator and sets the error flag; Since the error flag is set the actuator doesn't respond to any other commands, until the actuator is rebooted.

Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.enableMotorThermalLimit()

ret_status_t Actuator::enableMotorThermalLimit(uint16_t upper_limit)
Description

Enable Motor based Thermal limit. A thermistor is used to measure motor temperature and start limiting the motor current once the temperature starts to approach the upper limit. The current limiting starts when the difference between the current temperature & the upper limit reaches 20 degrees celsius. The acutators will shut themselves off in case the temperature reaches the upper limit.

Parameters
DatatypeVariableDescription
uint16_tupper_limitShutdown temperature at which the actuator will stop.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.eraseConfigurations()

ret_status_t Actuator::eraseConfigurations()
Description

Erase Configuration of the actuator.

Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.flash()

ret_status_t Actuator::flash(std::string firmware_path)
Description

Flash a firmware onto the device.

Parameters
DatatypeVariableDescription
std::stringfirmware_pathpath to firmware file
Returns
DatatypeDescription
ret_status_tret_status_t

Actuator.getBusCurrent()

ret_status_t Actuator::getBusCurrent(float *ibus)
Description

Get the Bus Current of the actuator.

Parameters
DatatypeVariableDescription
float *ibusPointer to the variable to which the bus current value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getBusVoltage()

ret_status_t Actuator::getBusVoltage(float *vbus_voltage)
Description

Get the Bus Voltage of the actuator.

Parameters
DatatypeVariableDescription
float *vbus_voltagePointer to the variable to which the current bus voltage value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getCANCommunicationStatus()

ret_status_t Actuator::getCANCommunicationStatus(bool *is_connected_to_master, bool *is_receiving_heartbeat)
Description

Get CAN communication status.

Parameters
DatatypeVariableDescription
bool *is_connected_to_masterPointer to the variable to which the status of connection to master node is to be saved.
bool *is_receiving_heartbeatPointer to the variable to which the heartbeat receive status is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getControllerMode()

ret_status_t Actuator::getControllerMode(uint16_t *control_mode)
Description

Get controller mode.

control_mode valueDescription
1Torque Control
2Velocity Control or Ramped Velocity Control
3Position Control or Trapezoidal Trajectory Control
Parameters
DatatypeVariableDescription
uint16_t *control_modePointer to the variable to which the value of control mode is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getControllerState()

ret_status_t Actuator::getControllerState(uint8_t *controller_state)
Description

Get the controller state of the driver.

controller_state valueDescription
0STATE_UNDEFINED
1STATE_IDLE
6STATE_INDEX_SEARCH
8STATE_CLOSED_LOOP_CONTROL
Parameters
DatatypeVariableDescription
uint8_t *controller_statePointer to the variable to which the controller state value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getCurrentControllerBandwidth()

ret_status_t Actuator::getCurrentControllerBandwidth(float *bandwidth)
Description

Get current bandwidth of the controller.

Parameters
DatatypeVariableDescription
float *bandwidthPointer to the variable to which the current controller bandwidth is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getCurrentControllerGains()

ret_status_t Actuator::getCurrentControllerGains(float *p_gain, float *i_gain)
Description

Get current controller gains.

Parameters
DatatypeVariableDescription
float *p_gainPointer to the variable to which the current controller gain value of the controller is to be saved.
float *i_gainPointer to the variable to which the current controller integrator gain value of the controller is to be saved. controller
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getCurrentFilter()

ret_status_t Actuator::getCurrentFilter(float *current_filter)
Description

Set the current data filter value in the controller.

Parameters
DatatypeVariableDescription
float *current_filterValue of current filter.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getDCBusTripLevels()

ret_status_t Actuator::getDCBusTripLevels(float *undervoltage_level, float *overvoltage_level)
Description

Get the actuator's current under-voltage and over-voltage levels.

Parameters
DatatypeVariableDescription
float *undervoltage_levelPointer to the variable where the under-voltage trip level is to be saved.
float *overvoltage_levelPointer to the variable where the over-voltage trip level is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getDriverFault()

ret_status_t Actuator::getDriverFault(uint32_t *driver_error)
Description

Get the Driver error status from the actuator.

Parameters
DatatypeVariableDescription
uint32_t *driver_errorPointer to the variable to which the value of driver error is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getDriverTemperature()

ret_status_t Actuator::getDriverTemperature(float *driver_temperature)
Description

Get driver temperature in degree Celsius. It uses a thermistor near the FETs to measure the temperature.

Parameters
DatatypeVariableDescription
float *driver_temperaturePointer to the variable to which the current driver temperature value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getEncoderDataFilter()

ret_status_t Actuator::getEncoderDataFilter(float *encoder_data_filter)
Description

Get the current value of encoder data filter in the controller.

Parameters
DatatypeVariableDescription
float *encoder_data_filterPointer to the variable to which the current encoder data filter value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getErrorCode()

ret_status_t Actuator::getErrorCode(uint32_t *error_code)
Description

Get the error code from the actuator.

Parameters
DatatypeVariableDescription
uint32_t *error_codePointer to the variable to which the value of error code is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getFirmwareVersion()

ret_status_t Actuator::getFirmwareVersion(uint8_t *major, uint8_t *minor, uint16_t *revision)
Description

Get Driver's Firmware version.

Parameters
DatatypeVariableDescription
uint8_t *majorPointer to the variable where the major version value is to be saved.
uint8_t *minorPointer to the variable where the minor version value is to be saved.
uint16_t *revisionPointer to the variable where the revsion value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getHardwareVersion()

ret_status_t Actuator::getHardwareVersion(uint8_t *tag, uint8_t *major, uint8_t *minor, uint8_t *variant)
Description

Get Actuator's Hardware version.

Parameters
DatatypeVariableDescription
uint8_t *tagPointer to the variable where the hardware tag value is to be saved.
uint8_t *majorPointer to the variable where the major version value is to be saved.
uint8_t *minorPointer to the variable where the minor version value is to be saved.
uint8_t *variantPointer to the variable where the revsion value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getIdqCurrents()

ret_status_t Actuator::getIdqCurrents(float *id_current, float *iq_current)
Description

Get the Id and Iq currents of the motor.

Parameters
DatatypeVariableDescription
float *id_currentPointer to the variable to which the Id current value is to be saved.
float *iq_currentPointer to the variable to which the Iq current value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getMotorAcceleration()

ret_status_t Actuator::getMotorAcceleration(float *rotor_acceleration)
Description

Get current acceleration of the motor rotor in rotations per second^2.

Parameters
DatatypeVariableDescription
float *rotor_accelerationPointer to the variable to which the current acceleration value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getMotorEncoderBandwidth()

ret_status_t Actuator::getMotorEncoderBandwidth(float *bandwidth)
Description

Get motor encoder bandwidth of the controller.

Parameters
DatatypeVariableDescription
float *bandwidthPointer to the variable to which the encoder bandwidth is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getMotorEncoderRawData()

ret_status_t Actuator::getMotorEncoderRawData(int32_t *encoder_data)
Description

Get raw encoder data from the encoder on the motor side. Returns the counts in case its an incremental encoder or it returns the raw bit data in case its an absolute encoder.

Parameters
DatatypeVariableDescription
int32_t *encoder_dataPointer to the variable to which the raw encoder value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getMotorEncoderState()

ret_status_t Actuator::getMotorEncoderState(bool *index_found, bool *is_ready)
Description

Get the motor encoder state of the actuator.

Parameters
DatatypeVariableDescription
bool *index_foundPointer to the variable to which the index_found state of the motor encoder is to be saved.
bool *is_readyPointer to the variable to which the is_ready state of the motor encoder is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getMotorPhaseCurrents()

ret_status_t Actuator::getMotorPhaseCurrents(float *phA, float *phB, float *phC)
Description

Get motor phase currents in Ampere.

Parameters
DatatypeVariableDescription
float *phAPointer to the variable to which the current in phase A value is to be saved.
float *phBPointer to the variable to which the current in phase B value is to be saved.
float *phCPointer to the variable to which the current in phase C value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getMotorPhaseParameters()

ret_status_t Actuator::getMotorPhaseParameters(float *phase_resistance, float *phase_inductance)
Description

Get the Motor Phase Parameters (Phase Resistance and Phase Inductance of the motor windings)

Parameters
DatatypeVariableDescription
float *phase_resistancePointer to the variable to which the phase resistance of the motor is to be saved.
float *phase_inductancePointer to the variable to which the phase inductance of the motor is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getMotorPosition()

ret_status_t Actuator::getMotorPosition(float *rotor_position)
Description

Get current angle of the motor rotor in number of rotations.

Parameters
DatatypeVariableDescription
float *rotor_positionPointer to the variable to which the current rotation value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getMotorState()

ret_status_t Actuator::getMotorState(bool *is_calibrated, bool *is_armed)
Description

Get the motor state of the actuator.

Parameters
DatatypeVariableDescription
bool *is_calibratedPointer to the variable to which the is_calibrated state of motor is to be saved.
bool *is_armedPointer to the variable to which the is_armed state of motor is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getMotorTemperature()

ret_status_t Actuator::getMotorTemperature(float *motor_temperature)
Description

Get motor temperature in degree Celsius.

Parameters
DatatypeVariableDescription
float *motor_temperaturePointer to the variable to which the current motor temperature value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getMotorThermistorConfiguration()

ret_status_t Actuator::getMotorThermistorConfiguration(bool *enable, uint16_t *r_ref, uint16_t *beta, uint8_t *upper_limit, uint8_t *lower_limit)
Description

Get the Motor thermistor configuration.

Parameters
DatatypeVariableDescription
bool *enablePointer to the variable where the enabled/disabled status of the motor thermal limit is to be saved.
uint16_t *r_refPointer to the variable to which the Reference Resistance value is to be saved.
uint16_t *betaPointer to the variable to which the beta value of thermistor is to be saved.
uint8_t *upper_limitPointer to the variable where the upper limit of the thermal limit is to be saved.
uint8_t *lower_limitPointer to the variable where the lower limit of the thermal limit is to be saved. This is the limit from which the current limiting of the driver will start.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getMotorTorque()

ret_status_t Actuator::getMotorTorque(float *rotor_torque)
Description

Get torque of the motor rotor in Nm.

Parameters
DatatypeVariableDescription
float *rotor_torquePointer to the variable to which the current torque value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getMotorVelocity()

ret_status_t Actuator::getMotorVelocity(float *rotor_velocity)
Description

Get current velocity of the motor rotor in rotations per second[rps].

Parameters
DatatypeVariableDescription
float *rotor_velocityPointer to the variable to which the current velocity value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getNodeId()

ret_status_t Actuator::getNodeId(uint32_t *node_id)
Description

Get current CAN Node ID of the actuator.

Parameters
DatatypeVariableDescription
uint32_t *node_idPointer to the variable to which the current CAN Node ID of the actuator is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getOutputAcceleration()

ret_status_t Actuator::getOutputAcceleration(float *output_acceleration)
Description

Get current acceleration of the output in degrees per second^2.

Parameters
DatatypeVariableDescription
float *output_accelerationPointer to the variable to which the current output acceleration value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getOutputEncoderRawData()

ret_status_t Actuator::getOutputEncoderRawData(int32_t *raw_data)
Description

Get the raw data from output encoder.

Parameters
DatatypeVariableDescription
int32_t *raw_dataPointer to the variable to which the raw data value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getOutputEncoderState()

ret_status_t Actuator::getOutputEncoderState(bool *is_ready)
Description

Get the output encoder state of the actuator.

Parameters
DatatypeVariableDescription
bool *is_readyPointer to the variable to which the is_ready state of the output encoder is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getOutputPosition()

ret_status_t Actuator::getOutputPosition(float *output_position)
Description

Get current angle of the output in degrees.

Parameters
DatatypeVariableDescription
float *output_positionPointer to the variable to which the current output angle value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getOutputTorque()

ret_status_t Actuator::getOutputTorque(float *output_torque)
Description

Get current torque at the output in Nm.

Parameters
DatatypeVariableDescription
float *output_torquePointer to the variable to which the current output torque value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getOutputVelocity()

ret_status_t Actuator::getOutputVelocity(float *output_velocity)
Description

Get current velocity of the output in degrees per second.

Parameters
DatatypeVariableDescription
float *output_velocityPointer to the variable to which the current velocity value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getPositionControllerGain()

ret_status_t Actuator::getPositionControllerGain(float *position_gain)
Description

Get position controller gain value.

Parameters
DatatypeVariableDescription
float *position_gainPointer to the variable to which the current position controller gain value is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getRegenCurrentTripLevel()

ret_status_t Actuator::getRegenCurrentTripLevel(float *regen_current_trip_level)
Description

Get the maximum regenerative current the power supply/battery can take.

Parameters
DatatypeVariableDescription
float *regen_current_trip_levelPointer to the variable to which the value of the maximum regeneration current that battery/supply is to be saved
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getTrajectoryDoneStatus()

ret_status_t Actuator::getTrajectoryDoneStatus(bool *is_done)
Description

Get the trajectory status of the actuator.

Parameters
DatatypeVariableDescription
bool *is_donePointer to the variable to which the status of reaching the trajectory end point is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getVelocityControllerGains()

ret_status_t Actuator::getVelocityControllerGains(float *vel_gain, float *vel_integrator_gain)
Description

Get controller velocity controller gains.

Parameters
DatatypeVariableDescription
float *vel_gainPointer to the variable to which the velocity gain value of the controller is to be saved.
float *vel_integrator_gainPointer to the variable to which the velocity integrator gain value of the controller is to be saved. controller
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.getZeroPosition()

ret_status_t Actuator::getZeroPosition(float *zero_position)
Description

Get zero offset postion in degrees.

Parameters
DatatypeVariableDescription
float *zero_positionPointer to the variable to which the zero position of the actuator is to be saved.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.isConnected()

bool Actuator::isConnected()
Description

Check if the device is still connected or not.

Returns
DatatypeDescription
booltrue

Actuator.rebootActuator()

ret_status_t Actuator::rebootActuator()
Description

Reboot the Actuator.

Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.runCalibrationSequence()

ret_status_t Actuator::runCalibrationSequence()
Description

Run calibration sequence on the acutator.

Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.saveConfigurations()

ret_status_t Actuator::saveConfigurations()
Description

Save the configuration to the actuator.

Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.setCurrentControllerBandwidth()

ret_status_t Actuator::setCurrentControllerBandwidth(float bandwidth)
Description

Set current controller bandwith.

Parameters
DatatypeVariableDescription
floatbandwidthbandwidth value of the current controller
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.setCurrentFilter()

ret_status_t Actuator::setCurrentFilter(float current_filter)
Description

Set the current data filter value in the controller.

Parameters
DatatypeVariableDescription
floatcurrent_filterValue of current filter.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.setCurrentPostionToZero()

ret_status_t Actuator::setCurrentPostionToZero()
Description

Set current position of the actuator as zero.

Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.setDCBusTripLevels()

ret_status_t Actuator::setDCBusTripLevels(float undervoltage_level, float overvoltage_level)
Description

Set the actuator's undervoltage and overvoltage trip levels. The device will throw an error when the bus voltage will drop below under-voltage level or goes higher that the over-voltage level. Used to keep the actuator safe from high transient currents and voltage fluctuations.

Parameters
DatatypeVariableDescription
floatundervoltage_levelunder-voltage trip level
floatovervoltage_levelover-voltage trip level
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.setDeviceToActive()

ret_status_t Actuator::setDeviceToActive()
Description

Set the actuator to active state.

Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.setDeviceToIdle()

ret_status_t Actuator::setDeviceToIdle()
Description

Set the actuator to idle state.

Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.setEncoderDataFilter()

ret_status_t Actuator::setEncoderDataFilter(float encoder_data_filter)
Description

Set the encoder data filter value in the controller.

Parameters
DatatypeVariableDescription
floatencoder_data_filterValue of the encoder data filter.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.setMotorEncoderBandwidth()

ret_status_t Actuator::setMotorEncoderBandwidth(float bandwidth)
Description

Set motor encoder bandwith.

Parameters
DatatypeVariableDescription
floatbandwidthbandwidth value of the encoder
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.setNodeId()

ret_status_t Actuator::setNodeId(uint32_t id)
Description

Set the node id for the actuator.

Parameters
DatatypeVariableDescription
uint32_tidCAN Node ID of the actuator
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.setOutputLogStream()

void Actuator::setOutputLogStream(std::ostream *out)
Description

Set an output log stream object to which the low-level logs can be written. To be used for debugging purposes.

Parameters
DatatypeVariableDescription
std::ostream *outOutput log stream object

Actuator.setPositionControl()

ret_status_t Actuator::setPositionControl(float angle, float degrees_per_seconds)
Description

Set the Actuator in Position Control mode.

Parameters
DatatypeVariableDescription
floatangleangle in degrees to where the actuator should move
floatdegrees_per_secondsvelocity in degrees per second at which the actuator should move
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.setPositionControllerGain()

ret_status_t Actuator::setPositionControllerGain(float position_gain)
Description

Set position controller gain value.

Parameters
DatatypeVariableDescription
floatposition_gainpos gain value of the position controller
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.setRegenCurrentTripLevel()

ret_status_t Actuator::setRegenCurrentTripLevel(float regen_current_trip_level)
Description

Set the maximum regenerative current the power supply/battery can take. The device will throw DC_BUS_OVERREGEN Error if the current sink is more than this value.

Parameters
DatatypeVariableDescription
floatregen_current_trip_levelmaximum regeneration current that battery/supply can take in
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.setTorqueControl()

ret_status_t Actuator::setTorqueControl(float torque, float degrees_per_seconds)
Description

Set the actuator in Torque Control mode.

Parameters
DatatypeVariableDescription
floattorquemotor torque in Nm
floatdegrees_per_secondsvelocity limit in degrees per seconds
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.setTrajectoryControl()

ret_status_t Actuator::setTrajectoryControl(float angle, float degrees_per_seconds, float accel_rate, float decel_rate)
Description

Set the Actuator in Trajectory Control mode.

Parameters
DatatypeVariableDescription
floatangleangle in degrees to where the actuator should move
floatdegrees_per_secondsvelocity in degrees per second at which the actuator should move
floataccel_ratevelocity in degrees per seconds
floatdecel_ratevelocity in degrees per seconds
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.setVelocityControl()

ret_status_t Actuator::setVelocityControl(float degrees_per_seconds)
Description

Set the actuator in Velocity Control mode.

Parameters
DatatypeVariableDescription
floatdegrees_per_secondsvelocity in degrees per second at which the actuator should move.
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.setVelocityControllerGains()

ret_status_t Actuator::setVelocityControllerGains(float vel_gain, float vel_integrator_gain)
Description

Set velocity controller gains.

Parameters
DatatypeVariableDescription
floatvel_gainvelocity gain value of the velocity controller
floatvel_integrator_gainvelocity integrator gain value of the velocity controller
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.setVelocityRampControl()

ret_status_t Actuator::setVelocityRampControl(float degrees_per_seconds, float ramp_rate_degrees_per_seconds)
Description

Set the actuator in Velocity Ramp Control mode.

Parameters
DatatypeVariableDescription
floatdegrees_per_secondsvelocity in degrees per second at which the actuator should move
floatramp_rate_degrees_per_secondsvelocity ramp rate in degrees per seconds
Returns
DatatypeDescription
ret_status_tReturn Status

Actuator.~Actuator()

Actuator::~Actuator()
Description

Destroy the Actuator object.

Python API Reference

Actuator.__init__()

__init__(id: int, interface: USBInterface) 
Description

Actuator class constructor.

Parameters
DatatypeVariableDescription
intidCAN Node ID of the Actuator
USBInterfaceinterfaceInitialised CANInterface or USBInterface object

Actuator.clearActuatorErrors()

clearActuatorErrors() -> int
Description

Clear actuator errors.

Returns
DatatypeDescription
intReturn Status

Actuator.disableMotorThermalLimit()

disableMotorThermalLimit(upper_limit: int) -> int
Description

Disable Motor based thermal limit.

Parameters
DatatypeVariableDescription
intupper_limit-
Returns
DatatypeDescription
intReturn Status

Actuator.emergencyStop()

emergencyStop() ->  'int'
Description

Function to issue an emergency stop to the device which stops the actuator and sets the error flag; Since the error flag is set the actuator doesn't respond to any other commands, until the actuator is rebooted.

Returns
DatatypeDescription
'int'Return status

Actuator.enableMotorThermalLimit()

enableMotorThermalLimit(upper_limit: int) -> int
Description

Enable Motor based Thermal limit.

Parameters
DatatypeVariableDescription
intupper_limitShutdown temperature at which the actuator will stop.
Returns
DatatypeDescription
intReturn Status

Actuator.eraseConfigurations()

eraseConfigurations() -> int
Description

Erase configuration of the actuator.

Returns
DatatypeDescription
intReturn Status

Actuator.getBusCurrent()

getBusCurrent() ->  'tuple[int, float]'
Description

Get the bus current of the actuator.

Returns
DatatypeDescription
'tuple[int,float]'Tuple containing return status and bus current.

Actuator.getBusVoltage()

getBusVoltage() ->  'tuple[int, float]'
Description

Get the bus voltage of the actuator.

Returns
DatatypeDescription
'tuple[int,float]'Tuple containing return status and bus voltage.

Actuator.getCANCommunicationStatus()

getCANCommunicationStatus() ->  'tuple[int, bool, bool]'
Description

Get CAN communication status.

Returns
DatatypeDescription
'tuple[int,bool,bool]'Tuple containing the return status, master connection status (true means master connection is OK) and heartbeat receive status (true means the device is still receiving heartbeat from master).

Actuator.getControllerMode()

getControllerMode() ->  'tuple[int, int]'
Description

Get controller mode.

control_mode valueDescription
1Torque Control
2Velocity Control or Ramped Velocity Control
3Position Control or Trapezoidal Trajectory Control
Returns
DatatypeDescription
'tuple[int,int]'Tuple containing the return status and the control mode value.

Actuator.getControllerState()

getControllerState() ->  'tuple[int, int]'
Description

Get the controller state of the actuator.

controller_state valueDescription
0STATE_UNDEFINED
1STATE_IDLE
6STATE_INDEX_SEARCH
8STATE_CLOSED_LOOP_CONTROL
Returns
DatatypeDescription
'tuple[int,int]'Tuple containing the return status and the controller state value.

Actuator.getCurrentControllerBandwidth()

getCurrentControllerBandwidth() ->  'tuple[int, float]'
Description

Get current controller bandwidth.

Returns
DatatypeDescription
'tuple[int,float]'Tuple containing return status and the current controller bandwidth value.

Actuator.getCurrentControllerGains()

getCurrentControllerGains() ->  'tuple[int, float, float]'
Description

Get current controller gains.

Returns
DatatypeDescription
'tuple[int,float,float]'Tuple containing return status, current controller gain value and current controller integrator gain value.

Actuator.getCurrentFilter()

getCurrentFilter() ->  'tuple[float]'
Description

Get the current data filter value of the controller.

Returns
DatatypeDescription
'tuple[float]'Tuple containing return status and the current data filter value.

Actuator.getDCBusTripLevels()

getDCBusTripLevels() ->  'tuple[int, float, float]'
Description

Get the actuator's current under-voltage and over-voltage levels.

Returns
DatatypeDescription
'tuple[int,float,float]'Tuple containing return status, undervoltage level & overvoltage level

Actuator.getDriverFault()

getDriverFault() ->  'tuple[int, int]'
Description

Get the Driver error status from the actuator.

Returns
DatatypeDescription
'tuple[int,int]'Tuple containing the return status and the driver error value.

Actuator.getDriverTemperature()

getDriverTemperature() ->  'tuple[int, float]'
Description

Get driver temperature in degree Celsius.

Returns
DatatypeDescription
'tuple[int,float]'Tuple containing return status and driver temperature.

Actuator.getEncoderDataFilter()

getEncoderDataFilter() ->  'tuple[int, float]'
Description

Get the current value of encoder data filter in the controller.

Returns
DatatypeDescription
'tuple[int,float]'Tuple containing return status and the current encoder data filter value.

Actuator.getErrorCode()

getErrorCode() ->  'tuple[int, int]'
Description

Get the error code from the actuator.

Returns
DatatypeDescription
'tuple[int,int]'Tuple containing the return status and the error code value.

Actuator.getFirmwareVersion()

getFirmwareVersion() ->  'tuple[int, int, int, int]'
Description

Get the actuator firmware's major, minor and revision information.

Returns
DatatypeDescription
'tuple[int,int,int,int]'Tuple containing return status, major, minor and revision information.

Actuator.getHardwareVersion()

getHardwareVersion() ->  'tuple[int, int, int, int, int]'
Description

Get the actuator hardware's current tag, major, minor and variant information.

Returns
DatatypeDescription
'tuple[int,int,int,int,int]'Tuple containing return status, tag, major, minor and variant information.

Actuator.getIdqCurrents()

getIdqCurrents() ->  'tuple[int, float, float]'
Description

Get the Id and Iq currents of the motor.

Returns
DatatypeDescription
'tuple[int,float,float]'Tuple containing return status, Id current and Iq current values.

Actuator.getMotorAcceleration()

getMotorAcceleration() ->  'tuple[int, float]'
Description

Get current acceleration of the motor rotor in rotations per second^2.

Returns
DatatypeDescription
'tuple[int,float]'Tuple containing return status and the current acceleration value.

Actuator.getMotorEncoderBandwidth()

getMotorEncoderBandwidth() ->  'tuple[int, float]'
Description

Get current motor bandwidth value.

Returns
DatatypeDescription
'tuple[int,float]'Tuple containing return status and current motor bandwidth value.

Actuator.getMotorEncoderRawData()

getMotorEncoderRawData() ->  'tuple[int, int]'
Description

Get the raw encoder count from the motor.

Returns
DatatypeDescription
'tuple[int,int]'Tuple containing return status and raw count value of the incremental encoder.

Actuator.getMotorEncoderState()

getMotorEncoderState() ->  'tuple[int, bool, bool]'
Description

Get the motor encoder state of the actuator.

Returns
DatatypeDescription
'tuple[int,bool,bool]'Tuple containing the return status, index state (true means encoder found the index) and ready sate (true means the encoder is ready) of the motor encoder.

Actuator.getMotorPhaseCurrents()

getMotorPhaseCurrents() ->  'tuple[int, float, float, float]'
Description

Get motor phase currents in Ampere.

Returns
DatatypeDescription
'tuple[int,float,float,float]'Tuple containing return status and currents in phase A, B and C

Actuator.getMotorPhaseParameters()

getMotorPhaseParameters() ->  'tuple[int, float, float]'
Description

Get motor phase currents in Ampere.

Returns
DatatypeDescription
'tuple[int,float,float]'Tuple containing return status and currents in phase A, B and C

Actuator.getMotorPosition()

getMotorPosition() ->  'tuple[int, float]'
Description

Get current angle of the motor rotor in number of rotations.

Returns
DatatypeDescription
'tuple[int,float]'Tuple contatining return status and the current rotation value

Actuator.getMotorState()

getMotorState() ->  'tuple[int, bool, bool]'
Description

Get the motor state of the actuator.

Returns
DatatypeDescription
'tuple[int,bool,bool]'Tuple containing the return status, calibration state status (true means motor is calibrated) and the armed state (true means motor is currently armed) status of the motor.

Actuator.getMotorTemperature()

getMotorTemperature() ->  'tuple[int, float]'
Description

Get motor temperature in degree Celsius.

Returns
DatatypeDescription
'tuple[int,float]'Tuple containing return status and motor temperature.

Actuator.getMotorThermistorConfiguration()

getMotorThermistorConfiguration() ->  'tuple[bool, int, int, int, int]'
Description

Get the motor thermistor configuration.

Returns
DatatypeDescription
'tuple[bool,int,int,int,int]'Tuple containig return status, thermal limit enable status, upper limit and lower limit

Actuator.getMotorTorque()

getMotorTorque() ->  'tuple[int, float]'
Description

Get torque of the motor rotor in Nm.

Returns
DatatypeDescription
'tuple[int,float]'Tuple contatining return status and torque value.

Actuator.getMotorVelocity()

getMotorVelocity() ->  'tuple[int, float]'
Description

Get current velocity of the motor rotor in rotations per second.

Returns
DatatypeDescription
'tuple[int,float]'Tuple containing return status and the current velocity value.

Actuator.getNodeId()

getNodeId() ->  'tuple[int, int]'
Description

Get current CAN Node ID of the actuator.

Returns
DatatypeDescription
'tuple[int,int]'Tuple containing return status and the current CAN Node ID.

Actuator.getOutputAcceleration()

getOutputAcceleration() ->  'tuple[int, float]'
Description

Get current acceleration of the output in degrees per second^2.

Returns
DatatypeDescription
'tuple[int,float]'Tuple containing return status and current output acceleration.

Actuator.getOutputEncoderRawData()

getOutputEncoderRawData() ->  'tuple[int, int]'
Description

Get the raw data from output encoder.

Returns
DatatypeDescription
'tuple[int,int]'Tuple containing the return status and raw data value of the absolute encoder.

Actuator.getOutputEncoderState()

getOutputEncoderState() ->  'tuple[int, bool]'
Description

Get the output encoder state of the actuator.

Returns
DatatypeDescription
'tuple[int,bool]'Tuple containing return status and ready state (true means the encoder is ready) of the output encoder.

Actuator.getOutputPosition()

getOutputPosition() ->  'tuple[int, float]'
Returns
DatatypeDescription
'tuple[int,float]'-

Actuator.getOutputTorque()

getOutputTorque() ->  'tuple[int, float]'
Description

Get current torque at the output in Nm.

Returns
DatatypeDescription
'tuple[int,float]'Tuple containing return status and output torque.

Actuator.getOutputVelocity()

getOutputVelocity() ->  'tuple[int, float]'
Description

Get current velocity of output in degrees per second.

Returns
DatatypeDescription
'tuple[int,float]'Tuple containing return status and current output velocity.

Actuator.getPositionControllerGain()

getPositionControllerGain() ->  'tuple[int, float]'
Description

Get position controller gain value.

Returns
DatatypeDescription
'tuple[int,float]'Tuple containing return status and the current position controller gain value.

Actuator.getRegenCurrentTripLevel()

getRegenCurrentTripLevel() ->  'tuple[int, float]'
Description

Get the maximum regenerative current the power supply/battery can take.

Returns
DatatypeDescription
'tuple[int,float]'Tuple containing the return status and value of maximum regenerative current which is set.

Actuator.getTrajectoryDoneStatus()

getTrajectoryDoneStatus() ->  'tuple[int, bool]'
Description

Get the trajectory status of the actuator.

Returns
DatatypeDescription
'tuple[int,bool]'Tuple containing return status and the trajectory done status (true means the motion along the trajectory is complete)

Actuator.getVelocityControllerGains()

getVelocityControllerGains() ->  'tuple[int, float, float]'
Description

Get controller velocity controller gains.

Returns
DatatypeDescription
'tuple[int,float,float]'Tuple containing return status, velocity controller gain value and velocity controller integrator gain value.

Actuator.getZeroPosition()

getZeroPosition() ->  'tuple[int, float]'
Description

Get zero offset postion in degrees.

Returns
DatatypeDescription
'tuple[int,float]'Tuple containing return status and the current zero offset position.

Actuator.isConnected()

isConnected() ->  'bool'
Description

Check if the driver is still connected.

Returns
DatatypeDescription
'bool'Connection Status

Actuator.rebootActuator()

rebootActuator() -> int
Description

Reboot the Actuator.

Returns
DatatypeDescription
intReturn Status

Actuator.runCalibrationSequence()

runCalibrationSequence() -> int
Description

Run calibration sequence on the actuator.

Returns
DatatypeDescription
intReturn Status

Actuator.saveConfigurations()

saveConfigurations() -> int
Description

Save the configuration to the actuator.

Returns
DatatypeDescription
intReturn Status

Actuator.setCurrentControllerBandwidth()

setCurrentControllerBandwidth(bandwidth: float) -> int
Description

Set current controller bandwith.

Parameters
DatatypeVariableDescription
floatbandwidthBandwidth value for the current controller.
Returns
DatatypeDescription
intReturn status

Actuator.setCurrentFilter()

setCurrentFilter(current_filter: float) -> int
Description

Set the current data filter value in the controller.

Parameters
DatatypeVariableDescription
floatcurrent_filterValue of current filter.
Returns
DatatypeDescription
intReturn Status

Actuator.setCurrentPostionToZero()

setCurrentPostionToZero() -> int
Description

Set current position of the actuator as zero.

Returns
DatatypeDescription
intReturn Statu

Actuator.setDCBusTripLevels()

setDCBusTripLevels(undervoltage_level: float, overvoltage_level: float) ->  'int'
Description

Set the actuator's undervoltage and overvoltage trip levels.

Parameters
DatatypeVariableDescription
floatundervoltage_levelunder-voltage trip level
floatovervoltage_levelover-voltage trip level
Returns
DatatypeDescription
'int'Return status

Actuator.setDeviceToActive()

setDeviceToActive() ->  'int'
Description

Set the actuator to active state.

Returns
DatatypeDescription
'int'Return status

Actuator.setDeviceToIdle()

setDeviceToIdle() ->  'int'
Description

Set the actuator to idle state.

Returns
DatatypeDescription
'int'Return status

Actuator.setEncoderDataFilter()

setEncoderDataFilter(encoder_data_filter: float) -> int
Description

Set the encoder data filter value in the controller.

Parameters
DatatypeVariableDescription
floatencoder_data_filtervalue of encoder data filter.
Returns
DatatypeDescription
intReturn Status

Actuator.setMotorEncoderBandwidth()

setMotorEncoderBandwidth(bandwidth: float) -> int
Description

Set motor encoder bandwidth value.

Parameters
DatatypeVariableDescription
floatbandwidthBandwidth value
Returns
DatatypeDescription
intReturn status

Actuator.setNodeId()

setNodeId(id: int) ->  'int'
Description

Set the node id for the actuator.

Parameters
DatatypeVariableDescription
intidCAN Device ID of the actuator
Returns
DatatypeDescription
'int'Return Status

Actuator.setPositionControl()

setPositionControl(angle: float, degrees_per_seconds: float) -> int
Description

Set the actuator in position control mode.

Parameters
DatatypeVariableDescription
floatangleangle in degrees to where the actuator should move.
floatdegrees_per_secondsvelocity in degrees per second at which the actuator should move.
Returns
DatatypeDescription
intReturn Status

Actuator.setPositionControllerGain()

setPositionControllerGain(pos_gain: float) -> int
Description

Set position controller gain value.

Parameters
DatatypeVariableDescription
floatpos_gainposition gain value of the position controller
Returns
DatatypeDescription
intReturn Status

Actuator.setRegenCurrentTripLevel()

setRegenCurrentTripLevel(regen_current_trip_level: float) -> int
Description

Set the maximum regenerative current the power supply/battery can take.

Parameters
DatatypeVariableDescription
floatregen_current_trip_levelmaximum regeneration current that battery/supply can take in
Returns
DatatypeDescription
intReturn status

Actuator.setTorqueControl()

setTorqueControl(torque: float, degrees_per_second: float) -> int
Description

Set the actuator in torque control mode.

Parameters
DatatypeVariableDescription
floattorqueMotor Torque in Nm
floatdegrees_per_secondVelocity limit in degrees per second when the actuator is moving.
Returns
DatatypeDescription
intReturn Status

Actuator.setTrajectoryControl()

setTrajectoryControl(angle: float, degrees_per_seconds: float, accel_rate: float, decel_rate: float) -> int
Description

Set the actuator in trajectory control mode.

Parameters
DatatypeVariableDescription
floatangleangle in degrees to where the actuator should move
floatdegrees_per_secondsvelocity in degrees per second at which the actuator should move
floataccel_rateacceleration rate as a factor of velocity in degrees per second^2.
floatdecel_ratedeacceleration rate as a factor of velocity in degrees per second^2.
Returns
DatatypeDescription
intReturn Status

Actuator.setVelocityControl()

setVelocityControl(degrees_per_seconds: float) -> int
Description

Set the actuator in Velocity Control mode.

Parameters
DatatypeVariableDescription
floatdegrees_per_secondsvelocity in degrees per second at which the actuator should move.
Returns
DatatypeDescription
intReturn Status

Actuator.setVelocityControllerGains()

setVelocityControllerGains(vel_gain: float, vel_integrator_gain: float) -> int
Description

Set velocity controller gains.

Parameters
DatatypeVariableDescription
floatvel_gainvelocity gain value of the velocity controller
floatvel_integrator_gainvelocity integrator gain value of the velocity controller
Returns
DatatypeDescription
intReturn status

Actuator.setVelocityRampControl()

setVelocityRampControl(degrees_per_seconds: float, ramp_rate_degrees_per_second: float) -> int
Description

Set the actuator in Velocity Ramp Control mode.

Parameters
DatatypeVariableDescription
floatdegrees_per_secondsvelocity in degrees per second at which the actuator should move.
floatramp_rate_degrees_per_secondvelocity ramp rate.
Returns
DatatypeDescription
intReturn Status
  NMotionTM  is a sub-brand of Nawe Robotics
Copyright © 2025 Nawe Robotics Private Limited