Skip to content

Commit be741b9

Browse files
davetcolemanrhaschke
authored andcommitted
Remove deprecated attempts (#285)
1 parent 1e01f54 commit be741b9

1 file changed

Lines changed: 2 additions & 4 deletions

File tree

doc/robot_model_and_robot_state/src/robot_model_and_robot_state_tutorial.cpp

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -128,11 +128,9 @@ int main(int argc, char** argv)
128128
//
129129
// * The desired pose of the end-effector (by default, this is the last link in the "panda_arm" chain):
130130
// end_effector_state that we computed in the step above.
131-
// * The number of attempts to be made at solving IK: 10
132-
// * The timeout for each attempt: 0.1 s
133-
std::size_t attempts = 10;
131+
// * The timeout: 0.1 s
134132
double timeout = 0.1;
135-
bool found_ik = kinematic_state->setFromIK(joint_model_group, end_effector_state, attempts, timeout);
133+
bool found_ik = kinematic_state->setFromIK(joint_model_group, end_effector_state, timeout);
136134

137135
// Now, we can print out the IK solution (if found):
138136
if (found_ik)

0 commit comments

Comments
 (0)