@@ -907,14 +907,41 @@ void RobotState::updateStateWithLinkAt(const LinkModel* link, const Eigen::Isome
907
907
}
908
908
}
909
909
910
- const LinkModel* RobotState::getRigidlyConnectedParentLinkModel (const std::string& frame) const
910
+ const LinkModel* RobotState::getLinkModelIncludingAttachedBodies (const std::string& frame) const
911
911
{
912
- bool found;
913
- const LinkModel* link { nullptr };
914
- getFrameInfo (frame, link , found);
915
- if (!found)
916
- RCLCPP_ERROR (getLogger (), " Unable to find link for frame '%s'" , frame.c_str ());
917
- return getRobotModel ()->getRigidlyConnectedParentLinkModel (link );
912
+ // If the frame is a link, return that link.
913
+ if (getRobotModel ()->hasLinkModel (frame))
914
+ {
915
+ return getLinkModel (frame);
916
+ }
917
+
918
+ // If the frame is an attached body, return the link the body is attached to.
919
+ if (const auto it = attached_body_map_.find (frame); it != attached_body_map_.end ())
920
+ {
921
+ const auto & body{ it->second };
922
+ return body->getAttachedLink ();
923
+ }
924
+
925
+ // If the frame is a subframe of an attached body, return the link the body is attached to.
926
+ for (const auto & it : attached_body_map_)
927
+ {
928
+ const auto & body{ it.second };
929
+ if (body->hasSubframeTransform (frame))
930
+ {
931
+ return body->getAttachedLink ();
932
+ }
933
+ }
934
+
935
+ // If the frame is none of the above, return nullptr.
936
+ return nullptr ;
937
+ }
938
+
939
+ const LinkModel* RobotState::getRigidlyConnectedParentLinkModel (const std::string& frame,
940
+ const moveit::core::JointModelGroup* jmg) const
941
+ {
942
+ const LinkModel* link = getLinkModelIncludingAttachedBodies (frame);
943
+
944
+ return getRobotModel ()->getRigidlyConnectedParentLinkModel (link , jmg);
918
945
}
919
946
920
947
const Eigen::Isometry3d& RobotState::getJointTransform (const JointModel* joint)
0 commit comments