From 765fec88fead74b8ab7fde8d0faff51e66abdbd2 Mon Sep 17 00:00:00 2001 From: Dave Coleman Date: Wed, 20 Feb 2019 20:38:55 -0700 Subject: [PATCH] Remove deprecated attempts --- .../src/robot_model_and_robot_state_tutorial.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/doc/robot_model_and_robot_state/src/robot_model_and_robot_state_tutorial.cpp b/doc/robot_model_and_robot_state/src/robot_model_and_robot_state_tutorial.cpp index 28515c55a..c0076a302 100644 --- a/doc/robot_model_and_robot_state/src/robot_model_and_robot_state_tutorial.cpp +++ b/doc/robot_model_and_robot_state/src/robot_model_and_robot_state_tutorial.cpp @@ -128,11 +128,9 @@ int main(int argc, char** argv) // // * The desired pose of the end-effector (by default, this is the last link in the "panda_arm" chain): // end_effector_state that we computed in the step above. - // * The number of attempts to be made at solving IK: 10 - // * The timeout for each attempt: 0.1 s - std::size_t attempts = 10; + // * The timeout: 0.1 s double timeout = 0.1; - bool found_ik = kinematic_state->setFromIK(joint_model_group, end_effector_state, attempts, timeout); + bool found_ik = kinematic_state->setFromIK(joint_model_group, end_effector_state, timeout); // Now, we can print out the IK solution (if found): if (found_ik)