Go to the documentation of this file.    1 #ifndef AIKIDO_ROBOT_IKFAST_HPP_ 
    2 #define AIKIDO_ROBOT_IKFAST_HPP_ 
    7 #include <dart/dart.hpp> 
   20       ::dart::dynamics::MetaSkeletonPtr arm,
 
   21       ::dart::dynamics::BodyNodePtr endEffector,
 
   23       const std::string& binaryPath);
 
   27       const Eigen::Isometry3d& targetPose,
 
   28       const size_t maxSolutions) 
const override;
 
   31   ::dart::dynamics::MetaSkeletonPtr 
mArm;
 
   41 #endif // AIKIDO_ROBOT_IKFAST_HPP_ 
 
 
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
 
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
 
statespace::dart::ConstMetaSkeletonStateSpacePtr mArmSpace
Definition: IkFast.hpp:33
 
IkFast(::dart::dynamics::MetaSkeletonPtr arm, ::dart::dynamics::BodyNodePtr endEffector, statespace::dart::ConstMetaSkeletonStateSpacePtr armSpace, const std::string &binaryPath)
 
dart::dynamics::SharedLibraryIkFast * mIkFastSolverPtr
Definition: IkFast.hpp:35
 
::dart::dynamics::BodyNodePtr mEndEffector
Definition: IkFast.hpp:32
 
::dart::dynamics::MetaSkeletonPtr mArm
Definition: IkFast.hpp:31
 
Interface for IK solvers used with the Robot class.
Definition: InverseKinematics.hpp:8
 
Analytic IK solver that uses pre-compiled IkFast binary.
Definition: IkFast.hpp:16
 
std::vector< Eigen::VectorXd > getSolutions(const Eigen::Isometry3d &targetPose, const size_t maxSolutions) const override
Returns a set of IK solutions for the given pose.