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

Make checkKin optional in debug #1043

Closed
wants to merge 1 commit into from
Closed
Show file tree
Hide file tree
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
Original file line number Diff line number Diff line change
Expand Up @@ -204,7 +204,8 @@ class Environment
* @return A kinematics group
*/
std::unique_ptr<tesseract_kinematics::KinematicGroup> getKinematicGroup(const std::string& group_name,
const std::string& ik_solver_name = "") const;
const std::string& ik_solver_name = "",
bool check_kinematics = true) const;

/**
* @brief Find tool center point provided in the manipulator info
Expand Down
11 changes: 6 additions & 5 deletions tesseract_environment/src/environment.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -301,7 +301,8 @@ struct Environment::Implementation
const std::vector<std::string>& joint_names) const;

std::unique_ptr<tesseract_kinematics::KinematicGroup> getKinematicGroup(const std::string& group_name,
std::string ik_solver_name) const;
std::string ik_solver_name,
bool check_kinematics) const;

Eigen::Isometry3d findTCPOffset(const tesseract_common::ManipulatorInfo& manip_info) const;

Expand Down Expand Up @@ -806,7 +807,7 @@ Environment::Implementation::getJointGroup(const std::string& name, const std::v
}

std::unique_ptr<tesseract_kinematics::KinematicGroup>
Environment::Implementation::getKinematicGroup(const std::string& group_name, std::string ik_solver_name) const
Environment::Implementation::getKinematicGroup(const std::string& group_name, std::string ik_solver_name, bool check_kinematics) const
{
std::unique_lock<std::shared_mutex> cache_lock(kinematic_group_cache_mutex);
std::pair<std::string, std::string> key = std::make_pair(group_name, ik_solver_name);
Expand Down Expand Up @@ -839,7 +840,7 @@ Environment::Implementation::getKinematicGroup(const std::string& group_name, st
kinematic_group_cache[key] = std::make_unique<tesseract_kinematics::KinematicGroup>(*kg);

#ifndef NDEBUG
if (!tesseract_kinematics::checkKinematics(*kg))
if (check_kinematics && !tesseract_kinematics::checkKinematics(*kg))
{
CONSOLE_BRIDGE_logError("Check Kinematics failed. This means that inverse kinematics solution for a pose do not "
"match forward kinematics solution. Did you change the URDF recently?");
Expand Down Expand Up @@ -2324,10 +2325,10 @@ Environment::getJointGroup(const std::string& name, const std::vector<std::strin
}

std::unique_ptr<tesseract_kinematics::KinematicGroup>
Environment::getKinematicGroup(const std::string& group_name, const std::string& ik_solver_name) const
Environment::getKinematicGroup(const std::string& group_name, const std::string& ik_solver_name, bool check_kinematics) const
{
std::shared_lock<std::shared_mutex> lock(mutex_);
return std::as_const<Implementation>(*impl_).getKinematicGroup(group_name, ik_solver_name);
return std::as_const<Implementation>(*impl_).getKinematicGroup(group_name, ik_solver_name, check_kinematics);
}

// NOLINTNEXTLINE
Expand Down
Loading