Skip to content
Open
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 @@ -88,13 +88,17 @@ class KinematicsPluginLoader::KinematicsLoaderImpl
std::vector<std::string> chooseTipFrames(const moveit::core::JointModelGroup* jmg)
{
std::vector<std::string> tips;
// get the last link in the chain
RCLCPP_DEBUG(logger_,
"Choosing tip frame of kinematic solver for group %s"
"based on last link in chain",
jmg->getName().c_str());

tips.push_back(jmg->getLinkModels().back()->getName());
// try to retrieve the tip frames from the joint model group
if (!jmg->getEndEffectorTips(tips))
{
// get the last link in the chain as fallback
RCLCPP_DEBUG(logger_,
"Choosing tip frame of kinematic solver for group %s"
"based on last link in chain",
jmg->getName().c_str());
tips.push_back(jmg->getLinkModels().back()->getName());
}

// Error check
if (tips.empty())
Expand Down