|
| | IKCostEvaluator (size_t eeInd, const Eigen::Matrix3d &Qpos=Eigen::Matrix3d::Identity(), const Eigen::Matrix3d &Qrot=Eigen::Matrix3d::Identity()) |
| |
| | IKCostEvaluator (const std::string &costFunctionPath, const std::string &termTaskspaceName, const bool verbose=false) |
| |
| | IKCostEvaluator (const std::string &costFunctionPath, const std::string &termTaskspaceName, const std::string &termJointPosName, const bool verbose=false) |
| |
| | ~IKCostEvaluator () override=default |
| |
| void | setOptVector (std::shared_ptr< ct::optcon::tpl::OptVector< SCALAR >> optVector) |
| | opt vector needs to be set by NLP solver More...
|
| |
| void | setRegularizer (std::shared_ptr< IKRegularizerBase > reg) |
| |
| ct::rbd::RigidBodyPose | getTargetPose () |
| |
| void | setTargetPose (const ct::rbd::RigidBodyPose &rbdPose) |
| |
| void | setTargetPose (const core::StateVector< 3 > &w_pos_des, const Eigen::Quaterniond &w_q_des) |
| |
| void | setTargetPose (const core::StateVector< 3 > &w_pos_des, const Eigen::Matrix3d &eulerXyz) |
| |
| virtual SCALAR | eval () override |
| | evaluate cost function More...
|
| |
| virtual void | evalGradient (size_t grad_length, Eigen::Map< Eigen::Matrix< SCALAR, Eigen::Dynamic, 1 >> &grad) override |
| | retrieve first-order derivative More...
|
| |
| virtual void | getSparsityPatternHessian (Eigen::VectorXi &iRow, Eigen::VectorXi &jCol) override |
| | create sparsity pattern for the hessian (simply fill up completely) More...
|
| |
| void | sparseHessianValues (const Eigen::VectorXd &jointAngles, const Eigen::VectorXd &obj_fac, Eigen::VectorXd &hes) override |
| | retrieve second order derivative More...
|
| |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW | DiscreteCostEvaluatorBase ()=default |
| |
| virtual | ~DiscreteCostEvaluatorBase ()=default |
| |
template<typename KINEMATICS, typename SCALAR = double>
class ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >
Inverse Kinematics cost evaluator for NLP.
- Warning
- currently this works only with fix-base systems