C/C++ API Reference
Driver.Driver()
Driver::Driver(uint32_t node_id, Interface *interface)
Description
Construct a new Driver object.
Parameters
Datatype | Variable | Description |
---|
uint32_t | node_id | CAN Node ID of the driver |
Interface * | interface | Initialised CAN Interface object for the interface to which the driver is connected |
Driver.clearDriverErrors()
ret_status_t Driver::clearDriverErrors()
Description
Clear driver errors.
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
ret_status_t Driver::configureMotorEncoder(uint8_t encoder_type, int32_t resolution_param=4096, bool use_index=true)
Description
Configure motor side encoder. Set it to onboard absolute, external incremental or external absolute. Output side and motor side encoders can't be set to same.
encoder_type value | Encoder Type | Description |
---|
0 | TYPE_NONE | Using no encoder |
1 | TYPE_ONBOARD_ENCODER | Using onboard absolute encoder (Tested) |
2 | TYPE_INCREMENTAL | Using External incremental Encoder (Tested) |
3 | TYPE_SPI_ABS_AMS | Using AS5047P absolute encoder from AMS (Tested) |
4 | TYPE_SPI_ABS_MAXXX | Using MAXXX series absolute encoders from Monolith Power Systems (Tested with MA732, MA702) |
5 | TYPE_SPI_ABS_MUXXX | Using MU series absolute encoders from iC-Haus (Tested with MU150, MU200) |
6 | TYPE_SPI_ABS_CUI | Using AMT 203 absolute encoder from CUI (Tested) |
7 | TYPE_SPI_ABS_AEAT | Using AEAT absolute encoders from Broadcomm (To be tested) |
8 | TYPE_SPI_ABS_RLS | Using RLS absolute encoders from Renishaw (To be tested) |
Parameters
Datatype | Variable | Description |
---|
uint8_t | encoder_type | type of encoder used |
int32_t | resolution_param | CPR value of the encoder in case of an incremental encoder or resolution value in 2^bits in case of absolute encoder (this parameter is ignored in the case of using onboard absolute encoder) resolution_param is set to 4096 by default. |
bool | use_index | flag to set whether to use the index pin for incremental encoder or not. Valid only when an incremental encoder is used. use_index is set to true by default. |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
ret_status_t Driver::configureOutputEncoder(uint8_t encoder_type, int32_t resolution_param=4096, bool use_index=true)
Description
Configure Output side encoder. Set it to onboard absolute, external incremental or external absolute. Output side and motor side encoders can't be set to same.
encoder_type value | Encoder Type | Description |
---|
0 | TYPE_NONE | Using no encoder |
1 | TYPE_ONBOARD_ENCODER | Using onboard absolute encoder (Tested) |
2 | TYPE_INCREMENTAL | Using External incremental Encoder (Tested) |
3 | TYPE_SPI_ABS_AMS | Using AS5047P absolute encoder from AMS (Tested) |
4 | TYPE_SPI_ABS_MAXXX | Using MAXXX series absolute encoders from Monolith Power Systems (Tested with MA732, MA702) |
5 | TYPE_SPI_ABS_MUXXX | Using MU series absolute encoders from iC-Haus (Tested with MU150, MU200) |
6 | TYPE_SPI_ABS_CUI | Using AMT 203 absolute encoder from CUI (Tested) |
7 | TYPE_SPI_ABS_AEAT | Using AEAT absolute encoders from Broadcomm (To be tested) |
8 | TYPE_SPI_ABS_RLS | Using RLS absolute encoders from Renishaw (To be tested) |
Parameters
Datatype | Variable | Description |
---|
uint8_t | encoder_type | type of encoder used |
int32_t | resolution_param | CPR value of the encoder in case of an incremental encoder or resolution value in 2^bits in case of absolute encoder (this parameter is ignored in the case of using onboard absolute encoder) resolution_param is set to 4096 by default. |
bool | use_index | flag to set whether to use the index pin for incremental encoder or not. Valid only when an incremental encoder is used. use_index is set to true by default. |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.disableBrakeResistor()
ret_status_t Driver::disableBrakeResistor()
Description
Disable brake resistor and configure it.
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.disableMotorThermalLimit()
ret_status_t Driver::disableMotorThermalLimit()
Description
Disable Motor based Thermal limit.
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.disableOutputEncoder()
ret_status_t Driver::disableOutputEncoder()
Description
Disable Output Encoder.
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.emergencyStop()
ret_status_t Driver::emergencyStop()
Description
Function to issue an emergency stop to the device which halts the driver and sets the error flag; Since the error flag is set the driver doesn't respond to any other commands, until the driver is rebooted.
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.enableBrakeResistor()
ret_status_t Driver::enableBrakeResistor(float brake_resistance_value)
Description
Enable brake resistor and configure it.
Parameters
Datatype | Variable | Description |
---|
float | brake_resistance_value | brake resistance value |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.enableMotorThermalLimit()
ret_status_t Driver::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 driver will stop. |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.enterDFUMode()
ret_status_t Driver::enterDFUMode()
Description
Enter in DFU Mode.
Returns
Datatype | Description |
---|
ret_status_t | ret_status_t |
Driver.eraseConfigurations()
ret_status_t Driver::eraseConfigurations()
Description
Erase Configuration of the driver.
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.flash()
ret_status_t Driver::flash(std::string firmware_path, bool is_in_dfu_mode=false)
Description
Function to flash a firmware onto the device.
Parameters
Datatype | Variable | Description |
---|
std::string | firmware_path | path to firmware file |
bool | is_in_dfu_mode | flag to set if the driver is already in dfu mode |
Returns
Datatype | Description |
---|
ret_status_t | ret_status_t |
Driver.getBrakeCurrent()
ret_status_t Driver::getBrakeCurrent(float *brake_current)
Description
Function to get the brake current of the driver.
Parameters
Datatype | Variable | Description |
---|
float * | brake_current | variable to store the brake current |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.getBrakeResistorState()
ret_status_t Driver::getBrakeResistorState(bool *enable, float *brake_resistance_value, bool *brake_resistor_armed, bool *brake_resistor_saturated)
Description
Get current state of brake resistor.
Parameters
Datatype | Variable | Description |
---|
bool * | enable | Pointer to variable to which the enable status of the brake resistor is to be saved (true means that the brake resistor is enabled). |
float * | brake_resistance_value | Pointer to the variable to which the value of brake resistance is to be saved. |
bool * | brake_resistor_armed | Pointer to the variable to which the value of the arm status of the brake resistor is to be saved (true means that the brake resistor is armed). |
bool * | brake_resistor_saturated | Pointer to the variable to which the value of saturation status of the brake resistor is to be saved (true means that the brake resistor is saturated). |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.getBusCurrent()
ret_status_t Driver::getBusCurrent(float *ibus)
Description
Get the Bus Current of the driver.
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 |
Driver.getBusVoltage()
ret_status_t Driver::getBusVoltage(float *vbus_voltage)
Description
Get the Bus Voltage of the driver.
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 |
Driver.getCANCommunicationStatus()
ret_status_t Driver::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 |
Driver.getControllerMode()
ret_status_t Driver::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 |
Driver.getControllerState()
ret_status_t Driver::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 |
Driver.getCurrentControllerBandwidth()
ret_status_t Driver::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 |
Driver.getCurrentControllerGains()
ret_status_t Driver::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 |
Driver.getCurrentFilter()
ret_status_t Driver::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 |
Driver.getDCBusTripLevels()
ret_status_t Driver::getDCBusTripLevels(float *undervoltage_level, float *overvoltage_level)
Description
Get the driver'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 |
Driver.getDCCalibPhaseCurrents()
ret_status_t Driver::getDCCalibPhaseCurrents(float *dc_calib_phA, float *dc_calib_phB, float *dc_calib_phC)
Description
Get motor phase dc calib currents in Ampere.
Parameters
Datatype | Variable | Description |
---|
float * | dc_calib_phA | Pointer to the variable to which the current in phase A value is to be saved. |
float * | dc_calib_phB | Pointer to the variable to which the current in phase B value is to be saved. |
float * | dc_calib_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 |
Driver.getDebugErrorCode()
ret_status_t Driver::getDebugErrorCode(uint64_t *system_error, uint64_t *axis_error, uint64_t *motor_error, uint64_t *encoder_error, uint64_t *controller_error, uint64_t *driver_error)
Description
Get the debug error codes from the driver.
Parameters
Datatype | Variable | Description |
---|
uint64_t * | system_error | Pointer to the variable to which the value of system error code is saved |
uint64_t * | axis_error | Pointer to the variable to which the value of axis error code is saved |
uint64_t * | motor_error | Pointer to the variable to which the value of motor error code is saved |
uint64_t * | encoder_error | Pointer to the variable to which the value of encoder error code is saved |
uint64_t * | controller_error | Pointer to the variable to which the value of controller error code is saved |
uint64_t * | driver_error | Pointer to the variable to which the value of driver error code is saved |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.getDriverFault()
ret_status_t Driver::getDriverFault(uint32_t *driver_error)
Description
Get the Driver error status from the driver.
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 |
Driver.getDriverTemperature()
ret_status_t Driver::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 |
Driver.getEncoderDataFilter()
ret_status_t Driver::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 |
Driver.getErrorCode()
ret_status_t Driver::getErrorCode(uint32_t *error_code)
Description
Get the error code from the driver.
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 |
Driver.getFirmwareCommit()
ret_status_t Driver::getFirmwareCommit(std::string *commit)
Description
Get Driver's Firmware commit.
Parameters
Datatype | Variable | Description |
---|
std::string * | commit | Pointer to the variable where the commit value is to be saved. |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.getFirmwareVersion()
ret_status_t Driver::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 |
Driver.getGearBoxParameters()
ret_status_t Driver::getGearBoxParameters(float *gear_ratio)
Description
Get Gear ratio of the Gearbox.
Parameters
Datatype | Variable | Description |
---|
float * | gear_ratio | Pointer to the variable to which the gear ratio value is to be saved. |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.getHardwareVersion()
ret_status_t Driver::getHardwareVersion(uint8_t *tag, uint8_t *major, uint8_t *minor, uint8_t *variant)
Description
Get Driver'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 variant value is to be saved. |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.getIdqCurrents()
ret_status_t Driver::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 |
Driver.getMotorAcceleration()
ret_status_t Driver::getMotorAcceleration(float *motor_acceleration)
Description
Get current acceleration of the motor rotor in rotations per second^2.
Parameters
Datatype | Variable | Description |
---|
float * | motor_acceleration | Pointer to the variable to which the current acceleration value is to be saved. |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.getMotorCalibrationParameters()
ret_status_t Driver::getMotorCalibrationParameters(float *motor_calib_voltage, float *motor_calib_current)
Description
Get current Motor Calibration Parameters.
Parameters
Datatype | Variable | Description |
---|
float * | motor_calib_voltage | Pointer to the variable to which the current calibration voltage to calibrate motor is to be saved. |
float * | motor_calib_current | Pointer to the variable to which the current calibration current to calibrate motor is to be saved. |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.getMotorEncoderBandwidth()
ret_status_t Driver::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 |
Driver.getMotorEncoderConfiguration()
ret_status_t Driver::getMotorEncoderConfiguration(uint8_t *encoder_type, int32_t *resolution_param, bool *use_index)
Description
Get motor encoder configuration.
Parameters
Datatype | Variable | Description |
---|
uint8_t * | encoder_type | Pointer to the variable to which the current encoder type value is to be saved. If the value is 0, it means the output encoder is not enabled. |
int32_t * | resolution_param | Pointer to the variable to which the value of encoder CPR (in case of incremental encoder) or value of encoder resolution bits (in case of absolute encoder) is to be saved. |
bool * | use_index | Pointer to the variable to which the status of using index pin for incremental encoder is to be saved. |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.getMotorEncoderRawData()
ret_status_t Driver::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 |
Driver.getMotorEncoderState()
ret_status_t Driver::getMotorEncoderState(bool *index_found, bool *is_ready)
Description
Get the state of encoder on the motor side.
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. This value is only valid if the motor side encoder is incremental. |
bool * | is_ready | Pointer to the variable to which the is_ready state of the motor encoder is to be saved (true means that the motor side encoder is ready) |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.getMotorParameters()
ret_status_t Driver::getMotorParameters(uint8_t *pole_pairs, uint16_t *kV_rating, float *current_limit)
Description
Get current motor parameters.
Parameters
Datatype | Variable | Description |
---|
uint8_t * | pole_pairs | Pointer to the variable to which the pole-pair value of the motor is to be saved. |
uint16_t * | kV_rating | Pointer to the variable to which the kV rating value of the motor is to be saved. |
float * | current_limit | Pointer to the variable to which the current limit value for the motor is to be saved. |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.getMotorPhaseCurrents()
ret_status_t Driver::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 |
Driver.getMotorPhaseParameters()
ret_status_t Driver::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 |
Driver.getMotorPosition()
ret_status_t Driver::getMotorPosition(float *motor_position)
Description
Get current angle of the motor rotor in number of rotations.
Parameters
Datatype | Variable | Description |
---|
float * | motor_position | Pointer to the variable to which the current rotation value is to be saved. |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.getMotorState()
ret_status_t Driver::getMotorState(bool *is_calibrated, bool *is_armed)
Description
Get the motor state of the driver.
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 |
Driver.getMotorTemperature()
ret_status_t Driver::getMotorTemperature(float *motor_temperature)
Description
Get motor temperature in degree Celsius. Valid only if a motor thermistor is connected to the driver.
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 |
Driver.getMotorThermistorConfiguration()
ret_status_t Driver::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 |
Driver.getMotorTorque()
ret_status_t Driver::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 |
Driver.getMotorVelocity()
ret_status_t Driver::getMotorVelocity(float *motor_velocity)
Description
Get current velocity of the motor rotor in rotations per second[rps].
Parameters
Datatype | Variable | Description |
---|
float * | motor_velocity | Pointer to the variable to which the current velocity value is to be saved. |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.getNodeId()
ret_status_t Driver::getNodeId(uint32_t *node_id)
Description
Get current CAN Node ID of the driver.
Parameters
Datatype | Variable | Description |
---|
uint32_t * | node_id | Pointer to the variable to which the current CAN Node ID of the driver is to be saved. |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.getOutputAcceleration()
ret_status_t Driver::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 |
Driver.getOutputEncoderConfiguration()
ret_status_t Driver::getOutputEncoderConfiguration(uint8_t *encoder_type, int32_t *resolution_param, bool *use_index)
Description
Get output encoder configuration.
Parameters
Datatype | Variable | Description |
---|
uint8_t * | encoder_type | Pointer to the variable to which the current encoder type value is to be saved. If the value is 0, it means the output encoder is not enabled. |
int32_t * | resolution_param | Pointer to the variable to which the value of encoder CPR (in case of incremental encoder) or value of encoder resolution bits (in case of absolute encoder) is to be saved. |
bool * | use_index | Pointer to the variable to which the status of using index pin for incremental encoder is to be saved. |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.getOutputEncoderRawData()
ret_status_t Driver::getOutputEncoderRawData(int32_t *encoder_data)
Description
Get raw encoder data from the encoder on the Output 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 |
Driver.getOutputEncoderState()
ret_status_t Driver::getOutputEncoderState(bool *index_found, bool *is_ready)
Description
Get the state of encoder on the output side.
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. This value is only valid if the motor side encoder is incremental. |
bool * | is_ready | Pointer to the variable to which the is_ready state of the motor encoder is to be saved (true means that the output side encoder is ready) |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.getOutputPosition()
ret_status_t Driver::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 |
Driver.getOutputTorque()
ret_status_t Driver::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 |
Driver.getOutputVelocity()
ret_status_t Driver::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 |
Driver.getPositionControllerGain()
ret_status_t Driver::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 |
Driver.getRegenCurrentTripLevel()
ret_status_t Driver::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 |
Driver.getStartupConfigs()
ret_status_t Driver::getStartupConfigs(bool *index_search, bool *encoder_matching, bool *closed_loop)
Description
Get startup configuration of the driver.
Parameters
Datatype | Variable | Description |
---|
bool * | index_search | Pointer to the variable to which the enable/disable status of index searching on startup is to be saved. |
bool * | encoder_matching | Pointer to the variable to which the enable/disable status of output encoder matching sequence on startup is to be saved. |
bool * | closed_loop | Pointer to the variable to which the enable/disable status of setting the driver to closed loop on startup value is to be saved. |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.getTrajectoryDoneStatus()
ret_status_t Driver::getTrajectoryDoneStatus(bool *is_done)
Description
Get the trajectory done status.
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 |
Driver.getVelocityControllerGains()
ret_status_t Driver::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 |
Driver.getZeroPosition()
ret_status_t Driver::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 driver is to be saved. |
Returns
Datatype | Description |
---|
ret_status_t | Return Status |
Driver.isConnected()
bool Driver::isConnected()
Description
Check if the device is still connected or not.
Returns
Datatype | Description |
---|
bool | true |
Driver.rebootDriver()
ret_status_t Driver::rebootDriver()
Description