#include <ik_solver.h>
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::Tree &tree, const EndpointNameList &endpoint_names, const EndpointCouplingList &endpoint_couplings) | |
IkSolver (const KDL::Chain &chain) | |
Conveniece constructor for the particular case of solving for the pose of a single endpoint. | |
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 std::vector< KDL::Frame > &x_desired, KDL::JntArray &q_next) |
bool | solve (const KDL::JntArray &q_current, const 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< CoupledDirections > | coupled_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. |
Definition at line 153 of file ik_solver.h.
typedef std::vector<std::size_t> reem_kinematics_constraint_aware::IkSolver::CoupledDirections [private] |
Definition at line 199 of file ik_solver.h.
typedef std::vector<EndpointCoupling> reem_kinematics_constraint_aware::IkSolver::EndpointCouplingList |
Definition at line 165 of file ik_solver.h.
typedef std::vector<std::string> reem_kinematics_constraint_aware::IkSolver::EndpointNameList |
Definition at line 164 of file ik_solver.h.
typedef KDL::TreeFkSolverPos_recursive reem_kinematics_constraint_aware::IkSolver::FkSolver [private] |
0,1,2 -> xyz translation, 3,4,5 -> xyz rotation
Definition at line 200 of file ik_solver.h.
typedef boost::scoped_ptr<FkSolver> reem_kinematics_constraint_aware::IkSolver::FkSolverPtr [private] |
Definition at line 201 of file ik_solver.h.
typedef KDL::MatrixInverter<Eigen::MatrixXd> reem_kinematics_constraint_aware::IkSolver::Inverter [private] |
Definition at line 204 of file ik_solver.h.
typedef boost::scoped_ptr<Inverter> reem_kinematics_constraint_aware::IkSolver::InverterPtr [private] |
Definition at line 205 of file ik_solver.h.
typedef KDL::TreeJntToJacSolver reem_kinematics_constraint_aware::IkSolver::JacSolver [private] |
Definition at line 202 of file ik_solver.h.
typedef boost::scoped_ptr<JacSolver> reem_kinematics_constraint_aware::IkSolver::JacSolverPtr [private] |
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.
Kinematic coupling with reference frame.
Definition at line 157 of file ik_solver.h.
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.
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] |
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 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.
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.
Definition at line 253 of file ik_solver.h.
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.
Definition at line 213 of file ik_solver.h.
double reem_kinematics_constraint_aware::IkSolver::delta_joint_pos_max_ [private] |
Definition at line 231 of file ik_solver.h.
Eigen::VectorXd reem_kinematics_constraint_aware::IkSolver::delta_q_ [private] |
Definition at line 217 of file ik_solver.h.
Eigen::VectorXd reem_kinematics_constraint_aware::IkSolver::delta_twist_ [private] |
Definition at line 216 of file ik_solver.h.
double reem_kinematics_constraint_aware::IkSolver::delta_twist_max_ [private] |
Definition at line 230 of file ik_solver.h.
std::vector<std::string> reem_kinematics_constraint_aware::IkSolver::endpoint_names_ [private] |
Definition at line 212 of file ik_solver.h.
double reem_kinematics_constraint_aware::IkSolver::eps_ [private] |
Definition at line 233 of file ik_solver.h.
Forward kinematics solver.
Definition at line 208 of file ik_solver.h.
Eigen::MatrixXd reem_kinematics_constraint_aware::IkSolver::identity_qdim_ [private] |
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.
Eigen::MatrixXd reem_kinematics_constraint_aware::IkSolver::jacobian_ [private] |
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.
boost::scoped_ptr<JointPositionLimitsAvoider> reem_kinematics_constraint_aware::IkSolver::limits_avoider_ [private] |
Definition at line 236 of file ik_solver.h.
std::size_t reem_kinematics_constraint_aware::IkSolver::max_iter_ [private] |
Definition at line 234 of file ik_solver.h.
Eigen::MatrixXd reem_kinematics_constraint_aware::IkSolver::nullspace_projector_ [private] |
Definition at line 225 of file ik_solver.h.
KDL::JntArray reem_kinematics_constraint_aware::IkSolver::q_posture_ [private] |
Definition at line 227 of file ik_solver.h.
Eigen::VectorXd reem_kinematics_constraint_aware::IkSolver::q_tmp_ [private] |
Definition at line 218 of file ik_solver.h.
double reem_kinematics_constraint_aware::IkSolver::velik_gain_ [private] |
Definition at line 232 of file ik_solver.h.
Eigen::VectorXd reem_kinematics_constraint_aware::IkSolver::Wx_ [private] |
Diagonal of task-space weight matrix.
Definition at line 222 of file ik_solver.h.