Function signature changed to allow forward kinematics to calculate any joint's pose

This commit is contained in:
Derek Witcpalek
2020-04-26 12:48:42 -04:00
parent 3a2c3bb2cc
commit 719dcc9ac3

View File

@@ -41,7 +41,7 @@ class ArmRepresentation
public:
ArmRepresentation(const KDL::Frame &base_pose = KDL::Frame(KDL::Rotation::Quaternion(0, 0, 0, 1), KDL::Vector(0.3, 0.92, 0.9))); //KDL::Frame(KDL::Vector(0.3, 0.92, 1)));
int calculateForwardKinematics(const KDL::JntArray &joint_positions, KDL::Frame &end_effector_pose);
int calculateForwardKinematics(const KDL::JntArray &joint_positions, KDL::Frame &end_effector_pose, int joint_nbr = -1);
int calculateInverseKinematics(const KDL::JntArray &cur_configuration,
const KDL::Frame &desired_end_effector_pose,