C/C++ API Reference
Actuator.Actuator()
Actuator::Actuator(uint32_t node_id, Interface *interface)
Description
Construct a new Actuator object.
Parameters
| Datatype | Variable | Description |
|---|
uint32_t | node_id | CAN Node ID of the Actuator |
Interface * | interface | Initialised CAN Interface object for the interface to which the Actuator is connected |
Actuator.clearActuatorErrors()
ret_status_t Actuator::clearActuatorErrors()
Description
Clear actuator errors.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.disableMotorThermalLimit()
ret_status_t Actuator::disableMotorThermalLimit()
Description
Disable Motor based Thermal limit.
Returns
| Datatype | Description |
|---|
ret_status_t | Return 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
| Datatype | Description |
|---|
ret_status_t | Return 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
| Datatype | Variable | Description |
|---|
uint16_t | upper_limit | Shutdown temperature at which the actuator will stop. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.eraseConfigurations()
ret_status_t Actuator::eraseConfigurations()
Description
Erase Configuration of the actuator.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.flash()
ret_status_t Actuator::flash(std::string firmware_path)
Description
Flash a firmware onto the device.
Parameters
| Datatype | Variable | Description |
|---|
std::string | firmware_path | path to firmware file |
Returns
| Datatype | Description |
|---|
ret_status_t | ret_status_t |
Actuator.getBusCurrent()
ret_status_t Actuator::getBusCurrent(float *ibus)
Description
Get the Bus Current of the actuator.
Parameters
| Datatype | Variable | Description |
|---|
float * | ibus | Pointer to the variable to which the bus current value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getBusVoltage()
ret_status_t Actuator::getBusVoltage(float *vbus_voltage)
Description
Get the Bus Voltage of the actuator.
Parameters
| Datatype | Variable | Description |
|---|
float * | vbus_voltage | Pointer to the variable to which the current bus voltage value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getCANCommunicationStatus()
ret_status_t Actuator::getCANCommunicationStatus(bool *is_connected_to_master, bool *is_receiving_heartbeat)
Description
Get CAN communication status.
Parameters
| Datatype | Variable | Description |
|---|
bool * | is_connected_to_master | Pointer to the variable to which the status of connection to master node is to be saved. |
bool * | is_receiving_heartbeat | Pointer to the variable to which the heartbeat receive status is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getControllerMode()
ret_status_t Actuator::getControllerMode(uint16_t *control_mode)
Description
Get controller mode.
control_mode value | Description |
|---|
| 1 | Torque Control |
| 2 | Velocity Control or Ramped Velocity Control |
| 3 | Position Control or Trapezoidal Trajectory Control |
Parameters
| Datatype | Variable | Description |
|---|
uint16_t * | control_mode | Pointer to the variable to which the value of control mode is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getControllerState()
ret_status_t Actuator::getControllerState(uint8_t *controller_state)
Description
Get the controller state of the driver.
controller_state value | Description |
|---|
| 0 | STATE_UNDEFINED |
| 1 | STATE_IDLE |
| 6 | STATE_INDEX_SEARCH |
| 8 | STATE_CLOSED_LOOP_CONTROL |
Parameters
| Datatype | Variable | Description |
|---|
uint8_t * | controller_state | Pointer to the variable to which the controller state value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getCurrentControllerBandwidth()
ret_status_t Actuator::getCurrentControllerBandwidth(float *bandwidth)
Description
Get current bandwidth of the controller.
Parameters
| Datatype | Variable | Description |
|---|
float * | bandwidth | Pointer to the variable to which the current controller bandwidth is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getCurrentControllerGains()
ret_status_t Actuator::getCurrentControllerGains(float *p_gain, float *i_gain)
Description
Get current controller gains.
Parameters
| Datatype | Variable | Description |
|---|
float * | p_gain | Pointer to the variable to which the current controller gain value of the controller is to be saved. |
float * | i_gain | Pointer to the variable to which the current controller integrator gain value of the controller is to be saved. controller |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getCurrentFilter()
ret_status_t Actuator::getCurrentFilter(float *current_filter)
Description
Set the current data filter value in the controller.
Parameters
| Datatype | Variable | Description |
|---|
float * | current_filter | Value of current filter. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return 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
| Datatype | Variable | Description |
|---|
float * | undervoltage_level | Pointer to the variable where the under-voltage trip level is to be saved. |
float * | overvoltage_level | Pointer to the variable where the over-voltage trip level is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getDriverFault()
ret_status_t Actuator::getDriverFault(uint32_t *driver_error)
Description
Get the Driver error status from the actuator.
Parameters
| Datatype | Variable | Description |
|---|
uint32_t * | driver_error | Pointer to the variable to which the value of driver error is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return 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
| Datatype | Variable | Description |
|---|
float * | driver_temperature | Pointer to the variable to which the current driver temperature value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return 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
| Datatype | Variable | Description |
|---|
float * | encoder_data_filter | Pointer to the variable to which the current encoder data filter value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getErrorCode()
ret_status_t Actuator::getErrorCode(uint32_t *error_code)
Description
Get the error code from the actuator.
Parameters
| Datatype | Variable | Description |
|---|
uint32_t * | error_code | Pointer to the variable to which the value of error code is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getFirmwareVersion()
ret_status_t Actuator::getFirmwareVersion(uint8_t *major, uint8_t *minor, uint16_t *revision)
Description
Get Driver's Firmware version.
Parameters
| Datatype | Variable | Description |
|---|
uint8_t * | major | Pointer to the variable where the major version value is to be saved. |
uint8_t * | minor | Pointer to the variable where the minor version value is to be saved. |
uint16_t * | revision | Pointer to the variable where the revsion value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return 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
| Datatype | Variable | Description |
|---|
uint8_t * | tag | Pointer to the variable where the hardware tag value is to be saved. |
uint8_t * | major | Pointer to the variable where the major version value is to be saved. |
uint8_t * | minor | Pointer to the variable where the minor version value is to be saved. |
uint8_t * | variant | Pointer to the variable where the revsion value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return 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
| Datatype | Variable | Description |
|---|
float * | id_current | Pointer to the variable to which the Id current value is to be saved. |
float * | iq_current | Pointer to the variable to which the Iq current value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return 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
| Datatype | Variable | Description |
|---|
float * | rotor_acceleration | Pointer to the variable to which the current acceleration value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getMotorEncoderBandwidth()
ret_status_t Actuator::getMotorEncoderBandwidth(float *bandwidth)
Description
Get motor encoder bandwidth of the controller.
Parameters
| Datatype | Variable | Description |
|---|
float * | bandwidth | Pointer to the variable to which the encoder bandwidth is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return 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
| Datatype | Variable | Description |
|---|
int32_t * | encoder_data | Pointer to the variable to which the raw encoder value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getMotorEncoderState()
ret_status_t Actuator::getMotorEncoderState(bool *index_found, bool *is_ready)
Description
Get the motor encoder state of the actuator.
Parameters
| Datatype | Variable | Description |
|---|
bool * | index_found | Pointer to the variable to which the index_found state of the motor encoder is to be saved. |
bool * | is_ready | Pointer to the variable to which the is_ready state of the motor encoder is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getMotorPhaseCurrents()
ret_status_t Actuator::getMotorPhaseCurrents(float *phA, float *phB, float *phC)
Description
Get motor phase currents in Ampere.
Parameters
| Datatype | Variable | Description |
|---|
float * | phA | Pointer to the variable to which the current in phase A value is to be saved. |
float * | phB | Pointer to the variable to which the current in phase B value is to be saved. |
float * | phC | Pointer to the variable to which the current in phase C value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return 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
| Datatype | Variable | Description |
|---|
float * | phase_resistance | Pointer to the variable to which the phase resistance of the motor is to be saved. |
float * | phase_inductance | Pointer to the variable to which the phase inductance of the motor is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getMotorPosition()
ret_status_t Actuator::getMotorPosition(float *rotor_position)
Description
Get current angle of the motor rotor in number of rotations.
Parameters
| Datatype | Variable | Description |
|---|
float * | rotor_position | Pointer to the variable to which the current rotation value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getMotorState()
ret_status_t Actuator::getMotorState(bool *is_calibrated, bool *is_armed)
Description
Get the motor state of the actuator.
Parameters
| Datatype | Variable | Description |
|---|
bool * | is_calibrated | Pointer to the variable to which the is_calibrated state of motor is to be saved. |
bool * | is_armed | Pointer to the variable to which the is_armed state of motor is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getMotorTemperature()
ret_status_t Actuator::getMotorTemperature(float *motor_temperature)
Description
Get motor temperature in degree Celsius.
Parameters
| Datatype | Variable | Description |
|---|
float * | motor_temperature | Pointer to the variable to which the current motor temperature value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return 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
| Datatype | Variable | Description |
|---|
bool * | enable | Pointer to the variable where the enabled/disabled status of the motor thermal limit is to be saved. |
uint16_t * | r_ref | Pointer to the variable to which the Reference Resistance value is to be saved. |
uint16_t * | beta | Pointer to the variable to which the beta value of thermistor is to be saved. |
uint8_t * | upper_limit | Pointer to the variable where the upper limit of the thermal limit is to be saved. |
uint8_t * | lower_limit | Pointer 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
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getMotorTorque()
ret_status_t Actuator::getMotorTorque(float *rotor_torque)
Description
Get torque of the motor rotor in Nm.
Parameters
| Datatype | Variable | Description |
|---|
float * | rotor_torque | Pointer to the variable to which the current torque value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return 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
| Datatype | Variable | Description |
|---|
float * | rotor_velocity | Pointer to the variable to which the current velocity value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getNodeId()
ret_status_t Actuator::getNodeId(uint32_t *node_id)
Description
Get current CAN Node ID of the actuator.
Parameters
| Datatype | Variable | Description |
|---|
uint32_t * | node_id | Pointer to the variable to which the current CAN Node ID of the actuator is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getOutputAcceleration()
ret_status_t Actuator::getOutputAcceleration(float *output_acceleration)
Description
Get current acceleration of the output in degrees per second^2.
Parameters
| Datatype | Variable | Description |
|---|
float * | output_acceleration | Pointer to the variable to which the current output acceleration value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getOutputEncoderRawData()
ret_status_t Actuator::getOutputEncoderRawData(int32_t *raw_data)
Description
Get the raw data from output encoder.
Parameters
| Datatype | Variable | Description |
|---|
int32_t * | raw_data | Pointer to the variable to which the raw data value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getOutputEncoderState()
ret_status_t Actuator::getOutputEncoderState(bool *is_ready)
Description
Get the output encoder state of the actuator.
Parameters
| Datatype | Variable | Description |
|---|
bool * | is_ready | Pointer to the variable to which the is_ready state of the output encoder is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getOutputPosition()
ret_status_t Actuator::getOutputPosition(float *output_position)
Description
Get current angle of the output in degrees.
Parameters
| Datatype | Variable | Description |
|---|
float * | output_position | Pointer to the variable to which the current output angle value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getOutputTorque()
ret_status_t Actuator::getOutputTorque(float *output_torque)
Description
Get current torque at the output in Nm.
Parameters
| Datatype | Variable | Description |
|---|
float * | output_torque | Pointer to the variable to which the current output torque value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getOutputVelocity()
ret_status_t Actuator::getOutputVelocity(float *output_velocity)
Description
Get current velocity of the output in degrees per second.
Parameters
| Datatype | Variable | Description |
|---|
float * | output_velocity | Pointer to the variable to which the current velocity value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getPositionControllerGain()
ret_status_t Actuator::getPositionControllerGain(float *position_gain)
Description
Get position controller gain value.
Parameters
| Datatype | Variable | Description |
|---|
float * | position_gain | Pointer to the variable to which the current position controller gain value is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return 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
| Datatype | Variable | Description |
|---|
float * | regen_current_trip_level | Pointer to the variable to which the value of the maximum regeneration current that battery/supply is to be saved |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getTrajectoryDoneStatus()
ret_status_t Actuator::getTrajectoryDoneStatus(bool *is_done)
Description
Get the trajectory status of the actuator.
Parameters
| Datatype | Variable | Description |
|---|
bool * | is_done | Pointer to the variable to which the status of reaching the trajectory end point is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getVelocityControllerGains()
ret_status_t Actuator::getVelocityControllerGains(float *vel_gain, float *vel_integrator_gain)
Description
Get controller velocity controller gains.
Parameters
| Datatype | Variable | Description |
|---|
float * | vel_gain | Pointer to the variable to which the velocity gain value of the controller is to be saved. |
float * | vel_integrator_gain | Pointer to the variable to which the velocity integrator gain value of the controller is to be saved. controller |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.getZeroPosition()
ret_status_t Actuator::getZeroPosition(float *zero_position)
Description
Get zero offset postion in degrees.
Parameters
| Datatype | Variable | Description |
|---|
float * | zero_position | Pointer to the variable to which the zero position of the actuator is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.isConnected()
bool Actuator::isConnected()
Description
Check if the device is still connected or not.
Returns
| Datatype | Description |
|---|
bool | true |
Actuator.rebootActuator()
ret_status_t Actuator::rebootActuator()
Description
Reboot the Actuator.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.runCalibrationSequence()
ret_status_t Actuator::runCalibrationSequence()
Description
Run calibration sequence on the acutator.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.saveConfigurations()
ret_status_t Actuator::saveConfigurations()
Description
Save the configuration to the actuator.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.setCurrentControllerBandwidth()
ret_status_t Actuator::setCurrentControllerBandwidth(float bandwidth)
Description
Set current controller bandwith.
Parameters
| Datatype | Variable | Description |
|---|
float | bandwidth | bandwidth value of the current controller |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.setCurrentFilter()
ret_status_t Actuator::setCurrentFilter(float current_filter)
Description
Set the current data filter value in the controller.
Parameters
| Datatype | Variable | Description |
|---|
float | current_filter | Value of current filter. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.setCurrentPostionToZero()
ret_status_t Actuator::setCurrentPostionToZero()
Description
Set current position of the actuator as zero.
Returns
| Datatype | Description |
|---|
ret_status_t | Return 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
| Datatype | Variable | Description |
|---|
float | undervoltage_level | under-voltage trip level |
float | overvoltage_level | over-voltage trip level |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.setDeviceToActive()
ret_status_t Actuator::setDeviceToActive()
Description
Set the actuator to active state.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.setDeviceToIdle()
ret_status_t Actuator::setDeviceToIdle()
Description
Set the actuator to idle state.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.setEncoderDataFilter()
ret_status_t Actuator::setEncoderDataFilter(float encoder_data_filter)
Description
Set the encoder data filter value in the controller.
Parameters
| Datatype | Variable | Description |
|---|
float | encoder_data_filter | Value of the encoder data filter. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.setMotorEncoderBandwidth()
ret_status_t Actuator::setMotorEncoderBandwidth(float bandwidth)
Description
Set motor encoder bandwith.
Parameters
| Datatype | Variable | Description |
|---|
float | bandwidth | bandwidth value of the encoder |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.setNodeId()
ret_status_t Actuator::setNodeId(uint32_t id)
Description
Set the node id for the actuator.
Parameters
| Datatype | Variable | Description |
|---|
uint32_t | id | CAN Node ID of the actuator |
Returns
| Datatype | Description |
|---|
ret_status_t | Return 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
| Datatype | Variable | Description |
|---|
std::ostream * | out | Output 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
| Datatype | Variable | Description |
|---|
float | angle | angle in degrees to where the actuator should move |
float | degrees_per_seconds | velocity in degrees per second at which the actuator should move |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.setPositionControllerGain()
ret_status_t Actuator::setPositionControllerGain(float position_gain)
Description
Set position controller gain value.
Parameters
| Datatype | Variable | Description |
|---|
float | position_gain | pos gain value of the position controller |
Returns
| Datatype | Description |
|---|
ret_status_t | Return 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
| Datatype | Variable | Description |
|---|
float | regen_current_trip_level | maximum regeneration current that battery/supply can take in |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.setTorqueControl()
ret_status_t Actuator::setTorqueControl(float torque, float degrees_per_seconds)
Description
Set the actuator in Torque Control mode.
Parameters
| Datatype | Variable | Description |
|---|
float | torque | motor torque in Nm |
float | degrees_per_seconds | velocity limit in degrees per seconds |
Returns
| Datatype | Description |
|---|
ret_status_t | Return 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
| Datatype | Variable | Description |
|---|
float | angle | angle in degrees to where the actuator should move |
float | degrees_per_seconds | velocity in degrees per second at which the actuator should move |
float | accel_rate | velocity in degrees per seconds |
float | decel_rate | velocity in degrees per seconds |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.setVelocityControl()
ret_status_t Actuator::setVelocityControl(float degrees_per_seconds)
Description
Set the actuator in Velocity Control mode.
Parameters
| Datatype | Variable | Description |
|---|
float | degrees_per_seconds | velocity in degrees per second at which the actuator should move. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.setVelocityControllerGains()
ret_status_t Actuator::setVelocityControllerGains(float vel_gain, float vel_integrator_gain)
Description
Set velocity controller gains.
Parameters
| Datatype | Variable | Description |
|---|
float | vel_gain | velocity gain value of the velocity controller |
float | vel_integrator_gain | velocity integrator gain value of the velocity controller |
Returns
| Datatype | Description |
|---|
ret_status_t | Return 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
| Datatype | Variable | Description |
|---|
float | degrees_per_seconds | velocity in degrees per second at which the actuator should move |
float | ramp_rate_degrees_per_seconds | velocity ramp rate in degrees per seconds |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
Actuator.~Actuator()
Description
Destroy the Actuator object.
Python API Reference
Actuator.__init__()
__init__(id: int, interface: USBInterface)
Description
Actuator class constructor.
Parameters
| Datatype | Variable | Description |
|---|
int | id | CAN Node ID of the Actuator |
USBInterface | interface | Initialised CANInterface or USBInterface object |
Actuator.clearActuatorErrors()
clearActuatorErrors() -> int
Description
Clear actuator errors.
Returns
| Datatype | Description |
|---|
int | Return Status |
Actuator.disableMotorThermalLimit()
disableMotorThermalLimit(upper_limit: int) -> int
Description
Disable Motor based thermal limit.
Parameters
| Datatype | Variable | Description |
|---|
int | upper_limit | - |
Returns
| Datatype | Description |
|---|
int | Return Status |
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
| Datatype | Description |
|---|
'int' | Return status |
Actuator.enableMotorThermalLimit()
enableMotorThermalLimit(upper_limit: int) -> int
Description
Enable Motor based Thermal limit.
Parameters
| Datatype | Variable | Description |
|---|
int | upper_limit | Shutdown temperature at which the actuator will stop. |
Returns
| Datatype | Description |
|---|
int | Return Status |
Actuator.eraseConfigurations()
eraseConfigurations() -> int
Description
Erase configuration of the actuator.
Returns
| Datatype | Description |
|---|
int | Return Status |
Actuator.getBusCurrent()
getBusCurrent() -> 'tuple[int, float]'
Description
Get the bus current of the actuator.
Returns
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'tuple[int,float]' | Tuple containing return status and bus voltage. |
Actuator.getCANCommunicationStatus()
getCANCommunicationStatus() -> 'tuple[int, bool, bool]'
Description
Get CAN communication status.
Returns
| Datatype | Description |
|---|
'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 value | Description |
|---|
| 1 | Torque Control |
| 2 | Velocity Control or Ramped Velocity Control |
| 3 | Position Control or Trapezoidal Trajectory Control |
Returns
| Datatype | Description |
|---|
'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 value | Description |
|---|
| 0 | STATE_UNDEFINED |
| 1 | STATE_IDLE |
| 6 | STATE_INDEX_SEARCH |
| 8 | STATE_CLOSED_LOOP_CONTROL |
Returns
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'tuple[int,float]' | - |
Actuator.getOutputTorque()
getOutputTorque() -> 'tuple[int, float]'
Description
Get current torque at the output in Nm.
Returns
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'tuple[int,float]' | Tuple containing return status and current output velocity. |
Actuator.getPositionControllerGain()
getPositionControllerGain() -> 'tuple[int, float]'
Description
Get position controller gain value.
Returns
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'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
| Datatype | Description |
|---|
'tuple[int,float]' | Tuple containing return status and the current zero offset position. |
Actuator.isConnected()
Description
Check if the driver is still connected.
Returns
| Datatype | Description |
|---|
'bool' | Connection Status |
Actuator.rebootActuator()
Description
Reboot the Actuator.
Returns
| Datatype | Description |
|---|
int | Return Status |
Actuator.runCalibrationSequence()
runCalibrationSequence() -> int
Description
Run calibration sequence on the actuator.
Returns
| Datatype | Description |
|---|
int | Return Status |
Actuator.saveConfigurations()
saveConfigurations() -> int
Description
Save the configuration to the actuator.
Returns
| Datatype | Description |
|---|
int | Return Status |
Actuator.setCurrentControllerBandwidth()
setCurrentControllerBandwidth(bandwidth: float) -> int
Description
Set current controller bandwith.
Parameters
| Datatype | Variable | Description |
|---|
float | bandwidth | Bandwidth value for the current controller. |
Returns
| Datatype | Description |
|---|
int | Return status |
Actuator.setCurrentFilter()
setCurrentFilter(current_filter: float) -> int
Description
Set the current data filter value in the controller.
Parameters
| Datatype | Variable | Description |
|---|
float | current_filter | Value of current filter. |
Returns
| Datatype | Description |
|---|
int | Return Status |
Actuator.setCurrentPostionToZero()
setCurrentPostionToZero() -> int
Description
Set current position of the actuator as zero.
Returns
| Datatype | Description |
|---|
int | Return Statu |
Actuator.setDCBusTripLevels()
setDCBusTripLevels(undervoltage_level: float, overvoltage_level: float) -> 'int'
Description
Set the actuator's undervoltage and overvoltage trip levels.
Parameters
| Datatype | Variable | Description |
|---|
float | undervoltage_level | under-voltage trip level |
float | overvoltage_level | over-voltage trip level |
Returns
| Datatype | Description |
|---|
'int' | Return status |
Actuator.setDeviceToActive()
setDeviceToActive() -> 'int'
Description
Set the actuator to active state.
Returns
| Datatype | Description |
|---|
'int' | Return status |
Actuator.setDeviceToIdle()
setDeviceToIdle() -> 'int'
Description
Set the actuator to idle state.
Returns
| Datatype | Description |
|---|
'int' | Return status |
Actuator.setEncoderDataFilter()
setEncoderDataFilter(encoder_data_filter: float) -> int
Description
Set the encoder data filter value in the controller.
Parameters
| Datatype | Variable | Description |
|---|
float | encoder_data_filter | value of encoder data filter. |
Returns
| Datatype | Description |
|---|
int | Return Status |
Actuator.setMotorEncoderBandwidth()
setMotorEncoderBandwidth(bandwidth: float) -> int
Description
Set motor encoder bandwidth value.
Parameters
| Datatype | Variable | Description |
|---|
float | bandwidth | Bandwidth value |
Returns