Update inverse kinematics solver parameters. This makes the solver finish without errors

This commit is contained in:
Derek Witcpalek
2020-04-25 22:44:41 -04:00
parent 21d20ec5a1
commit 2a85cdee8d

View File

@@ -93,7 +93,7 @@ ArmRepresentation::ArmRepresentation(const KDL::Frame &base_pose)
int ArmRepresentation::calculateForwardKinematics(const KDL::JntArray &joint_positions, KDL::Frame &end_effector_pose) int ArmRepresentation::calculateForwardKinematics(const KDL::JntArray &joint_positions, KDL::Frame &end_effector_pose)
{ {
KDL::ChainFkSolverPos_recursive fk_solver = KDL::ChainFkSolverPos_recursive(chain); KDL::ChainFkSolverPos_recursive fk_solver(chain);
int status = fk_solver.JntToCart(joint_positions, end_effector_pose); int status = fk_solver.JntToCart(joint_positions, end_effector_pose);
return status; return status;
@@ -103,7 +103,7 @@ int ArmRepresentation::calculateInverseKinematics(const KDL::JntArray &cur_confi
const KDL::Frame &desired_end_effector_pose, const KDL::Frame &desired_end_effector_pose,
KDL::JntArray &final_joint_configuration) KDL::JntArray &final_joint_configuration)
{ {
KDL::ChainIkSolverPos_LMA ik_solver = KDL::ChainIkSolverPos_LMA(chain); KDL::ChainIkSolverPos_LMA ik_solver(chain, 1e-3, 2000, 1e-8);
int status = ik_solver.CartToJnt(cur_configuration, desired_end_effector_pose, final_joint_configuration); int status = ik_solver.CartToJnt(cur_configuration, desired_end_effector_pose, final_joint_configuration);
return status; return status;