Skip to content

Commit 244ad47

Browse files
Support for optimising IK solvers. Use minimum of the remaining stage timeout and the default solver timeout for each IK solve attempt
1 parent ef1cdee commit 244ad47

File tree

1 file changed

+2
-1
lines changed

1 file changed

+2
-1
lines changed

core/src/stages/compute_ik.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -413,7 +413,8 @@ void ComputeIK::compute() {
413413
tried_current_state_as_seed = true;
414414

415415
size_t previous = ik_solutions.size();
416-
bool succeeded = sandbox_state.setFromIK(jmg, target_pose, link->getName(), remaining_time, is_valid);
416+
auto iteration_timeout = std::min(remaining_time, jmg->getDefaultIKTimeout());
417+
bool succeeded = sandbox_state.setFromIK(jmg, target_pose, link->getName(), iteration_timeout, is_valid);
417418

418419
auto now = std::chrono::steady_clock::now();
419420
remaining_time -= std::chrono::duration<double>(now - start_time).count();

0 commit comments

Comments
 (0)