Drake
Drake C++ Documentation
DifferentialInverseKinematicsParameters Class Reference

Detailed Description

Contains parameters for differential inverse kinematics.

#include <drake/multibody/inverse_kinematics/differential_inverse_kinematics.h>

Public Member Functions

 DifferentialInverseKinematicsParameters (int num_positions, std::optional< int > num_velocities=std::nullopt)
 Constructor. More...
 
void AddLinearVelocityConstraint (const std::shared_ptr< solvers::LinearConstraint > constraint)
 Adds a linear velocity constraint. More...
 
void ClearLinearVelocityConstraints ()
 Clears all linear velocity constraints. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 DifferentialInverseKinematicsParameters (const DifferentialInverseKinematicsParameters &)=default
 
DifferentialInverseKinematicsParametersoperator= (const DifferentialInverseKinematicsParameters &)=default
 
 DifferentialInverseKinematicsParameters (DifferentialInverseKinematicsParameters &&)=default
 
DifferentialInverseKinematicsParametersoperator= (DifferentialInverseKinematicsParameters &&)=default
 
Getters.
double get_time_step () const
 
int get_num_positions () const
 
int get_num_velocities () const
 
const VectorX< double > & get_nominal_joint_position () const
 
const MatrixX< double > & get_joint_centering_gain () const
 
const Vector6< bool > & get_end_effector_velocity_flag () const
 
const std::optional< std::pair< VectorX< double >, VectorX< double > > > & get_joint_position_limits () const
 
const std::optional< std::pair< VectorX< double >, VectorX< double > > > & get_joint_velocity_limits () const
 
const std::optional< std::pair< VectorX< double >, VectorX< double > > > & get_joint_acceleration_limits () const
 
double get_maximum_scaling_to_report_stuck () const
 
double get_end_effector_angular_speed_limit () const
 
const std::optional< std::pair< Eigen::Vector3d, Eigen::Vector3d > > & get_end_effector_translational_velocity_limits () const
 
const std::vector< std::shared_ptr< solvers::LinearConstraint > > & get_linear_velocity_constraints () const
 
Setters.
void set_time_step (double dt)
 Sets time step to dt. More...
 
void set_nominal_joint_position (const Eigen::Ref< const VectorX< double >> &nominal_joint_position)
 Sets the nominal joint position. More...
 
void set_end_effector_velocity_flag (const Vector6< bool > &flag_E)
 Sets the end effector flags in the body frame. More...
 
void set_joint_centering_gain (const MatrixX< double > &K)
 Sets the joint centering gain, K, so that the joint centering command is attempting to achieve v_next = N⁺(q) * K * (q_nominal - q_current). More...
 
void set_joint_position_limits (const std::pair< VectorX< double >, VectorX< double >> &q_bounds)
 Sets the joint position limits. More...
 
void set_joint_velocity_limits (const std::pair< VectorX< double >, VectorX< double >> &v_bounds)
 Sets the joint velocity limits. More...
 
void set_joint_acceleration_limits (const std::pair< VectorX< double >, VectorX< double >> &vd_bounds)
 Sets the joint acceleration limits. More...
 
void set_maximum_scaling_to_report_stuck (double scaling)
 Sets the threshold for α below which the status returned is DifferentialInverseKinematicsStatus::kStuck. More...
 
void set_end_effector_angular_speed_limit (double speed)
 When calling DoDifferentialInverseKinematics with a desired end-effector pose, this limits the magnitude of the angular velocity vector. More...
 
void set_end_effector_translational_velocity_limits (const Eigen::Ref< const Eigen::Vector3d > &lower, const Eigen::Ref< const Eigen::Vector3d > &upper)
 When calling DoDifferentialInverseKinematics with a desired end-effector pose, this sets limits on the translational velocity. More...
 

Constructor & Destructor Documentation

◆ DifferentialInverseKinematicsParameters() [1/3]

◆ DifferentialInverseKinematicsParameters() [2/3]

◆ DifferentialInverseKinematicsParameters() [3/3]

DifferentialInverseKinematicsParameters ( int  num_positions,
std::optional< int num_velocities = std::nullopt 
)

Constructor.

Initializes the nominal joint position to zeros of size num_positions. The time step is initialized to 1. The end effector flags are initialized to True. The joint centering gains are initialized to zero. All constraints are initialized to nullopt.

Parameters
num_positionsNumber of generalized positions.
num_velocitiesNumber of generalized velocities (by default it will be set to num_positions).

Member Function Documentation

◆ AddLinearVelocityConstraint()

void AddLinearVelocityConstraint ( const std::shared_ptr< solvers::LinearConstraint constraint)

Adds a linear velocity constraint.

Parameters
linear_velocity_constraintA linear constraint on joint velocities.
Exceptions
std::exceptionif constraint->num_vars != this->get_num_velocities().

◆ ClearLinearVelocityConstraints()

void ClearLinearVelocityConstraints ( )

Clears all linear velocity constraints.

◆ get_end_effector_angular_speed_limit()

double get_end_effector_angular_speed_limit ( ) const

◆ get_end_effector_translational_velocity_limits()

const std::optional<std::pair<Eigen::Vector3d, Eigen::Vector3d> >& get_end_effector_translational_velocity_limits ( ) const

◆ get_end_effector_velocity_flag()

const Vector6<bool>& get_end_effector_velocity_flag ( ) const

◆ get_joint_acceleration_limits()

const std::optional<std::pair<VectorX<double>, VectorX<double> > >& get_joint_acceleration_limits ( ) const

◆ get_joint_centering_gain()

const MatrixX<double>& get_joint_centering_gain ( ) const

◆ get_joint_position_limits()

const std::optional<std::pair<VectorX<double>, VectorX<double> > >& get_joint_position_limits ( ) const

◆ get_joint_velocity_limits()

const std::optional<std::pair<VectorX<double>, VectorX<double> > >& get_joint_velocity_limits ( ) const

◆ get_linear_velocity_constraints()

const std::vector<std::shared_ptr<solvers::LinearConstraint> >& get_linear_velocity_constraints ( ) const

◆ get_maximum_scaling_to_report_stuck()

double get_maximum_scaling_to_report_stuck ( ) const

◆ get_nominal_joint_position()

const VectorX<double>& get_nominal_joint_position ( ) const

◆ get_num_positions()

int get_num_positions ( ) const

◆ get_num_velocities()

int get_num_velocities ( ) const

◆ get_time_step()

double get_time_step ( ) const

◆ operator=() [1/2]

◆ operator=() [2/2]

◆ set_end_effector_angular_speed_limit()

void set_end_effector_angular_speed_limit ( double  speed)

When calling DoDifferentialInverseKinematics with a desired end-effector pose, this limits the magnitude of the angular velocity vector.

◆ set_end_effector_translational_velocity_limits()

void set_end_effector_translational_velocity_limits ( const Eigen::Ref< const Eigen::Vector3d > &  lower,
const Eigen::Ref< const Eigen::Vector3d > &  upper 
)

When calling DoDifferentialInverseKinematics with a desired end-effector pose, this sets limits on the translational velocity.

◆ set_end_effector_velocity_flag()

void set_end_effector_velocity_flag ( const Vector6< bool > &  flag_E)

Sets the end effector flags in the body frame.

If a spatial velocity flag is set to false, it will not be included in the differential IK formulation.

◆ set_joint_acceleration_limits()

void set_joint_acceleration_limits ( const std::pair< VectorX< double >, VectorX< double >> &  vd_bounds)

Sets the joint acceleration limits.

Parameters
q_boundsThe first element is the lower bound, and the second is the upper bound.
Exceptions
std::exceptionif the first or second element of q_bounds has the wrong dimension or any element of the second element is smaller than its corresponding part in the first element.

◆ set_joint_centering_gain()

void set_joint_centering_gain ( const MatrixX< double > &  K)

Sets the joint centering gain, K, so that the joint centering command is attempting to achieve v_next = N⁺(q) * K * (q_nominal - q_current).

Precondition
K must be num_positions x num_positions.

◆ set_joint_position_limits()

void set_joint_position_limits ( const std::pair< VectorX< double >, VectorX< double >> &  q_bounds)

Sets the joint position limits.

Parameters
q_boundsThe first element is the lower bound, and the second is the upper bound.
Exceptions
std::exceptionif the first or second element of q_bounds has the wrong dimension or any element of the second element is smaller than its corresponding part in the first element.

◆ set_joint_velocity_limits()

void set_joint_velocity_limits ( const std::pair< VectorX< double >, VectorX< double >> &  v_bounds)

Sets the joint velocity limits.

Parameters
q_boundsThe first element is the lower bound, and the second is the upper bound.
Exceptions
std::exceptionif the first or second element of q_bounds has the wrong dimension or any element of the second element is smaller than its corresponding part in the first element.

◆ set_maximum_scaling_to_report_stuck()

void set_maximum_scaling_to_report_stuck ( double  scaling)

Sets the threshold for α below which the status returned is DifferentialInverseKinematicsStatus::kStuck.

α is the scaling of the commanded spatial velocity, so when α is small, it means that the actual spatial velocity magnitude will be small proportional to the commanded.
Default: 0.01.

◆ set_nominal_joint_position()

void set_nominal_joint_position ( const Eigen::Ref< const VectorX< double >> &  nominal_joint_position)

Sets the nominal joint position.

Exceptions
std::exceptionif nominal_joint_position's dimension differs.

◆ set_time_step()

void set_time_step ( double  dt)

Sets time step to dt.

Exceptions
std::exceptionif dt <= 0.

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