DART  6.10.1
dart::dynamics::InverseKinematics::ErrorMethod::Properties Struct Reference

The Properties struct contains settings that are commonly used by methods that compute error for inverse kinematics. More...

#include <InverseKinematics.hpp>

Inheritance diagram for dart::dynamics::InverseKinematics::ErrorMethod::Properties:
dart::dynamics::InverseKinematics::TaskSpaceRegion::Properties

Public Member Functions

 Properties (const Bounds &_bounds=Bounds(Eigen::Vector6d::Constant(-DefaultIKTolerance), Eigen::Vector6d::Constant(DefaultIKTolerance)), double _errorClamp=DefaultIKErrorClamp, const Eigen::Vector6d &_errorWeights=Eigen::compose(Eigen::Vector3d::Constant(DefaultIKAngularWeight), Eigen::Vector3d::Constant(DefaultIKLinearWeight)))
 Default constructor. More...
 

Public Attributes

std::pair< Eigen::Vector6d, Eigen::Vector6dmBounds
 Bounds that define the acceptable range of the Node's transform relative to its target frame. More...
 
double mErrorLengthClamp
 The error vector will be clamped to this length with each iteration. More...
 
Eigen::Vector6d mErrorWeights
 These weights will be applied to the error vector component-wise. More...
 

Detailed Description

The Properties struct contains settings that are commonly used by methods that compute error for inverse kinematics.

Constructor & Destructor Documentation

◆ Properties()

dart::dynamics::InverseKinematics::ErrorMethod::Properties::Properties ( const Bounds _bounds = Bounds(            Eigen::Vector6d::Constant(-DefaultIKTolerance),            Eigen::Vector6d::Constant(DefaultIKTolerance)),
double  _errorClamp = DefaultIKErrorClamp,
const Eigen::Vector6d _errorWeights = Eigen::compose(            Eigen::Vector3d::Constant(DefaultIKAngularWeight),            Eigen::Vector3d::Constant(DefaultIKLinearWeight)) 
)

Default constructor.

Member Data Documentation

◆ mBounds

std::pair<Eigen::Vector6d, Eigen::Vector6d> dart::dynamics::InverseKinematics::ErrorMethod::Properties::mBounds

Bounds that define the acceptable range of the Node's transform relative to its target frame.

◆ mErrorLengthClamp

double dart::dynamics::InverseKinematics::ErrorMethod::Properties::mErrorLengthClamp

The error vector will be clamped to this length with each iteration.

This is used to enforce sane behavior, even when there are extremely large error vectors.

◆ mErrorWeights

Eigen::Vector6d dart::dynamics::InverseKinematics::ErrorMethod::Properties::mErrorWeights

These weights will be applied to the error vector component-wise.

This allows you to set some components of error as more important than others, or to scale their coordinate spaces. For example, you will often want the first three components (orientation error) to have smaller weights than the last three components (translation error).