#include <InverseKinematicsBase.h>
|
| | InverseKinematicsBase ()=default |
| | default constructor More...
|
| |
| | InverseKinematicsBase (const InverseKinematicsSettings &settings) |
| | constructor with additional settings More...
|
| |
| virtual | ~InverseKinematicsBase ()=default |
| | default destructor More...
|
| |
| virtual bool | computeInverseKinematics (JointPositionsVector_t &ikSolutions, const RigidBodyPoseTpl &eeBasePose, const std::vector< size_t > &freeJoints)=0 |
| | compute inverse kinematics for an end-effector w.r.t robot base More...
|
| |
| virtual bool | computeInverseKinematics (JointPositionsVector_t &ikSolutions, const RigidBodyPoseTpl &eeWorldPose, const RigidBodyPoseTpl &baseWorldPose, const std::vector< size_t > &freeJoints)=0 |
| | compute inverse kinematics for an end-effector More...
|
| |
| virtual bool | computeInverseKinematicsCloseTo (JointPosition_t &ikSolution, const RigidBodyPoseTpl &eeWorldPose, const RigidBodyPoseTpl &baseWorldPose, const JointPosition_t &queryJointPositions, const std::vector< size_t > &freeJoints=std::vector< size_t >()) |
| | compute inverse kinematics for an end-effector More...
|
| |
| virtual bool | computeInverseKinematicsCloseTo (JointPosition_t &ikSolution, const RigidBodyPoseTpl &eeBasePose, const JointPosition_t &queryJointPositions, const std::vector< size_t > &freeJoints=std::vector< size_t >()) |
| | compute inverse kinematics for an end-effector More...
|
| |
| const InverseKinematicsSettings & | getSettings () const |
| |
| void | updateSettings (const InverseKinematicsSettings &settings) |
| |
◆ JointPosition_t
template<size_t NJOINTS, typename SCALAR = double>
◆ JointPositionsVector_t
template<size_t NJOINTS, typename SCALAR = double>
◆ RigidBodyPoseTpl
template<size_t NJOINTS, typename SCALAR = double>
◆ InverseKinematicsBase() [1/2]
template<size_t NJOINTS, typename SCALAR = double>
◆ InverseKinematicsBase() [2/2]
template<size_t NJOINTS, typename SCALAR = double>
constructor with additional settings
◆ ~InverseKinematicsBase()
template<size_t NJOINTS, typename SCALAR = double>
◆ computeInverseKinematics() [1/2]
template<size_t NJOINTS, typename SCALAR = double>
compute inverse kinematics for an end-effector w.r.t robot base
- Parameters
-
| ikSolutions | vector of all solutions to the inverse kinematics problem |
| eeBasePose | end-effector pose in base coordinates |
| freeJoints | vector of indices of the free joints |
- Returns
- true if solution found, false otherwise
◆ computeInverseKinematics() [2/2]
template<size_t NJOINTS, typename SCALAR = double>
compute inverse kinematics for an end-effector
- Parameters
-
| ikSolutions | vector of all solutions to the inverse kinematics problem |
| eeWorldPose | end-effector pose in world coordinates |
| baseWorldPose | base pose in world coordinates |
| freeJoints | vector of indices of the free joints |
- Returns
- true if solution found, false otherwise
◆ computeInverseKinematicsCloseTo() [1/2]
template<size_t NJOINTS, typename SCALAR = double>
compute inverse kinematics for an end-effector
- Parameters
-
| ikSolution | solution to the inverse kinematics problem which is closest to parameter 'queryJointPositions' |
| eeWorldPose | end-effector pose in world coordinates |
| baseWorldPose | base pose in world coordinates |
| freeJoints | vector of indices of the free joints |
- Returns
- true if solution found, false otherwise
◆ computeInverseKinematicsCloseTo() [2/2]
template<size_t NJOINTS, typename SCALAR = double>
compute inverse kinematics for an end-effector
- Parameters
-
| ikSolution | solution to the inverse kinematics problem which is closest to parameter 'queryJointPositions' |
| eeBasePose | end-effector pose in base coordinates |
| freeJoints | vector of indices of the free joints |
- Returns
- true if solution found, false otherwise
◆ getSettings()
template<size_t NJOINTS, typename SCALAR = double>
◆ updateSettings()
template<size_t NJOINTS, typename SCALAR = double>
◆ settings_
template<size_t NJOINTS, typename SCALAR = double>
The documentation for this class was generated from the following file: