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

Fix getLinkModelNamesWithCollisionGeometry to include the base link #2660

Merged
merged 3 commits into from
Jan 25, 2024
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
8 changes: 8 additions & 0 deletions moveit_core/robot_model/src/joint_model_group.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -229,6 +229,14 @@ JointModelGroup::JointModelGroup(const std::string& group_name, const srdf::Mode
{
link_model_map_[link_model->getName()] = link_model;
link_model_name_vector_.push_back(link_model->getName());
// if this is the first link of the group with a valid parent and includes geometry (for example `base_link`) it should included
if (link_model_with_geometry_vector_.empty() && link_model->getParentLinkModel() &&
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm not sure this is the correct approach. There can be more than one discrete subtree in a group, this would only consider the first one.

We discussed a similar issue I observed in moveit/moveit#3570

I think the previous version of the code is correct for is_chain_ == false (a list of <link> or <joint> tags in SRDF) but not for the case of <chain> where the root link is included but not parent joint.

Copy link
Contributor

@sjahr sjahr Mar 25, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Oh you're right, thanks for pointing that out! Do you think we should revert this change for now or just add a check for is_chain_?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hmm, this is getting surprisingly complicated ... is_chain_ is not passed to the constructor but guessed about near the end of the constructor. They might be different things altogether?

According to the code in RobotModel a chain as specified in SRDF could also go from finger_1_tip to finger_2_tip with the root being somewhere in the middle (eg the wrist).

Maybe a list of links should also get passed in to the constructor.

I'm also not yet sure how this relates to collision checking and what the problem actually was.

!link_model->getParentLinkModel()->getShapes().empty())
{
link_model_with_geometry_vector_.push_back(link_model->getParentLinkModel());
link_model_with_geometry_name_vector_.push_back(link_model->getParentLinkModel()->getName());
}
// all child links with collision geometry should also be included
if (!link_model->getShapes().empty())
{
link_model_with_geometry_vector_.push_back(link_model);
Expand Down
Loading