experimental Inverse Kinematics for KUKA iiwa exposed in
shared memory api and pybullet. Will be extended for arbitrary bodies and with target orientation (besides target position)
This commit is contained in:
@@ -391,12 +391,18 @@ struct CalculateJacobianResultArgs
|
||||
double m_angularJacobian[3*MAX_DEGREE_OF_FREEDOM];
|
||||
};
|
||||
|
||||
enum EnumCalculateInverseKinematicsFlags
|
||||
{
|
||||
IK_HAS_TARGET_ORIENTATION=1,
|
||||
IK_HAS_CURRENT_JOINT_POSITIONS=2,
|
||||
};
|
||||
|
||||
struct CalculateInverseKinematicsArgs
|
||||
{
|
||||
int m_bodyUniqueId;
|
||||
double m_jointPositionsQ[MAX_DEGREE_OF_FREEDOM];
|
||||
// double m_jointPositionsQ[MAX_DEGREE_OF_FREEDOM];
|
||||
double m_targetPosition[3];
|
||||
double m_targetOrientation[4];//orientation represented as quaternion, x,y,z,w
|
||||
// double m_targetOrientation[4];//orientation represented as quaternion, x,y,z,w
|
||||
};
|
||||
|
||||
struct CalculateInverseKinematicsResultArgs
|
||||
|
||||
Reference in New Issue
Block a user