Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes
constrained_ik::Constrained_IK Class Reference

Damped Least-Squares Inverse Kinematic Solution. More...

#include <constrained_ik.h>

Inheritance diagram for constrained_ik::Constrained_IK:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void addConstraint (Constraint *constraint)
 Add a new constraint to this IK solver.
virtual void calcInvKin (const Eigen::Affine3d &pose, const Eigen::VectorXd &joint_seed, Eigen::VectorXd &joint_angles)
bool checkInitialized () const
 Checks to see if object is initialized (ie: init() has been called)
void clearConstraintList ()
 Delete all constraints.
 Constrained_IK ()
bool getJointNames (std::vector< std::string > &names) const
 Getter for joint names.
double getJointUpdateGain () const
 Getter for joint_update_gain_ (gain used to scale joint diff in IK loop)
double getJtCnvTolerance () const
 Getter for joint_convergence_tol_ (convergence criteria in IK loop) Used to check if solution is progressing or has settled.
const basic_kin::BasicKingetKin () const
 Getter for kinematics object.
bool getLinkNames (std::vector< std::string > &names) const
 Getter for link names.
unsigned int getMaxIter () const
 Getter for max_iter_ (maximum allowable iterations in IK loop)
const SolverStategetState () const
 Getter for latest solver state.
void init (const urdf::Model &robot, const std::string &base_name, const std::string &tip_name)
 Initializes object with robot info.
virtual void init (const basic_kin::BasicKin &kin)
 Initializes object with kinematic model of robot.
bool linkTransforms (const Eigen::VectorXd &joints, std::vector< KDL::Frame > &poses, const std::vector< std::string > link_names=std::vector< std::string >()) const
unsigned int numJoints () const
 Getter for BasicKin numJoints.
void setJointUpdateGain (const double gain)
 Setter for joint_update_gain_ (gain used to scale joint diff in IK loop)
void setJtCnvTolerance (const double jt_cnv_tol)
 Setter for joint_convergence_tol_ (convergence criteria in IK loop)
void setMaxIter (const unsigned int max_iter)
 Setter for man_iter_ (maximum allowable iterations in IK loop)
virtual ~Constrained_IK ()

Static Public Member Functions

static double rangedAngle (double angle)
 Translates an angle to lie between +/-PI.

Protected Member Functions

virtual Eigen::VectorXd calcConstraintError ()
 Pure definition for calculating constraint error.
virtual Eigen::MatrixXd calcConstraintJacobian ()
 Pure definition for calculating Jacobian.
virtual bool checkStatus () const
void clipToJointLimits (Eigen::VectorXd &joints)
virtual void reset (const Eigen::Affine3d &goal, const Eigen::VectorXd &joint_seed)
virtual void update (const Eigen::VectorXd &joints)

Protected Attributes

ConstraintGroup constraints_
bool debug_
bool initialized_
std::vector< Eigen::VectorXd > iteration_path_
double joint_convergence_tol_
double joint_update_gain_
basic_kin::BasicKin kin_
unsigned int max_iter_
SolverState state_

Detailed Description

Damped Least-Squares Inverse Kinematic Solution.

Definition at line 38 of file constrained_ik.h.


Constructor & Destructor Documentation

Definition at line 30 of file constrained_ik.cpp.

virtual constrained_ik::Constrained_IK::~Constrained_IK ( ) [inline, virtual]

Definition at line 43 of file constrained_ik.h.


Member Function Documentation

virtual void constrained_ik::Constrained_IK::addConstraint ( Constraint constraint) [inline, virtual]

Add a new constraint to this IK solver.

Parameters:
constraintConstraint to limit IK solution

Definition at line 54 of file constrained_ik.h.

Eigen::VectorXd constrained_ik::Constrained_IK::calcConstraintError ( ) [protected, virtual]

Pure definition for calculating constraint error.

Returns:
Error vector (b-input in calcPInv)

Definition at line 39 of file constrained_ik.cpp.

Eigen::MatrixXd constrained_ik::Constrained_IK::calcConstraintJacobian ( ) [protected, virtual]

Pure definition for calculating Jacobian.

Returns:
Jacobian matrix (A-input in calcPInv)

Definition at line 44 of file constrained_ik.cpp.

void constrained_ik::Constrained_IK::calcInvKin ( const Eigen::Affine3d &  pose,
const Eigen::VectorXd &  joint_seed,
Eigen::VectorXd &  joint_angles 
) [virtual]

Definition at line 49 of file constrained_ik.cpp.

Checks to see if object is initialized (ie: init() has been called)

Returns:
True if object is initialized

Definition at line 62 of file constrained_ik.h.

bool constrained_ik::Constrained_IK::checkStatus ( ) const [protected, virtual]

Definition at line 84 of file constrained_ik.cpp.

Delete all constraints.

Definition at line 108 of file constrained_ik.cpp.

void constrained_ik::Constrained_IK::clipToJointLimits ( Eigen::VectorXd &  joints) [protected]

Definition at line 113 of file constrained_ik.cpp.

bool constrained_ik::Constrained_IK::getJointNames ( std::vector< std::string > &  names) const [inline]

Getter for joint names.

Parameters:
namesOutput vector of strings naming all joints in robot
Returns:
True if BasicKin object is initialized

Definition at line 72 of file constrained_ik.h.

Getter for joint_update_gain_ (gain used to scale joint diff in IK loop)

Returns:
Value of joint_update_gain_

Definition at line 77 of file constrained_ik.h.

Getter for joint_convergence_tol_ (convergence criteria in IK loop) Used to check if solution is progressing or has settled.

Returns:
Value of joint_convergence_tol_

Definition at line 83 of file constrained_ik.h.

Getter for kinematics object.

Returns:
Reference to active kinematics object

Definition at line 88 of file constrained_ik.h.

bool constrained_ik::Constrained_IK::getLinkNames ( std::vector< std::string > &  names) const [inline]

Getter for link names.

Parameters:
namesOutput vector of strings naming all links in robot
Returns:
True is BasicKin object is initialized

Definition at line 94 of file constrained_ik.h.

unsigned int constrained_ik::Constrained_IK::getMaxIter ( ) const [inline]

Getter for max_iter_ (maximum allowable iterations in IK loop)

Returns:
Value of max_iter_

Definition at line 99 of file constrained_ik.h.

Getter for latest solver state.

Returns:
Latest solver state

Definition at line 104 of file constrained_ik.h.

void constrained_ik::Constrained_IK::init ( const urdf::Model robot,
const std::string &  base_name,
const std::string &  tip_name 
)

Initializes object with robot info.

Parameters:
robotRobot urdf information
base_nameName of base link
tip_nameName of tip link

Definition at line 129 of file constrained_ik.cpp.

Initializes object with kinematic model of robot.

Parameters:
kinBasicKin object with robot info

Definition at line 138 of file constrained_ik.cpp.

bool constrained_ik::Constrained_IK::linkTransforms ( const Eigen::VectorXd &  joints,
std::vector< KDL::Frame > &  poses,
const std::vector< std::string >  link_names = std::vector<std::string>() 
) const [inline]

Definition at line 46 of file constrained_ik.h.

unsigned int constrained_ik::Constrained_IK::numJoints ( ) const [inline]

Getter for BasicKin numJoints.

Returns:
Number of variable joints in robot

Definition at line 121 of file constrained_ik.h.

double constrained_ik::Constrained_IK::rangedAngle ( double  angle) [static]

Translates an angle to lie between +/-PI.

Parameters:
angleInput angle, radians
Returns:
Output angle within range of +/- PI

Definition at line 148 of file constrained_ik.cpp.

void constrained_ik::Constrained_IK::reset ( const Eigen::Affine3d &  goal,
const Eigen::VectorXd &  joint_seed 
) [protected, virtual]

Definition at line 156 of file constrained_ik.cpp.

void constrained_ik::Constrained_IK::setJointUpdateGain ( const double  gain) [inline]

Setter for joint_update_gain_ (gain used to scale joint diff in IK loop)

Parameters:
gainNew value for joint_update_gain_

Definition at line 132 of file constrained_ik.h.

void constrained_ik::Constrained_IK::setJtCnvTolerance ( const double  jt_cnv_tol) [inline]

Setter for joint_convergence_tol_ (convergence criteria in IK loop)

Parameters:
jt_cnv_tolnew value for joint_convergence_tol_

Definition at line 137 of file constrained_ik.h.

void constrained_ik::Constrained_IK::setMaxIter ( const unsigned int  max_iter) [inline]

Setter for man_iter_ (maximum allowable iterations in IK loop)

Parameters:
max_iterNew value for max_iter_

Definition at line 142 of file constrained_ik.h.

void constrained_ik::Constrained_IK::update ( const Eigen::VectorXd &  joints) [protected, virtual]

Definition at line 169 of file constrained_ik.cpp.


Member Data Documentation

Definition at line 153 of file constrained_ik.h.

Definition at line 160 of file constrained_ik.h.

Definition at line 156 of file constrained_ik.h.

std::vector<Eigen::VectorXd> constrained_ik::Constrained_IK::iteration_path_ [protected]

Definition at line 161 of file constrained_ik.h.

Definition at line 150 of file constrained_ik.h.

Definition at line 142 of file constrained_ik.h.

Definition at line 158 of file constrained_ik.h.

Definition at line 149 of file constrained_ik.h.

Definition at line 157 of file constrained_ik.h.


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


constrained_ik
Author(s): Chris Lewis , Jeremy Zoss , Dan Solomon
autogenerated on Mon Oct 6 2014 00:52:27