Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove attempts from setFromIK #43

Merged
merged 1 commit into from
Feb 21, 2019
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Remove attempts from setFromIK
davetcoleman committed Feb 21, 2019
commit ee3356821e330c78dbb9055ebd17b0898ae7b7cf
3 changes: 1 addition & 2 deletions src/imarker_end_effector.cpp
Original file line number Diff line number Diff line change
@@ -136,7 +136,6 @@ void IMarkerEndEffector::iMarkerCallback(const visualization_msgs::InteractiveMa
void IMarkerEndEffector::solveIK(Eigen::Isometry3d& pose)
{
// Cartesian settings
const std::size_t attempts = 2;
const double timeout = 1.0 / 30.0; // 30 fps

// Optionally collision check
@@ -151,7 +150,7 @@ void IMarkerEndEffector::solveIK(Eigen::Isometry3d& pose)
}

// Attempt to set robot to new pose
if (imarker_state_->setFromIK(arm_data_.jmg_, pose, arm_data_.ee_link_->getName(), attempts, timeout, constraint_fn))
if (imarker_state_->setFromIK(arm_data_.jmg_, pose, arm_data_.ee_link_->getName(), timeout, constraint_fn))
{
imarker_state_->update();
// if (psm_->getPlanningScene()->isStateValid(*imarker_state_))
3 changes: 1 addition & 2 deletions src/imarker_robot_state.cpp
Original file line number Diff line number Diff line change
@@ -281,7 +281,6 @@ bool IMarkerRobotState::setFromPoses(const EigenSTL::vector_Isometry3d poses,

// ROS_DEBUG_STREAM_NAMED(name_, "First pose should be for joint model group: " << arm_datas_[0].ee_link_->getName());

const std::size_t attempts = 10;
const double timeout = 1.0 / 30.0; // 30 fps

// Optionally collision check
@@ -303,7 +302,7 @@ bool IMarkerRobotState::setFromPoses(const EigenSTL::vector_Isometry3d poses,
std::size_t outer_attempts = 20;
for (std::size_t i = 0; i < outer_attempts; ++i)
{
if (!imarker_state_->setFromIK(group, poses, tips, attempts, timeout, constraint_fn))
if (!imarker_state_->setFromIK(group, poses, tips, timeout, constraint_fn))
{
ROS_DEBUG_STREAM_NAMED(name_, "Failed to find dual arm pose, trying again");