Public Member Functions | Private Attributes | List of all members
qb_move_transmission_interface::qbMoveTransmission Class Reference

The qbrobotics qbmove Transmission interface implements the specific transmission_interface::Transmission to convert from qbmove motors state to its equivalent joint state representation, and vice versa. More...

#include <qb_move_transmission_interface.h>

Inheritance diagram for qb_move_transmission_interface::qbMoveTransmission:
Inheritance graph
[legend]

Public Member Functions

void actuatorToJointEffort (const transmission_interface::ActuatorData &actuator, transmission_interface::JointData &joint)
 Transform effort variables from actuator to joint space. More...
 
void actuatorToJointPosition (const transmission_interface::ActuatorData &actuator, transmission_interface::JointData &joint)
 Transform position variables from actuator to joint space. More...
 
void actuatorToJointVelocity (const transmission_interface::ActuatorData &actuator, transmission_interface::JointData &joint)
 Transform velocity variables from actuator to joint space. More...
 
const bool getCommandWithPoistionAndPreset () const
 
const double getEffortFactor () const
 
const std::vector< double > getPositionFactor () const
 
const double getPresetFactor () const
 
const double getPresetPercentToRadians () const
 
const double getVelocityFactor () const
 
void jointToActuatorEffort (const transmission_interface::JointData &joint, transmission_interface::ActuatorData &actuator)
 Transform effort variables from joint to actuator space. More...
 
void jointToActuatorPosition (const transmission_interface::JointData &joint, transmission_interface::ActuatorData &actuator)
 Transform position variables from joint to actuator space. More...
 
void jointToActuatorVelocity (const transmission_interface::JointData &joint, transmission_interface::ActuatorData &actuator)
 Transform velocity variables from joint to actuator space. More...
 
std::size_t numActuators () const
 
std::size_t numJoints () const
 
 qbMoveTransmission ()
 Build the qbmove transmission with default velocity and effort scale factors (respectively 0.2 and 0.001). More...
 
 qbMoveTransmission (const bool &command_with_position_and_preset, const std::vector< double > &position_factor, const double &preset_factor, const double &velocity_factor, const double &effort_factor)
 Build the qbmove transmission with the given scale factors. More...
 
void setCommandWithPoistionAndPreset (const bool &command_with_position_and_preset)
 
void setPositionFactor (const std::vector< int > &encoder_resolutions)
 
void setPresetFactor (const int &stiffness_preset_limit)
 
- Public Member Functions inherited from transmission_interface::Transmission
virtual ~Transmission ()
 

Private Attributes

bool command_with_position_and_preset_
 
double effort_factor_
 
std::vector< double > position_factor_
 
double preset_factor_
 
double velocity_factor_
 

Detailed Description

The qbrobotics qbmove Transmission interface implements the specific transmission_interface::Transmission to convert from qbmove motors state to its equivalent joint state representation, and vice versa.

See also
qb_device_transmission_interface::qbDeviceTransmissionResources

Definition at line 40 of file qb_move_transmission_interface.h.

Constructor & Destructor Documentation

qb_move_transmission_interface::qbMoveTransmission::qbMoveTransmission ( )
inline

Build the qbmove transmission with default velocity and effort scale factors (respectively 0.2 and 0.001).

The position scale factors (one value per each motor) are based on the "encoder resolutions", following the formula $f_{pos} = \frac{\pi}{2^(2-encoder\_resolution)}$. The default encoder resolutions are equal 1, but they can be modified during the execution with the proper method. The preset scale factor is based on the "stiffness preset limit" (expressed in ticks), which is the maximum stiffness value for the given qbrobotics device, and follows the formula $f_{pres} = \frac{1}{stiffness\_preset\_limit}$. The default maximum stiffness is set to 3000 ticks, but it can be modified during the execution with the proper method. Finally, the control mode can be set to work either with motor positions or with shaft position and stiffness preset; the default behavior is to use the "position and preset" controller, but it can be modified even during the execution with the proper method.

Definition at line 53 of file qb_move_transmission_interface.h.

qb_move_transmission_interface::qbMoveTransmission::qbMoveTransmission ( const bool &  command_with_position_and_preset,
const std::vector< double > &  position_factor,
const double &  preset_factor,
const double &  velocity_factor,
const double &  effort_factor 
)
inline

Build the qbmove transmission with the given scale factors.

Parameters
command_with_position_and_presetIf true the controller exploits shaft position and stiffness preset.
position_factorMotor position ticks to joint position radians scale factor vector.
preset_factorPreset value ticks to preset percent value [0, 1] scale factor.
velocity_factorExponential filter smoothing factor.
effort_factorMotor current mA to joint effort A scale factor.

Definition at line 65 of file qb_move_transmission_interface.h.

Member Function Documentation

void qb_move_transmission_interface::qbMoveTransmission::actuatorToJointEffort ( const transmission_interface::ActuatorData actuator,
transmission_interface::JointData joint 
)
inlinevirtual

Transform effort variables from actuator to joint space.

Parameters
actuatorActuator-space variables.
[out]jointJoint-space variables.
Precondition
Actuator and joint effort vectors must have size according respectively to numActuators and numJoints and must point to valid data, at least for the used fields, i.e. it is not required that all other data vectors contain valid data; they can even remain empty.

Implements transmission_interface::Transmission.

Definition at line 81 of file qb_move_transmission_interface.h.

void qb_move_transmission_interface::qbMoveTransmission::actuatorToJointPosition ( const transmission_interface::ActuatorData actuator,
transmission_interface::JointData joint 
)
inlinevirtual

Transform position variables from actuator to joint space.

Parameters
actuatorActuator-space variables.
[out]jointJoint-space variables.
Precondition
Actuator and joint position vectors must have size according respectively to numActuators and numJoints and must point to valid data, at least for the used fields, i.e. it is not required that all other data vectors contain valid data; they can even remain empty.

Implements transmission_interface::Transmission.

Definition at line 120 of file qb_move_transmission_interface.h.

void qb_move_transmission_interface::qbMoveTransmission::actuatorToJointVelocity ( const transmission_interface::ActuatorData actuator,
transmission_interface::JointData joint 
)
inlinevirtual

Transform velocity variables from actuator to joint space.

Parameters
actuatorActuator-space variables.
[out]jointJoint-space variables.
Precondition
Actuator and joint velocity vectors must have size according respectively to numActuators and numJoints and must point to valid data, at least for the used fields, i.e. it is not required that all other data vectors contain valid data; they can even remain empty.

Implements transmission_interface::Transmission.

Definition at line 99 of file qb_move_transmission_interface.h.

const bool qb_move_transmission_interface::qbMoveTransmission::getCommandWithPoistionAndPreset ( ) const
inline
Returns
true if the controller exploits shaft position and stiffness preset.

Definition at line 133 of file qb_move_transmission_interface.h.

const double qb_move_transmission_interface::qbMoveTransmission::getEffortFactor ( ) const
inline
Returns
The current effort scale factor.

Definition at line 158 of file qb_move_transmission_interface.h.

const std::vector<double> qb_move_transmission_interface::qbMoveTransmission::getPositionFactor ( ) const
inline
Returns
The current position scale factor.

Definition at line 138 of file qb_move_transmission_interface.h.

const double qb_move_transmission_interface::qbMoveTransmission::getPresetFactor ( ) const
inline
Returns
The current preset scale factor.

Definition at line 143 of file qb_move_transmission_interface.h.

const double qb_move_transmission_interface::qbMoveTransmission::getPresetPercentToRadians ( ) const
inline
Returns
The preset percent value to radians scale factor: $\frac{pos\_tick\_to\_rad}{preset_tick_to_percent}$.

Definition at line 148 of file qb_move_transmission_interface.h.

const double qb_move_transmission_interface::qbMoveTransmission::getVelocityFactor ( ) const
inline
Returns
The current velocity scale factor.

Definition at line 153 of file qb_move_transmission_interface.h.

void qb_move_transmission_interface::qbMoveTransmission::jointToActuatorEffort ( const transmission_interface::JointData joint,
transmission_interface::ActuatorData actuator 
)
inlinevirtual

Transform effort variables from joint to actuator space.

Parameters
jointJoint-space variables.
[out]actuatorActuator-space variables.
Precondition
Actuator and joint effort vectors must have size according respectively to numActuators and numJoints and must point to valid data, at least for the used fields, i.e. it is not required that all other data vectors contain valid data; they can even remain empty.

Implements transmission_interface::Transmission.

Definition at line 168 of file qb_move_transmission_interface.h.

void qb_move_transmission_interface::qbMoveTransmission::jointToActuatorPosition ( const transmission_interface::JointData joint,
transmission_interface::ActuatorData actuator 
)
inlinevirtual

Transform position variables from joint to actuator space.

Parameters
jointJoint-space variables.
[out]actuatorActuator-space variables.
Precondition
Actuator and joint position vectors must have size according respectively to numActuators and numJoints and must point to valid data, at least for the used fields, i.e. it is not required that all other data vectors contain valid data; they can even remain empty.

Implements transmission_interface::Transmission.

Definition at line 212 of file qb_move_transmission_interface.h.

void qb_move_transmission_interface::qbMoveTransmission::jointToActuatorVelocity ( const transmission_interface::JointData joint,
transmission_interface::ActuatorData actuator 
)
inlinevirtual

Transform velocity variables from joint to actuator space.

Parameters
jointJoint-space variables.
[out]actuatorActuator-space variables.
Precondition
Actuator and joint velocity vectors must have size according respectively to numActuators and numJoints and must point to valid data, at least for the used fields, i.e. it is not required that all other data vectors contain valid data; they can even remain empty.

Implements transmission_interface::Transmission.

Definition at line 194 of file qb_move_transmission_interface.h.

std::size_t qb_move_transmission_interface::qbMoveTransmission::numActuators ( ) const
inlinevirtual
Returns
The number of actuators of this transmission, i.e always 2 for the qbmove.

Implements transmission_interface::Transmission.

Definition at line 231 of file qb_move_transmission_interface.h.

std::size_t qb_move_transmission_interface::qbMoveTransmission::numJoints ( ) const
inlinevirtual
Returns
The number of joints of this transmission, i.e always 4 for the qbmove.

Implements transmission_interface::Transmission.

Definition at line 236 of file qb_move_transmission_interface.h.

void qb_move_transmission_interface::qbMoveTransmission::setCommandWithPoistionAndPreset ( const bool &  command_with_position_and_preset)
inline
Returns
true if the controller exploits shaft position and stiffness preset.

Definition at line 241 of file qb_move_transmission_interface.h.

void qb_move_transmission_interface::qbMoveTransmission::setPositionFactor ( const std::vector< int > &  encoder_resolutions)
inline
Returns
The current position scale factor.

Definition at line 246 of file qb_move_transmission_interface.h.

void qb_move_transmission_interface::qbMoveTransmission::setPresetFactor ( const int &  stiffness_preset_limit)
inline
Returns
The current preset scale factor.

Definition at line 257 of file qb_move_transmission_interface.h.

Member Data Documentation

bool qb_move_transmission_interface::qbMoveTransmission::command_with_position_and_preset_
private

Definition at line 260 of file qb_move_transmission_interface.h.

double qb_move_transmission_interface::qbMoveTransmission::effort_factor_
private

Definition at line 264 of file qb_move_transmission_interface.h.

std::vector<double> qb_move_transmission_interface::qbMoveTransmission::position_factor_
private

Definition at line 261 of file qb_move_transmission_interface.h.

double qb_move_transmission_interface::qbMoveTransmission::preset_factor_
private

Definition at line 262 of file qb_move_transmission_interface.h.

double qb_move_transmission_interface::qbMoveTransmission::velocity_factor_
private

Definition at line 263 of file qb_move_transmission_interface.h.


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


qb_move_hardware_interface
Author(s): qbroboticsĀ®
autogenerated on Wed Jun 12 2019 19:18:54