A robot's gripper reprensentation. More...
#include <mc_control/generic_gripper.h>
Public Member Functions | |
Gripper (const mc_rbdyn::Robot &robot, const std::vector< std::string > &jointNames, const std::string &robot_urdf, bool reverseLimits, const mc_rbdyn::RobotModule::Gripper::Safety &safety) | |
Constructor. More... | |
Gripper (const mc_rbdyn::Robot &robot, const std::vector< std::string > &jointNames, const std::vector< mc_rbdyn::Mimic > &mimics, bool reverseLimits, const mc_rbdyn::RobotModule::Gripper::Safety &safety) | |
Constructor. More... | |
void | resetDefaults () |
Resets the gripper parameters to their default value (percentVMax, actualCommandDiffTrigger) More... | |
void | saveConfig () |
Saves the current gripper configuration parameters contained in Config. More... | |
void | restoreConfig () |
Restores the gripper configuration parameters from their saved value. More... | |
void | configure (const mc_rtc::Configuration &config) |
Applies a new gripper configuration (safeties and targets) More... | |
void | reset (const std::vector< double > ¤tQ) |
Reset the gripper state to the current actual state of the gripper. More... | |
void | reset (const Gripper &gripper) |
Reset from another gripper. More... | |
void | run (double timeStep, mc_rbdyn::Robot &robot, mc_rbdyn::Robot &real) |
Run one iteration of control. More... | |
void | setTargetQ (const std::vector< double > &targetQ) |
Set the target configuration of the active joints involved in the gripper. More... | |
void | setTargetQ (const std::string &jointName, double targetQ) |
Set the target configuration of the specified active joint. More... | |
double | getTargetQ (const std::string &jointName) const |
std::vector< double > | getTargetQ () const |
void | setTargetOpening (double targetOpening) |
Set the target opening of all gripper joints simultaneously. More... | |
void | setTargetOpening (const std::string &jointName, double targetOpening) |
Set the target opening of a single gripper joint. More... | |
double | getTargetOpening (const std::string &jointName) const |
Get the target opening of a single gripper joint. More... | |
std::vector< double > | curPosition () const |
Get current configuration. More... | |
std::vector< double > | curOpening () const |
Get current opening percentage. More... | |
double | curOpening (const std::string &jointName) const |
Get the current opening of a single gripper joint. More... | |
const std::vector< std::string > & | joints () const |
Returns all joints involved in the gripper. More... | |
const std::vector< std::string > & | activeJoints () const |
Returns all active joints involved in the gripper. More... | |
bool | hasActiveJoint (const std::string &jointName) const |
const std::vector< double > & | q () const |
Return all gripper joints configuration. More... | |
double | opening () const |
Get the current opening percentage. More... | |
void | percentVMAX (double percent) |
double | percentVMAX () const |
void | actualCommandDiffTrigger (double d) |
double | actualCommandDiffTrigger () const |
void | overCommandLimitIterN (unsigned int N) |
unsigned int | overCommandLimitIterN () const |
void | releaseSafetyOffset (double offset) |
double | releaseSafetyOffset () const |
bool | complete () const |
Check if the gripper motion stopped moving. More... | |
bool | is_metric () const noexcept |
Returns true if a gripper is metric, i.e. all active joints are prismatic rather than revolute. More... | |
bool | reversed () const noexcept |
When true the gripper is considered "open" when the joints' values are minimal. More... | |
Protected Types | |
using | Config = mc_rbdyn::RobotModule::Gripper::Safety |
Protected Member Functions | |
void | setTargetOpening (size_t activeJointId, double targetOpening) |
Set the target opening of a single gripper joint by index. More... | |
void | setTargetQ (size_t activeJointId, double targetQ) |
Set the target configuration of the specified active joint. More... | |
void | setTargetQ_ (size_t activeJoints, double targetQ) |
Fast version of setTargetQ(size_t, double) without clamping. More... | |
void | setTargetQ_ (const std::vector< double > &targetQ) |
Fast version of setTargetQ(std::vector<double>) More... | |
double | curPosition (size_t jointId) const |
Current position of an active joint. More... | |
double | curOpening (size_t jointId) const |
Current opening percentage of an active joint. More... | |
double | targetOpening (size_t jointId) const |
Target opening percentage of an active joint. More... | |
double | getTargetQ (size_t jointId) const |
Target opening angle of an active joint. More... | |
double | clampQ (size_t activeJoint, double q) |
Clamp an active joint value within its joint limits. More... | |
Protected Attributes | |
std::vector< std::string > | names |
std::vector< std::string > | active_joints |
std::vector< size_t > | active_joints_idx |
std::vector< int > | joints_mbc_idx |
bool | is_metric_ |
std::vector< double > | closeP |
std::vector< double > | openP |
std::vector< double > | vmax |
std::vector< std::pair< size_t, double > > | mult |
std::vector< double > | offset |
std::vector< double > | _q |
std::vector< double > | targetQIn |
std::vector< double > * | targetQ |
std::vector< double > | reached_threshold_ |
std::vector< double > | actualQ |
Config | config_ |
Config | savedConfig_ |
Config | defaultConfig_ |
std::vector< double > | percentOpen |
std::vector< bool > | overCommandLimit |
std::vector< unsigned int > | overCommandLimitIter |
bool | reversed_ = false |
A robot's gripper reprensentation.
A gripper is composed of a set of joints that we want to control only through "manual" operations. It may include passive joints.
By default, a gripper is considered "open" when its joints' values are at maximum value and "closed" at minimum value. This behaviour can be reversed when the gripper is created.
In real operations the actuated joints are also monitored to avoid potential servo errors.
|
protected |
mc_control::Gripper::Gripper | ( | const mc_rbdyn::Robot & | robot, |
const std::vector< std::string > & | jointNames, | ||
const std::string & | robot_urdf, | ||
bool | reverseLimits, | ||
const mc_rbdyn::RobotModule::Gripper::Safety & | safety | ||
) |
Constructor.
robot | The full robot including uncontrolled joints |
jointNames | Name of the active joints involved in the gripper |
robot_urdf | URDF of the robot |
reverseLimits | If set to true, then the gripper is considered "open" when the joints' values are minimal |
safety | Default gripper safety parameters |
mc_control::Gripper::Gripper | ( | const mc_rbdyn::Robot & | robot, |
const std::vector< std::string > & | jointNames, | ||
const std::vector< mc_rbdyn::Mimic > & | mimics, | ||
bool | reverseLimits, | ||
const mc_rbdyn::RobotModule::Gripper::Safety & | safety | ||
) |
Constructor.
This constructor does not use information from the URDF file
robot | Robot, must have the active joints of the gripper to work properly |
jointNames | Name of the active joints involved in the gripper |
mimics | Mimic joints for the gripper |
reverseLimits | If true, the gripper is considered "open" when the joints values are minimal |
safety | Default gripper safety parameters |
|
inline |
Returns all active joints involved in the gripper.
|
inline |
Difference between the command and the reality that triggers the safety
|
inline |
Set safety trigger threshold (difference between the command and the reality)
This safety is meant to prevent over-torques on position controlled grippers with no torque readings by checking how far the encoder output is from the desired command. If it is over the limit, it can only stay there for overCommandLimitIterN iterations before being released
|
protected |
Clamp an active joint value within its joint limits.
bool mc_control::Gripper::complete | ( | ) | const |
Check if the gripper motion stopped moving.
The gripper will stop if
void mc_control::Gripper::configure | ( | const mc_rtc::Configuration & | config | ) |
Applies a new gripper configuration (safeties and targets)
std::vector<double> mc_control::Gripper::curOpening | ( | ) | const |
Get current opening percentage.
double mc_control::Gripper::curOpening | ( | const std::string & | jointName | ) | const |
Get the current opening of a single gripper joint.
jointName | Name of the active joint |
std::runtime_error | if the joint name does not match any of the gripper's active joints |
|
protected |
Current opening percentage of an active joint.
std::vector<double> mc_control::Gripper::curPosition | ( | ) | const |
Get current configuration.
|
protected |
Current position of an active joint.
double mc_control::Gripper::getTargetOpening | ( | const std::string & | jointName | ) | const |
Get the target opening of a single gripper joint.
jointName | Name of the active joint |
std::runtime_error | if the joint name does not match any of the gripper's active joints |
std::vector<double> mc_control::Gripper::getTargetQ | ( | ) | const |
Get the current gripper's target
double mc_control::Gripper::getTargetQ | ( | const std::string & | jointName | ) | const |
Get a joint's target angle
std::runtime_error | if the joint name does not match any of the gripper's active joints |
|
protected |
Target opening angle of an active joint.
|
inline |
|
inlinenoexcept |
Returns true if a gripper is metric, i.e. all active joints are prismatic rather than revolute.
This only affects safety settings in the GUI
|
inline |
Returns all joints involved in the gripper.
double mc_control::Gripper::opening | ( | ) | const |
Get the current opening percentage.
|
inline |
Number of iterations where actualCommandDiffTrigger() threshold may be exceeded before the security is triggered
|
inline |
Number of iterations where actualCommandDiffTrigger() threshold may be exceeded before the security is triggered
double mc_control::Gripper::percentVMAX | ( | ) | const |
Get gripper speed (percentage of max velocity)
void mc_control::Gripper::percentVMAX | ( | double | percent | ) |
Set gripper speed as a percentage of maximum velocity
|
inline |
Return all gripper joints configuration.
|
inline |
Offset by which the gripper is release if overCommandDiffTrigger is trigger for more than overCommandLimitIterN
|
inline |
Offset by which the gripper is released if overCommandDiffTrigger is trigger for more than overCommandLimitIterN
offset | offset angle in [rad] or distance in [meter] |
void mc_control::Gripper::reset | ( | const Gripper & | gripper | ) |
Reset from another gripper.
gripper | Gripper used to reset this one |
void mc_control::Gripper::reset | ( | const std::vector< double > & | currentQ | ) |
Reset the gripper state to the current actual state of the gripper.
currentQ | Current encoder values for the robot |
void mc_control::Gripper::resetDefaults | ( | ) |
Resets the gripper parameters to their default value (percentVMax, actualCommandDiffTrigger)
void mc_control::Gripper::restoreConfig | ( | ) |
Restores the gripper configuration parameters from their saved value.
|
inlinenoexcept |
When true the gripper is considered "open" when the joints' values are minimal.
void mc_control::Gripper::run | ( | double | timeStep, |
mc_rbdyn::Robot & | robot, | ||
mc_rbdyn::Robot & | real | ||
) |
Run one iteration of control.
robot | Robot for which this gripper control is running |
real | Real robot for which this gripper control is running |
The gripper control updates both the robot's configuration and the output
void mc_control::Gripper::saveConfig | ( | ) |
Saves the current gripper configuration parameters contained in Config.
void mc_control::Gripper::setTargetOpening | ( | const std::string & | jointName, |
double | targetOpening | ||
) |
Set the target opening of a single gripper joint.
jointName | Name of the active joint to move |
targetOpening | Opening value ranging from 0 (closed) to 1 (open) |
std::runtime_error | if the joint name does not match any of the gripper's active joints |
void mc_control::Gripper::setTargetOpening | ( | double | targetOpening | ) |
Set the target opening of all gripper joints simultaneously.
targetOpening | Opening value ranging from 0 (closed) to 1 (open) |
|
protected |
Set the target opening of a single gripper joint by index.
activeJointId | Index of the active joint |
targetOpening | Opening value ranging from 0 (closed) to 1 (open) |
void mc_control::Gripper::setTargetQ | ( | const std::string & | jointName, |
double | targetQ | ||
) |
Set the target configuration of the specified active joint.
jointName | Name of the gripper's active joint to move |
targetQ | Desired value of the active joint |
std::runtime_error | if the joint name does not match any of the gripper's active joints |
void mc_control::Gripper::setTargetQ | ( | const std::vector< double > & | targetQ | ) |
Set the target configuration of the active joints involved in the gripper.
targetQ | Desired values of the active joints involved in the gripper |
std::runtime_error | If the targetQ size does not match the number of active joints |
|
protected |
Set the target configuration of the specified active joint.
activeJointId | Index of the gripper's active joint to move |
targetQ | Desired value of the active joint. Clamps the target within the joint limits. |
|
protected |
Fast version of setTargetQ(std::vector<double>)
|
protected |
Fast version of setTargetQ(size_t, double) without clamping.
|
protected |
Target opening percentage of an active joint.
|
protected |
Full joints' values
|
protected |
Name of active joints involved in the gripper
|
protected |
Active joints indexes in the reference joint order
|
protected |
Joints' values from the encoders
|
protected |
Lower limits of active joints in the gripper (closed-gripper values)
|
protected |
Current configuration of the gripper parameters
|
protected |
Default configuration provided at construction
|
protected |
True if all joints are primatic
|
protected |
All joint indexes in mbc, -1 if absent
|
protected |
Mimic multiplier, first element is the joint to mimic, second is the multiplier
|
protected |
Name of joints involved in the gripper
|
protected |
Mimic offsets
|
protected |
Upper limits of active joints in the gripper (open-gripper values)
|
protected |
True if the gripper has been too far from the command for over overCommandLimitIterN iterations
|
protected |
Store the number of iterations where the gripper command was over the limit
|
protected |
Current opening percentage
|
protected |
Target reached threshold per-joint (0.001 rad for revolute and 0.0001 for prismatic joints)
|
protected |
True if the gripper is reversed
|
protected |
Saved configuration of the parameters saved by saveConfig()
|
protected |
Current gripper target: NULL if target has been reached or safety was triggered
|
protected |
Current gripper target
|
protected |
Maximum velocity of active joints in the gripper