Classes | Public Member Functions | Private Member Functions | Private Attributes
puma_motor_driver::Driver Class Reference

#include <driver.h>

List of all members.

Classes

struct  StatusField

Public Member Functions

void clearStatusCache ()
void commandDutyCycle (float cmd)
void commandSpeed (double cmd)
void configureParams ()
std::string deviceName ()
uint8_t deviceNumber ()
 Driver (Gateway &gateway, uint8_t device_number, std::string device_name)
uint16_t encoderCounts ()
double getD ()
double getI ()
double getP ()
uint8_t * getRawD ()
uint8_t * getRawI ()
uint8_t * getRawP ()
bool isConfigured ()
float lastAnalogInput ()
float lastBusVoltage ()
float lastCurrent ()
float lastDutyCycle ()
uint8_t lastFault ()
uint8_t lastMode ()
float lastOutVoltage ()
double lastPosition ()
uint8_t lastPower ()
double lastSetpoint ()
double lastSpeed ()
float lastTemperature ()
Driver operator= (const Driver &rhs)
uint8_t posEncoderRef ()
void processMessage (const Message &received_msg)
void requestFeedbackCurrent ()
void requestFeedbackDutyCycle ()
void requestFeedbackMessages ()
void requestFeedbackPosition ()
void requestFeedbackPowerState ()
void requestFeedbackSetpoint ()
void requestFeedbackSpeed ()
void requestStatusMessages ()
void resetConfiguration ()
void setEncoderCPR (uint16_t encoder_cpr)
void setGains (double p, double i, double d)
void setGearRatio (float gear_ratio)
void setMode (uint8_t mode)
void setMode (uint8_t mode, double p, double i, double d)
uint8_t spdEncoderRef ()
float statusCurrentGet ()
float statusDutyCycleGet ()
double statusPositionGet ()
double statusSpeedGet ()
void updateGains ()
void verifyParams ()

Private Member Functions

void sendFixed16x16 (uint32_t id, double value)
void sendFixed8x8 (uint32_t id, float value)
void sendUint16 (uint32_t id, uint16_t value)
void sendUint8 (uint32_t id, uint8_t value)
StatusFieldstatusFieldForMessage (const Message &msg)
bool verifyRaw16x16 (uint8_t *received, double expected)
bool verifyRaw8x8 (uint8_t *received, float expected)

Private Attributes

bool configured_
uint8_t control_mode_
std::string device_name_
uint8_t device_number_
uint16_t encoder_cpr_
double gain_d_
double gain_i_
double gain_p_
Gatewaygateway_
float gear_ratio_
uint8_t state_
StatusField status_fields_ [12]

Detailed Description

Definition at line 39 of file driver.h.


Constructor & Destructor Documentation

puma_motor_driver::Driver::Driver ( Gateway gateway,
uint8_t  device_number,
std::string  device_name 
)

Definition at line 39 of file driver.cpp.


Member Function Documentation

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

Definition at line 451 of file driver.cpp.

Command the supplied value in open-loop voltage control.

Parameters:
[in]cmdValue to command, ranging from -1.0 to 1.0, where zero is neutral.

Definition at line 144 of file driver.cpp.

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

Parameters:
[in]cmdValue to command in rad/s.

Definition at line 149 of file driver.cpp.

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

Definition at line 308 of file driver.cpp.

std::string puma_motor_driver::Driver::deviceName ( ) [inline]

Definition at line 342 of file driver.h.

Definition at line 344 of file driver.h.

Process the last received encoder counts response

Returns:
value of the encoder counts.

Definition at line 649 of file driver.cpp.

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

Returns:
value of the D gain response.

Definition at line 691 of file driver.cpp.

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

Returns:
value of the I gain response.

Definition at line 673 of file driver.cpp.

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

Returns:
value of the P gain response.

Definition at line 655 of file driver.cpp.

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

Returns:
pointer to raw 4 bytes of the I gain response.

Definition at line 745 of file driver.cpp.

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

Returns:
pointer to raw 4 bytes of the I gain response.

Definition at line 727 of file driver.cpp.

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

Returns:
pointer to raw 4 bytes of the P gain response.

Definition at line 709 of file driver.cpp.

Gets if the driver has been configured.

Returns:
bool if driver is configured.

Definition at line 393 of file driver.cpp.

Process the last received analog_input response.

Returns:
value of the instantaneous analog_input.

Definition at line 587 of file driver.cpp.

Process the last received bus voltage response.

Returns:
value of the instantaneous bus voltage.

Definition at line 533 of file driver.cpp.

Process the last received current response.

Returns:
value of the instantaneous current.

Definition at line 539 of file driver.cpp.

Process the last received duty cycle response.

Returns:
value of the instantaneous duty cycle.

Definition at line 527 of file driver.cpp.

Process the last received fault response.

Returns:
state of fault status.

Definition at line 557 of file driver.cpp.

Process the last received mode response.

Returns:
current mode of motor driver.

Definition at line 569 of file driver.cpp.

Process the last received out voltage response.

Returns:
value of the instantaneous out voltage.

Definition at line 575 of file driver.cpp.

Process the last received travel response.

Returns:
value of the instantaneous angular position.

Definition at line 545 of file driver.cpp.

Process the last received power response.

Returns:
state of power status.

Definition at line 563 of file driver.cpp.

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

Returns:
value of the set-point response.

Definition at line 593 of file driver.cpp.

Process the last received speed response.

Returns:
value of the instantaneous angular speed.

Definition at line 551 of file driver.cpp.

Process the last received temperature response.

Returns:
value of the instantaneous temperature.

Definition at line 581 of file driver.cpp.

Driver puma_motor_driver::Driver::operator= ( const Driver rhs) [inline]

Assignment operator, necessary on GCC 4.8 to copy instances into a vector.

Definition at line 337 of file driver.h.

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

Returns:
value of the reference response.

Definition at line 637 of file driver.cpp.

void puma_motor_driver::Driver::processMessage ( const Message received_msg)

Definition at line 46 of file driver.cpp.

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

Definition at line 476 of file driver.cpp.

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

Definition at line 471 of file driver.cpp.

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.

Definition at line 463 of file driver.cpp.

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

Definition at line 481 of file driver.cpp.

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

Definition at line 491 of file driver.cpp.

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

Definition at line 496 of file driver.cpp.

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

Definition at line 486 of file driver.cpp.

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.

Definition at line 458 of file driver.cpp.

Definition at line 515 of file driver.cpp.

void puma_motor_driver::Driver::sendFixed16x16 ( uint32_t  id,
double  value 
) [private]

Definition at line 92 of file driver.cpp.

void puma_motor_driver::Driver::sendFixed8x8 ( uint32_t  id,
float  value 
) [private]

Definition at line 82 of file driver.cpp.

void puma_motor_driver::Driver::sendUint16 ( uint32_t  id,
uint16_t  value 
) [private]

Definition at line 73 of file driver.cpp.

void puma_motor_driver::Driver::sendUint8 ( uint32_t  id,
uint8_t  value 
) [private]

Helpers to generate data for CAN messages.

Definition at line 64 of file driver.cpp.

void puma_motor_driver::Driver::setEncoderCPR ( uint16_t  encoder_cpr)

Set the encoders resolution in counts per rev.

Parameters:
[in]encoder_cprValue to set.

Definition at line 134 of file driver.cpp.

void puma_motor_driver::Driver::setGains ( double  p,
double  i,
double  d 
)

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

Parameters:
[in]pValue to set.
[in]iValue to set.
[in]dValue to set.

Definition at line 398 of file driver.cpp.

void puma_motor_driver::Driver::setGearRatio ( float  gear_ratio)

Set the gear ratio of the motors.

Parameters:
[in]gear_ratioValue to set.

Definition at line 139 of file driver.cpp.

void puma_motor_driver::Driver::setMode ( uint8_t  mode)

Set the control mode of the motor drivers.

Parameters:
[in]modeValue to set.

Definition at line 410 of file driver.cpp.

void puma_motor_driver::Driver::setMode ( uint8_t  mode,
double  p,
double  i,
double  d 
)

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

Parameters:
[in]modeValue to set.
[in]pValue to set.
[in]iValue to set.
[in]dValue to set.

Definition at line 427 of file driver.cpp.

Process the last received speed encoder reference response

Returns:
value of the reference response.

Definition at line 643 of file driver.cpp.

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

Returns:
value of the set-point response.

Definition at line 626 of file driver.cpp.

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

Returns:
value of the set-point response.

Definition at line 620 of file driver.cpp.

Definition at line 762 of file driver.cpp.

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

Returns:
value of the set-point response.

Definition at line 631 of file driver.cpp.

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

Returns:
value of the set-point response.

Definition at line 614 of file driver.cpp.

Reset the configured flag to restart the verification process.

Definition at line 521 of file driver.cpp.

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

Definition at line 155 of file driver.cpp.

bool puma_motor_driver::Driver::verifyRaw16x16 ( uint8_t *  received,
double  expected 
) [private]

Comparing the raw bytes of the 16x16 fixed-point numbers to avoid comparing the floating point values.

Returns:
boolean if received is equal to expected.

Definition at line 102 of file driver.cpp.

bool puma_motor_driver::Driver::verifyRaw8x8 ( uint8_t *  received,
float  expected 
) [private]

Comparing the raw bytes of the 8x8 fixed-point numbers to avoid comparing the floating point values.

Returns:
boolean if received is equal to expected.

Definition at line 118 of file driver.cpp.


Member Data Documentation

Definition at line 369 of file driver.h.

Definition at line 372 of file driver.h.

Definition at line 367 of file driver.h.

Definition at line 366 of file driver.h.

Definition at line 376 of file driver.h.

Definition at line 375 of file driver.h.

Definition at line 374 of file driver.h.

Definition at line 373 of file driver.h.

Definition at line 365 of file driver.h.

Definition at line 377 of file driver.h.

Definition at line 370 of file driver.h.

Definition at line 403 of file driver.h.


The documentation for this class was generated from the following files:


puma_motor_driver
Author(s):
autogenerated on Sat Jun 8 2019 18:55:15