Class Driver

Nested Relationships

Nested Types

Class Documentation

class Driver

Public Functions

Driver(const std::shared_ptr<puma_motor_driver::Gateway> gateway, const uint8_t &device_number, const std::string &device_name)
void processMessage(const Message &received_msg)
double radPerSecToRpm() const
void requestStatusMessages()

Sends messages to the motor controller requesting all missing elements to populate the cache of status data. Returns true if any messages were sent, false if the cache is already complete.

void requestFeedbackMessages()

Sends messages to the motor controller requesting all missing elements to populate the cache of feedback data. Returns true if any messages were sent, false if the cache is already complete.

void requestFeedbackDutyCycle()

Sends a message to the motor controller requesting the instantaneous duty cycle to populate the cache of feedback data.

void requestFeedbackCurrent()

Sends a message to the motor controller requesting the instantaneous current consumption to populate the cache of feedback data.

void requestFeedbackPosition()

Sends a message to the motor controller requesting the instantaneous angular distance to populate the cache of feedback data.

void requestFeedbackSpeed()

Sends a message to the motor controller requesting the instantaneous angular speed to populate the cache of feedback data.

void requestFeedbackPowerState()

Sends a message to the motor controller requesting the state of the power flag.

void requestFeedbackSetpoint()

Sends a message to the motor controller requesting the instantaneous set point of the current control mode to populate the cache of feedback data.

void clearMsgCache()

Clear the received flags from the status cache, in preparation for the next request batch to go out.

void commandDutyCycle(const float cmd)

Command the supplied value in open-loop voltage control.

Parameters:

cmd[in] Value to command, ranging from -1.0 to 1.0, where zero is neutral.

void commandSpeed(const double cmd)

Command the desired speed set-point in close-loop speed control.

Parameters:

cmd[in] Value to command in rad/s.

void setEncoderCPR(const uint16_t encoder_cpr)

Set the encoders resolution in counts per rev.

Parameters:

encoder_cpr[in] Value to set.

void setGearRatio(const float gear_ratio)

Set the gear ratio of the motors.

Parameters:

gear_ratio[in] Value to set.

void setMode(const uint8_t mode)

Set the control mode of the motor drivers.

Parameters:

mode[in] Value to set.

void setMode(const uint8_t mode, const double p, const double i, const double d)

Set the control mode of the motor drivers with PID gains for close loop control.

Parameters:
  • mode[in] Value to set.

  • p[in] Value to set.

  • i[in] Value to set.

  • d[in] Value to set.

void setGains(const double p, const double i, const double d)

Set the control mode’s PID gains for close loop control.

Parameters:
  • p[in] Value to set.

  • i[in] Value to set.

  • d[in] Value to set.

bool receivedFault()

Check fault response field was received.

Returns:

received flag

bool receivedPower()

Check power field was received.

Returns:

received flag

bool receivedMode()

Check mode field was received.

Returns:

received flag

bool receivedDutyCycle()

Check duty cycle field was received.

Returns:

received flag

bool receivedBusVoltage()

Check bus voltage field was received.

Returns:

received flag

bool receivedCurrent()

Check current field was received.

Returns:

received flag

bool receivedOutVoltage()

Check out voltage field was received.

Returns:

received flag

bool receivedTemperature()

Check teperature field was received.

Returns:

received flag

bool receivedAnalogInput()

Check analog input field was received.

Returns:

received flag

bool receivedPosition()

Check position field was received.

Returns:

received flag

bool receivedSpeed()

Check speed field was received.

Returns:

received flag

bool receivedSetpoint()

Check setpoint field was received.

Returns:

received flag

bool receivedDutyCycleSetpoint()

Check the set-point response in voltage open-loop control was received.

Returns:

received flag

bool receivedSpeedSetpoint()

Check the set-point response in speed closed-loop control was received.

Returns:

received flag

bool receivedCurrentSetpoint()

Check the set-point response in currrent closed-loop control was received.

Returns:

received flag

bool receivedPositionSetpoint()

Check the set-point response in position closed-loop control was received.

Returns:

received flag

uint8_t lastFault()

Process the last received fault response.

Returns:

state of fault status.

uint8_t lastPower()

Process the last received power response.

Returns:

state of power status.

uint8_t lastMode()

Process the last received mode response.

Returns:

current mode of motor driver.

float lastDutyCycle()

Process the last received duty cycle response.

Returns:

value of the instantaneous duty cycle.

float lastBusVoltage()

Process the last received bus voltage response.

Returns:

value of the instantaneous bus voltage.

float lastCurrent()

Process the last received current response.

Returns:

value of the instantaneous current.

float lastOutVoltage()

Process the last received out voltage response.

Returns:

value of the instantaneous out voltage.

float lastTemperature()

Process the last received temperature response.

Returns:

value of the instantaneous temperature.

float lastAnalogInput()

Process the last received analog_input response.

Returns:

value of the instantaneous analog_input.

double lastPosition()

Process the last received travel response.

Returns:

value of the instantaneous angular position.

double lastSpeed()

Process the last received speed response.

Returns:

value of the instantaneous angular speed.

double lastSetpoint()

Process the last received set-point response for the current control mode.

Returns:

value of the set-point response.

void configureParams()

The requesting part of the state machine that sends a message to the motor controller requesting a parameter be set.

void verifyParams()

The verifying part of the state machine that checks the response of the motor controller to ensure the value was set.

bool isConfigured() const

Gets if the driver has been configured.

Returns:

bool if driver is configured.

void resetConfiguration()
void updateGains()

Reset the configured flag to restart the verification process.

uint8_t posEncoderRef()

Updates the PID gains. Process the last received position encoder reference response

Returns:

value of the reference response.

uint8_t spdEncoderRef()

Process the last received speed encoder reference response

Returns:

value of the reference response.

uint16_t encoderCounts()

Process the last received encoder counts response

Returns:

value of the encoder counts.

double getP()

Process the last received P gain for the current control mode.

Returns:

value of the P gain response.

double getI()

Process the last received I gain for the current control mode.

Returns:

value of the I gain response.

double getD()

Process the last received D gain for the current control mode.

Returns:

value of the D gain response.

uint8_t *getRawP()

Process the last received P gain for the current control mode.

Returns:

pointer to raw 4 bytes of the P gain response.

uint8_t *getRawI()

Process the last received I gain for the current control mode.

Returns:

pointer to raw 4 bytes of the I gain response.

uint8_t *getRawD()

Process the last received I gain for the current control mode.

Returns:

pointer to raw 4 bytes of the I gain response.

float statusDutyCycleGet()

Process the last received set-point response in voltage open-loop control.

Returns:

value of the set-point response.

double statusSpeedGet()

Process the last received set-point response in speed closed-loop control.

Returns:

value of the set-point response.

float statusCurrentGet()

Process the last received set-point response in currrent closed-loop control.

Returns:

value of the set-point response.

double statusPositionGet()

Process the last received set-point response in position closed-loop control.

Returns:

value of the set-point response.

inline std::string deviceName() const
inline uint8_t deviceNumber() const
struct Field

Public Functions

inline float interpretFixed8x8()
inline double interpretFixed16x16()

Public Members

uint8_t data[4]
bool received