$search

reem_kinematics_constraint_aware::IkSolver Class Reference

#include <ik_solver.h>

List of all members.

Public Types

enum  EndpointCoupling { Position = 1, Orientation = 2, Pose = Position | Orientation }
 

Kinematic coupling with reference frame.

More...
typedef std::vector
< EndpointCoupling
EndpointCouplingList
typedef std::vector< std::string > EndpointNameList

Public Member Functions

 IkSolver (const KDL::Chain &chain)
 Conveniece constructor for the particular case of solving for the pose of a single endpoint.
 IkSolver (const KDL::Tree &tree, const EndpointNameList &endpoint_names, const EndpointCouplingList &endpoint_couplings)
void setEpsilon (double eps)
void setJointPositionLimits (const Eigen::VectorXd &q_min, const Eigen::VectorXd &q_max)
void setJointSpaceWeights (const Eigen::VectorXd &Wq)
 Contains diagonal elements of matrix (nondiagonal not yet supported).
void setMaxDeltaPosJoint (double delta_joint_pos_max)
void setMaxDeltaPosTask (double delta_twist_max)
void setMaxIterations (std::size_t max_iter)
void setPosture (const KDL::JntArray &q_posture)
void setTaskSpaceWeights (const Eigen::VectorXd &Wq)
 Contains diagonal elements of matrix (nondiagonal not yet supported).
void setVelocityIkGain (double velik_gain)
bool solve (const KDL::JntArray &q_current, const KDL::Frame &x_desired, KDL::JntArray &q_next)
bool solve (const KDL::JntArray &q_current, const std::vector< KDL::Frame > &x_desired, KDL::JntArray &q_next)
virtual ~IkSolver ()

Private Types

typedef std::vector< std::size_t > CoupledDirections
typedef
KDL::TreeFkSolverPos_recursive 
FkSolver
 0,1,2 -> xyz translation, 3,4,5 -> xyz rotation
typedef boost::scoped_ptr
< FkSolver
FkSolverPtr
typedef KDL::MatrixInverter
< Eigen::MatrixXd > 
Inverter
typedef boost::scoped_ptr
< Inverter
InverterPtr
typedef KDL::TreeJntToJacSolver JacSolver
typedef boost::scoped_ptr
< JacSolver
JacSolverPtr
typedef std::map< std::string,
int > 
JointNameToIndexMap

Private Member Functions

void init (const KDL::Tree &tree, const std::vector< std::string > &endpoint_names, const std::vector< EndpointCoupling > &endpoint_couplings)
void updateDeltaTwist (const KDL::JntArray &q, const std::vector< KDL::Frame > &x_desired)
void updateJacobian (const KDL::JntArray &q)

Private Attributes

std::vector< CoupledDirectionscoupled_dirs_
double delta_joint_pos_max_
Eigen::VectorXd delta_q_
Eigen::VectorXd delta_twist_
double delta_twist_max_
std::vector< std::string > endpoint_names_
double eps_
FkSolverPtr fk_solver_
 Forward kinematics solver.
Eigen::MatrixXd identity_qdim_
InverterPtr inverter_
 SVD matrix inverter/solver.
JacSolverPtr jac_solver_
 Jacobian solver.
Eigen::MatrixXd jacobian_
KDL::Jacobian jacobian_tmp_
JointNameToIndexMap joint_name_to_idx_
 Map from joint names to KDL tree indices // TODO: Remove???
boost::scoped_ptr
< JointPositionLimitsAvoider
limits_avoider_
std::size_t max_iter_
Eigen::MatrixXd nullspace_projector_
KDL::JntArray q_posture_
Eigen::VectorXd q_tmp_
double velik_gain_
Eigen::VectorXd Wx_
 Diagonal of task-space weight matrix.

Detailed Description

Definition at line 153 of file ik_solver.h.


Member Typedef Documentation

typedef std::vector<std::size_t> reem_kinematics_constraint_aware::IkSolver::CoupledDirections [private]

Definition at line 199 of file ik_solver.h.

Definition at line 165 of file ik_solver.h.

Definition at line 164 of file ik_solver.h.

0,1,2 -> xyz translation, 3,4,5 -> xyz rotation

Definition at line 200 of file ik_solver.h.

Definition at line 201 of file ik_solver.h.

Definition at line 204 of file ik_solver.h.

Definition at line 205 of file ik_solver.h.

Definition at line 202 of file ik_solver.h.

Definition at line 203 of file ik_solver.h.

typedef std::map<std::string, int> reem_kinematics_constraint_aware::IkSolver::JointNameToIndexMap [private]

Definition at line 206 of file ik_solver.h.


Member Enumeration Documentation

Kinematic coupling with reference frame.

Enumerator:
Position 
Orientation 
Pose 

Definition at line 157 of file ik_solver.h.


Constructor & Destructor Documentation

IkSolver::IkSolver ( const KDL::Tree tree,
const EndpointNameList endpoint_names,
const EndpointCouplingList endpoint_couplings 
)

Definition at line 51 of file ik_solver.cpp.

IkSolver::IkSolver ( const KDL::Chain chain  ) 

Conveniece constructor for the particular case of solving for the pose of a single endpoint.

Definition at line 58 of file ik_solver.cpp.

IkSolver::~IkSolver (  )  [virtual]

Definition at line 72 of file ik_solver.cpp.


Member Function Documentation

void IkSolver::init ( const KDL::Tree tree,
const std::vector< std::string > &  endpoint_names,
const std::vector< EndpointCoupling > &  endpoint_couplings 
) [private]

Definition at line 74 of file ik_solver.cpp.

void reem_kinematics_constraint_aware::IkSolver::setEpsilon ( double  eps  )  [inline]

Definition at line 192 of file ik_solver.h.

void reem_kinematics_constraint_aware::IkSolver::setJointPositionLimits ( const Eigen::VectorXd &  q_min,
const Eigen::VectorXd &  q_max 
) [inline]

Definition at line 247 of file ik_solver.h.

void reem_kinematics_constraint_aware::IkSolver::setJointSpaceWeights ( const Eigen::VectorXd &  Wq  )  [inline]

Contains diagonal elements of matrix (nondiagonal not yet supported).

Definition at line 195 of file ik_solver.h.

void reem_kinematics_constraint_aware::IkSolver::setMaxDeltaPosJoint ( double  delta_joint_pos_max  )  [inline]

Definition at line 190 of file ik_solver.h.

void reem_kinematics_constraint_aware::IkSolver::setMaxDeltaPosTask ( double  delta_twist_max  )  [inline]

Definition at line 189 of file ik_solver.h.

void reem_kinematics_constraint_aware::IkSolver::setMaxIterations ( std::size_t  max_iter  )  [inline]

Definition at line 193 of file ik_solver.h.

void reem_kinematics_constraint_aware::IkSolver::setPosture ( const KDL::JntArray &  q_posture  )  [inline]
Note:
Copies values.

Definition at line 194 of file ik_solver.h.

void reem_kinematics_constraint_aware::IkSolver::setTaskSpaceWeights ( const Eigen::VectorXd &  Wq  )  [inline]

Contains diagonal elements of matrix (nondiagonal not yet supported).

Definition at line 196 of file ik_solver.h.

void reem_kinematics_constraint_aware::IkSolver::setVelocityIkGain ( double  velik_gain  )  [inline]

Definition at line 191 of file ik_solver.h.

bool reem_kinematics_constraint_aware::IkSolver::solve ( const KDL::JntArray &  q_current,
const KDL::Frame x_desired,
KDL::JntArray &  q_next 
) [inline]

Conveniece overload for the particular case of solving for the pose of a single endpoint.

Note:
This method will allocate heap memory for constructing a std::vector<KDL::Frame>.

Definition at line 253 of file ik_solver.h.

bool IkSolver::solve ( const KDL::JntArray &  q_current,
const std::vector< KDL::Frame > &  x_desired,
KDL::JntArray &  q_next 
)

Definition at line 157 of file ik_solver.cpp.

void IkSolver::updateDeltaTwist ( const KDL::JntArray &  q,
const std::vector< KDL::Frame > &  x_desired 
) [private]

Definition at line 238 of file ik_solver.cpp.

void IkSolver::updateJacobian ( const KDL::JntArray &  q  )  [private]

Definition at line 262 of file ik_solver.cpp.


Member Data Documentation

Definition at line 213 of file ik_solver.h.

Definition at line 231 of file ik_solver.h.

Definition at line 217 of file ik_solver.h.

Definition at line 216 of file ik_solver.h.

Definition at line 230 of file ik_solver.h.

Definition at line 212 of file ik_solver.h.

Definition at line 233 of file ik_solver.h.

Forward kinematics solver.

Definition at line 208 of file ik_solver.h.

Definition at line 226 of file ik_solver.h.

SVD matrix inverter/solver.

Definition at line 210 of file ik_solver.h.

Jacobian solver.

Definition at line 209 of file ik_solver.h.

Definition at line 220 of file ik_solver.h.

Definition at line 221 of file ik_solver.h.

Map from joint names to KDL tree indices // TODO: Remove???

Definition at line 214 of file ik_solver.h.

Definition at line 236 of file ik_solver.h.

Definition at line 234 of file ik_solver.h.

Definition at line 225 of file ik_solver.h.

Definition at line 227 of file ik_solver.h.

Definition at line 218 of file ik_solver.h.

Definition at line 232 of file ik_solver.h.

Diagonal of task-space weight matrix.

Definition at line 222 of file ik_solver.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


reem_kinematics_constraint_aware
Author(s): Adolfo Rodriguez Tsouroukdissian, Hilario Tome.
autogenerated on Fri Mar 1 17:27:14 2013