Public Member Functions | Private Attributes | List of all members
qb_hand_transmission_interface::qbHandVirtualTransmission Class Reference

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

#include <qb_hand_transmission_interface.h>

Inheritance diagram for qb_hand_transmission_interface::qbHandVirtualTransmission:
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 double & getEffortFactor () const
 
const double & getPositionFactor () 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
 
 qbHandVirtualTransmission ()
 Build the qbhand transmission with default velocity and effort scale factors (respectively 0.2 and 0.001). More...
 
 qbHandVirtualTransmission (const double &position_factor, const double &velocity_factor, const double &effort_factor)
 Build the qbhand transmission with the given scale factors. More...
 
void setPositionFactor (const int &motor_position_limit)
 Set the position scale factor. More...
 
- Public Member Functions inherited from transmission_interface::Transmission
virtual ~Transmission ()
 

Private Attributes

double effort_factor_
 
double position_factor_
 
double velocity_factor_
 

Detailed Description

The qbrobotics qbhand Transmission interface implements the specific transmission_interface::Transmission to convert from qbhand 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_hand_transmission_interface.h.

Constructor & Destructor Documentation

qb_hand_transmission_interface::qbHandVirtualTransmission::qbHandVirtualTransmission ( )
inline

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

The position scale factor is based on the "motor position limit" (expressed in ticks) which is the maximum closure value, and follows the formula $f_{pos} = \frac{1}{closure\_limit}$. The default closure_limit is set to 19000 ticks, but it can be modified during the execution with the proper method.

Definition at line 48 of file qb_hand_transmission_interface.h.

qb_hand_transmission_interface::qbHandVirtualTransmission::qbHandVirtualTransmission ( const double &  position_factor,
const double &  velocity_factor,
const double &  effort_factor 
)
inline

Build the qbhand transmission with the given scale factors.

Parameters
position_factorMotor position ticks to closure percent value [0, 1] scale factor.
velocity_factorExponential filter smoothing factor.
effort_factorMotor current mA to joint effort A scale factor.

Definition at line 57 of file qb_hand_transmission_interface.h.

Member Function Documentation

void qb_hand_transmission_interface::qbHandVirtualTransmission::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 71 of file qb_hand_transmission_interface.h.

void qb_hand_transmission_interface::qbHandVirtualTransmission::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 102 of file qb_hand_transmission_interface.h.

void qb_hand_transmission_interface::qbHandVirtualTransmission::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 86 of file qb_hand_transmission_interface.h.

const double& qb_hand_transmission_interface::qbHandVirtualTransmission::getEffortFactor ( ) const
inline
Returns
The current effort scale factor.

Definition at line 122 of file qb_hand_transmission_interface.h.

const double& qb_hand_transmission_interface::qbHandVirtualTransmission::getPositionFactor ( ) const
inline
Returns
The current position scale factor.

Definition at line 112 of file qb_hand_transmission_interface.h.

const double& qb_hand_transmission_interface::qbHandVirtualTransmission::getVelocityFactor ( ) const
inline
Returns
The current velocity scale factor.

Definition at line 117 of file qb_hand_transmission_interface.h.

void qb_hand_transmission_interface::qbHandVirtualTransmission::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 132 of file qb_hand_transmission_interface.h.

void qb_hand_transmission_interface::qbHandVirtualTransmission::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 164 of file qb_hand_transmission_interface.h.

void qb_hand_transmission_interface::qbHandVirtualTransmission::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 148 of file qb_hand_transmission_interface.h.

std::size_t qb_hand_transmission_interface::qbHandVirtualTransmission::numActuators ( ) const
inlinevirtual
Returns
The number of actuators of this transmission, i.e always 1 for the qbhand.

Implements transmission_interface::Transmission.

Definition at line 174 of file qb_hand_transmission_interface.h.

std::size_t qb_hand_transmission_interface::qbHandVirtualTransmission::numJoints ( ) const
inlinevirtual
Returns
The number of joints of this transmission, i.e always 1 for the qbhand.

Implements transmission_interface::Transmission.

Definition at line 179 of file qb_hand_transmission_interface.h.

void qb_hand_transmission_interface::qbHandVirtualTransmission::setPositionFactor ( const int &  motor_position_limit)
inline

Set the position scale factor.

Parameters
position_factorMotor position ticks to closure percent value [0, 1] scale factor.

Definition at line 185 of file qb_hand_transmission_interface.h.

Member Data Documentation

double qb_hand_transmission_interface::qbHandVirtualTransmission::effort_factor_
private

Definition at line 190 of file qb_hand_transmission_interface.h.

double qb_hand_transmission_interface::qbHandVirtualTransmission::position_factor_
private

Definition at line 188 of file qb_hand_transmission_interface.h.

double qb_hand_transmission_interface::qbHandVirtualTransmission::velocity_factor_
private

Definition at line 189 of file qb_hand_transmission_interface.h.


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


qb_hand_hardware_interface
Author(s): qbroboticsĀ®
autogenerated on Wed Jun 5 2019 20:23:24