Robowflex
v0.1
Making MoveIt Easy
|
Manager for a set of TSR constraints. Attempts to reduce redundancy and combines errors and Jacobians together. More...
#include <tsr.h>
Public Member Functions | |
void | print (std::ostream &out) const |
Print out the TSRs in this set. More... | |
Constructor and Initialization | |
TSRSet (const WorldPtr &world, const TSRPtr &tsr) | |
Constructor. More... | |
TSRSet (const WorldPtr &world, const std::vector< TSRPtr > &tsrs, bool intersect=true) | |
Constructor. More... | |
void | setWorld (const WorldPtr &world) |
Set the world used by this TSR set. More... | |
void | addTSR (const TSRPtr &tsr, bool intersect=true, double weight=1.0) |
Add a TSR to the set. More... | |
void | initialize () |
Initialize this set of TSRs. More... | |
void | updateSolver () |
Update the solver information (iterations, tolerance, etc.) More... | |
DoF Indexing | |
void | useGroup (const std::string &name) |
Use the joints in a robot's group. Robot used is the target frame's structure. More... | |
void | useIndices (const std::vector< std::size_t > &indices) |
Use DoF indices for all TSRs computation. More... | |
void | useWorldIndices (const std::vector< std::pair< std::size_t, std::size_t >> &indices) |
Use World DoF indices for all TSRs computation. World indices are pairs of skeleton index and DoF index. More... | |
void | setWorldIndices (const std::vector< std::pair< std::size_t, std::size_t >> &indices) |
Output world indices. TSR information for *WorldState methods uses this set of world indices. World indices are pairs of skeleton index and DoF index. More... | |
const std::vector< std::pair< std::size_t, std::size_t > > & | getWorldIndices () const |
Get the world indices used. More... | |
void | setWorldUpperLimits (const Eigen::Ref< const Eigen::VectorXd > &upper) |
Set the upper limit on joints given their index in the world configuration. More... | |
void | setWorldLowerLimits (const Eigen::Ref< const Eigen::VectorXd > &lower) |
Set the lower limit on joints given their index in the world configuration. More... | |
void | computeLimits () |
Compute the upper and lower limits from the skeleton. More... | |
Getters | |
void | getPositionsWorldState (Eigen::Ref< Eigen::VectorXd > world) const |
Get the current world state. More... | |
std::size_t | getDimension () const |
Get the error dimension of this set of TSRs. More... | |
std::size_t | numTSRs () const |
Get the number of TSRs in the set. More... | |
const std::vector< TSRPtr > & | getTSRs () const |
Get the TSRs that form the set. More... | |
double | getTolerance () const |
Get the numerical tolerance for solving. More... | |
void | setTolerance (double tolerance) |
Set the maximum tolerance used for solving. More... | |
std::size_t | getMaxIterations () const |
Get the maximum iterations allowed. More... | |
void | setMaxIterations (std::size_t iterations) |
Set the maximum iterations used for solving. More... | |
void | addSuffix (const std::string &suffix) |
Add a suffix to the end of all structures in the TSRs in the set. More... | |
void | setStep (double step) |
Set the step parameter in the solver. More... | |
double | getStep () const |
Get the solver step parameter. More... | |
void | setLimit (double limit) |
Set the limit parameter in the solver. More... | |
double | getLimit () const |
Get the solver limit parameter. More... | |
void | setDamping (double damping) |
Set the damping parameter in the solver. More... | |
double | getDamping () const |
Get the solver damping parameter. More... | |
void | useDamping (bool damping) |
Set if damping is used in SVD solving. More... | |
void | useSVD () |
Use SVD for solving. More... | |
void | useQR () |
Use QR for solving. More... | |
Error / Function Computation | |
void | getErrorWorld (Eigen::Ref< Eigen::VectorXd > error) const |
Get the current error given the world state. More... | |
void | getErrorWorldState (const Eigen::Ref< const Eigen::VectorXd > &world, Eigen::Ref< Eigen::VectorXd > error) const |
Get the error given a provided world configuration. More... | |
Jacobian Computation | |
void | getJacobianWorldState (const Eigen::Ref< const Eigen::VectorXd > &world, Eigen::Ref< Eigen::MatrixXd > jacobian) const |
Get the Jacobian given a provided world configuration. More... | |
Distance Computation | |
double | distanceWorld () const |
Get the current distance to satisfaction given the world state. More... | |
double | distanceWorldState (const Eigen::Ref< const Eigen::VectorXd > &world) const |
Get the distance to satisfaction given a provided world configuration. More... | |
Solving for Satisfying Configurations | |
bool | solveWorld () |
Solve for a satisfying configuration given the current state of the world. More... | |
bool | solveWorldState (Eigen::Ref< Eigen::VectorXd > world) |
Solve for a satisfying configuration given an initial world configuration. More... | |
bool | solveGradientWorldState (Eigen::Ref< Eigen::VectorXd > world) |
Solve using gradient descent for a satisfying configuration given an initial world configuration. More... | |
Private Member Functions | |
void | enforceBoundsWorld (Eigen::Ref< Eigen::VectorXd > world) const |
Enforce upper and lower bounds on a world configuration. More... | |
Private Attributes | |
WorldPtr | world_ |
World to use. More... | |
std::set< std::size_t > | skel_indices_ |
All skeleton indices used by members of the set. More... | |
bool | qr_ {false} |
If true, use QR in gradient solve. Else, SVD. More... | |
bool | damped_ {true} |
If true, use damped SVD. More... | |
double | step_ {1.0} |
Step scaling in gradient. More... | |
double | limit_ {1.} |
Step size limit. More... | |
double | damping_ {1e-8} |
Damping factor. More... | |
double | tolerance_ {magic::DEFAULT_IK_TOLERANCE} |
Tolerance for solving. More... | |
std::size_t | maxIter_ {50} |
Maximum iterations to use for solving. More... | |
std::vector< TSRPtr > | tsrs_ |
Set of TSRs. More... | |
std::vector< double > | weights_ |
Weights on TSRs. More... | |
std::size_t | dimension_ {0} |
Total error dimension of set. More... | |
Eigen::VectorXd | upper_ |
Upper bounds on world configuration. More... | |
Eigen::VectorXd | lower_ |
Lower bounds on world configuration. More... | |
Manager for a set of TSR constraints. Attempts to reduce redundancy and combines errors and Jacobians together.
Will "stack" the error values and Jacobians together. For example, given two TSRs "a" and "b" in the set, the error vector will be [ea, eb] where ea and eb are a and b's error vector. The Jacobian will also correspond to this stacked error vector.
Constructor.
Definition at line 928 of file tsr.cpp.
TSRSet::TSRSet | ( | const WorldPtr & | world, |
const std::vector< TSRPtr > & | tsrs, | ||
bool | intersect = true |
||
) |
void TSRSet::addSuffix | ( | const std::string & | suffix | ) |
void TSRSet::addTSR | ( | const TSRPtr & | tsr, |
bool | intersect = true , |
||
double | weight = 1.0 |
||
) |
Add a TSR to the set.
[in] | tsr | TSR to add. |
[in] | intersect | If true, tries to simplify TSR set. |
[in] | weight | Weight to use for this TSR. |
Definition at line 939 of file tsr.cpp.
void TSRSet::computeLimits | ( | ) |
Compute the upper and lower limits from the skeleton.
Definition at line 1242 of file tsr.cpp.
double TSRSet::distanceWorld | ( | ) | const |
Get the current distance to satisfaction given the world state.
Definition at line 1081 of file tsr.cpp.
double TSRSet::distanceWorldState | ( | const Eigen::Ref< const Eigen::VectorXd > & | world | ) | const |
Get the distance to satisfaction given a provided world configuration.
[in] | world | World configuration (from world indices). |
Definition at line 1088 of file tsr.cpp.
|
private |
double TSRSet::getDamping | ( | ) | const |
std::size_t TSRSet::getDimension | ( | ) | const |
Get the error dimension of this set of TSRs.
void TSRSet::getErrorWorld | ( | Eigen::Ref< Eigen::VectorXd > | error | ) | const |
void TSRSet::getErrorWorldState | ( | const Eigen::Ref< const Eigen::VectorXd > & | world, |
Eigen::Ref< Eigen::VectorXd > | error | ||
) | const |
void TSRSet::getJacobianWorldState | ( | const Eigen::Ref< const Eigen::VectorXd > & | world, |
Eigen::Ref< Eigen::MatrixXd > | jacobian | ||
) | const |
double TSRSet::getLimit | ( | ) | const |
std::size_t TSRSet::getMaxIterations | ( | ) | const |
void TSRSet::getPositionsWorldState | ( | Eigen::Ref< Eigen::VectorXd > | world | ) | const |
double TSRSet::getStep | ( | ) | const |
double TSRSet::getTolerance | ( | ) | const |
Get the numerical tolerance for solving.
const std::vector< TSRPtr > & TSRSet::getTSRs | ( | ) | const |
const std::vector< std::pair< std::size_t, std::size_t > > & TSRSet::getWorldIndices | ( | ) | const |
void TSRSet::initialize | ( | ) |
Initialize this set of TSRs.
Definition at line 1214 of file tsr.cpp.
std::size_t TSRSet::numTSRs | ( | ) | const |
void TSRSet::print | ( | std::ostream & | out | ) | const |
Print out the TSRs in this set.
[in] | out | Output stream. |
void TSRSet::setDamping | ( | double | damping | ) |
void TSRSet::setLimit | ( | double | limit | ) |
void TSRSet::setMaxIterations | ( | std::size_t | iterations | ) |
void TSRSet::setStep | ( | double | step | ) |
void TSRSet::setTolerance | ( | double | tolerance | ) |
Set the maximum tolerance used for solving.
[in] | tolerance | New tolerance. |
void TSRSet::setWorld | ( | const WorldPtr & | world | ) |
Set the world used by this TSR set.
[in] | world | New world to use. |
Definition at line 983 of file tsr.cpp.
void TSRSet::setWorldIndices | ( | const std::vector< std::pair< std::size_t, std::size_t >> & | indices | ) |
void TSRSet::setWorldLowerLimits | ( | const Eigen::Ref< const Eigen::VectorXd > & | lower | ) |
void TSRSet::setWorldUpperLimits | ( | const Eigen::Ref< const Eigen::VectorXd > & | upper | ) |
bool TSRSet::solveGradientWorldState | ( | Eigen::Ref< Eigen::VectorXd > | world | ) |
Solve using gradient descent for a satisfying configuration given an initial world configuration.
[in] | world | World configuration (from world indices). |
Definition at line 1135 of file tsr.cpp.
bool TSRSet::solveWorld | ( | ) |
bool TSRSet::solveWorldState | ( | Eigen::Ref< Eigen::VectorXd > | world | ) |
Solve for a satisfying configuration given an initial world configuration.
[in] | world | World configuration (from world indices). |
Definition at line 1120 of file tsr.cpp.
void TSRSet::updateSolver | ( | ) |
void TSRSet::useDamping | ( | bool | damping | ) |
void TSRSet::useGroup | ( | const std::string & | name | ) |
void TSRSet::useIndices | ( | const std::vector< std::size_t > & | indices | ) |
void TSRSet::useQR | ( | ) |
void TSRSet::useSVD | ( | ) |
void TSRSet::useWorldIndices | ( | const std::vector< std::pair< std::size_t, std::size_t >> & | indices | ) |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |