DART
6.7.3
|
The TaskSpaceRegion is a nicely generalized method for computing the error of an IK Problem. More...
#include <InverseKinematics.hpp>
Classes | |
struct | Properties |
struct | UniqueProperties |
Public Types | |
typedef std::pair< Eigen::Vector6d, Eigen::Vector6d > | Bounds |
Public Member Functions | |
TaskSpaceRegion (InverseKinematics *_ik, const Properties &_properties=Properties()) | |
Default Constructor. More... | |
virtual | ~TaskSpaceRegion ()=default |
Virtual destructor. More... | |
std::unique_ptr< ErrorMethod > | clone (InverseKinematics *_newIK) const override |
Enable this ErrorMethod to be cloned to a new IK module. More... | |
Eigen::Isometry3d | computeDesiredTransform (const Eigen::Isometry3d &_currentTf, const Eigen::Vector6d &_error) override |
Override this function with your implementation of computing the desired given the current transform and error vector. More... | |
Eigen::Vector6d | computeError () override |
Override this function with your implementation of the error vector computation. More... | |
void | setComputeFromCenter (bool computeFromCenter) |
Set whether this TaskSpaceRegion should compute its error vector from the center of the region. More... | |
bool | isComputingFromCenter () const |
Get whether this TaskSpaceRegion is set to compute its error vector from the center of the region. More... | |
Properties | getTaskSpaceRegionProperties () const |
Get the Properties of this TaskSpaceRegion. More... | |
const Eigen::Vector6d & | evalError (const Eigen::VectorXd &_q) |
This function is used to handle caching the error vector. More... | |
const std::string & | getMethodName () const |
Get the name of this ErrorMethod. More... | |
void | setBounds (const Eigen::Vector6d &_lower=Eigen::Vector6d::Constant(-DefaultIKTolerance), const Eigen::Vector6d &_upper=Eigen::Vector6d::Constant(DefaultIKTolerance)) |
Set all the error bounds. More... | |
void | setBounds (const std::pair< Eigen::Vector6d, Eigen::Vector6d > &_bounds) |
Set all the error bounds. More... | |
const std::pair< Eigen::Vector6d, Eigen::Vector6d > & | getBounds () const |
Get all the error bounds. More... | |
void | setAngularBounds (const Eigen::Vector3d &_lower=Eigen::Vector3d::Constant(-DefaultIKTolerance), const Eigen::Vector3d &_upper=Eigen::Vector3d::Constant(DefaultIKTolerance)) |
Set the error bounds for orientation. More... | |
void | setAngularBounds (const std::pair< Eigen::Vector3d, Eigen::Vector3d > &_bounds) |
Set the error bounds for orientation. More... | |
std::pair< Eigen::Vector3d, Eigen::Vector3d > | getAngularBounds () const |
Get the error bounds for orientation. More... | |
void | setLinearBounds (const Eigen::Vector3d &_lower=Eigen::Vector3d::Constant(-DefaultIKTolerance), const Eigen::Vector3d &_upper=Eigen::Vector3d::Constant(DefaultIKTolerance)) |
Set the error bounds for translation. More... | |
void | setLinearBounds (const std::pair< Eigen::Vector3d, Eigen::Vector3d > &_bounds) |
Set the error bounds for translation. More... | |
std::pair< Eigen::Vector3d, Eigen::Vector3d > | getLinearBounds () const |
Get the error bounds for translation. More... | |
void | setErrorLengthClamp (double _clampSize=DefaultIKErrorClamp) |
Set the clamp that will be applied to the length of the error vector each iteration. More... | |
double | getErrorLengthClamp () const |
Set the clamp that will be applied to the length of the error vector each iteration. More... | |
void | setErrorWeights (const Eigen::Vector6d &_weights) |
Set the weights that will be applied to each component of the error vector. More... | |
const Eigen::Vector6d & | getErrorWeights () const |
Get the weights that will be applied to each component of the error vector. More... | |
void | setAngularErrorWeights (const Eigen::Vector3d &_weights=Eigen::Vector3d::Constant(DefaultIKAngularWeight)) |
Set the weights that will be applied to each angular component of the error vector. More... | |
Eigen::Vector3d | getAngularErrorWeights () const |
Get the weights that will be applied to each angular component of the error vector. More... | |
void | setLinearErrorWeights (const Eigen::Vector3d &_weights=Eigen::Vector3d::Constant(DefaultIKLinearWeight)) |
Set the weights that will be applied to each linear component of the error vector. More... | |
Eigen::Vector3d | getLinearErrorWeights () const |
Get the weights that will be applied to each linear component of the error vector. More... | |
Properties | getErrorMethodProperties () const |
Get the Properties of this ErrorMethod. More... | |
void | clearCache () |
Clear the cache to force the error to be recomputed. More... | |
Protected Member Functions | |
void | sendDestructionNotification () const |
Send a destruction notification to all Observers. More... | |
void | addObserver (Observer *_observer) const |
Add an Observer to the list of Observers. More... | |
void | removeObserver (Observer *_observer) const |
Remove an Observer from the list of Observers. More... | |
Protected Attributes | |
UniqueProperties | mTaskSpaceP |
Properties of this TaskSpaceRegion. More... | |
common::sub_ptr< InverseKinematics > | mIK |
Pointer to the IK module of this ErrorMethod. More... | |
std::string | mMethodName |
Name of this error method. More... | |
Eigen::VectorXd | mLastPositions |
The last joint positions passed into this ErrorMethod. More... | |
Eigen::Vector6d | mLastError |
The last error vector computed by this ErrorMethod. More... | |
Properties | mErrorP |
The properties of this ErrorMethod. More... | |
std::set< Observer * > | mObservers |
List of current Observers. More... | |
The TaskSpaceRegion is a nicely generalized method for computing the error of an IK Problem.
|
inherited |
|
explicit |
Default Constructor.
|
virtualdefault |
Virtual destructor.
|
protectedinherited |
Add an Observer to the list of Observers.
|
inherited |
Clear the cache to force the error to be recomputed.
It should generally not be necessary to call this function.
|
overridevirtual |
Enable this ErrorMethod to be cloned to a new IK module.
Implements dart::dynamics::InverseKinematics::ErrorMethod.
|
overridevirtual |
Override this function with your implementation of computing the desired given the current transform and error vector.
If you want the desired transform to always be equal to the Target's transform, you can simply call ErrorMethod::computeDesiredTransform to implement this function.
Implements dart::dynamics::InverseKinematics::ErrorMethod.
|
overridevirtual |
Override this function with your implementation of the error vector computation.
The expectation is that the first three components of the vector will correspond to orientation error (in an angle-axis format) while the last three components correspond to translational error.
When implementing this function, you should assume that the Skeleton's current joint positions corresponds to the positions that you must use to compute the error. This function will only get called when an update is needed.
Implements dart::dynamics::InverseKinematics::ErrorMethod.
|
inherited |
This function is used to handle caching the error vector.
|
inherited |
Get the error bounds for orientation.
|
inherited |
Get the weights that will be applied to each angular component of the error vector.
|
inherited |
Get all the error bounds.
|
inherited |
Set the clamp that will be applied to the length of the error vector each iteration.
|
inherited |
Get the Properties of this ErrorMethod.
|
inherited |
Get the weights that will be applied to each component of the error vector.
|
inherited |
Get the error bounds for translation.
|
inherited |
Get the weights that will be applied to each linear component of the error vector.
|
inherited |
Get the name of this ErrorMethod.
InverseKinematics::TaskSpaceRegion::Properties dart::dynamics::InverseKinematics::TaskSpaceRegion::getTaskSpaceRegionProperties | ( | ) | const |
Get the Properties of this TaskSpaceRegion.
bool dart::dynamics::InverseKinematics::TaskSpaceRegion::isComputingFromCenter | ( | ) | const |
Get whether this TaskSpaceRegion is set to compute its error vector from the center of the region.
|
protectedinherited |
Remove an Observer from the list of Observers.
|
protectedinherited |
Send a destruction notification to all Observers.
This will cause all Observers to behave as if this Subject has been permanently deleted, so it should only be called when that behavior is desired.
|
inherited |
Set the error bounds for orientation.
|
inherited |
Set the error bounds for orientation.
|
inherited |
Set the weights that will be applied to each angular component of the error vector.
|
inherited |
Set all the error bounds.
|
inherited |
Set all the error bounds.
void dart::dynamics::InverseKinematics::TaskSpaceRegion::setComputeFromCenter | ( | bool | computeFromCenter | ) |
Set whether this TaskSpaceRegion should compute its error vector from the center of the region.
|
inherited |
Set the clamp that will be applied to the length of the error vector each iteration.
|
inherited |
Set the weights that will be applied to each component of the error vector.
|
inherited |
Set the error bounds for translation.
|
inherited |
Set the error bounds for translation.
|
inherited |
Set the weights that will be applied to each linear component of the error vector.
|
protectedinherited |
The properties of this ErrorMethod.
|
protectedinherited |
Pointer to the IK module of this ErrorMethod.
|
protectedinherited |
The last error vector computed by this ErrorMethod.
|
protectedinherited |
The last joint positions passed into this ErrorMethod.
|
protectedinherited |
Name of this error method.
|
mutableprotectedinherited |
List of current Observers.
|
protected |
Properties of this TaskSpaceRegion.