Skip to content

Commit 1794b8e

Browse files
rr-markrhaschkev4hnsjahr
authored
Reverts moveit#2985, Ports moveit moveit#3388 moveit#3470 #3539 (moveit#3284)
* Revert "Fix RobotState::getRigidlyConnectedParentLinkModel() (moveit#2985)" This reverts commit 1f23344. * Merge PR moveit#3388: Generalize RobotState::setFromIK() So far, setFromIK only accepted target (link) frames that were rigidly connected to a solver's tip frame. This, for example, excluded the fingertip of an actuated gripper, because that would be separated by an active joint from the arm's tooltip. However, as long as this joint is not part of the JMG, the corresponding transform can be considered as fixed as well. This PR generalizes the functions getRigidlyConnectedParentLinkModel() in RobotState and RobotModel to receive an optional JMG pointer. If present, only (active) joints from that group are considered non-fixed. This PR also enables subframe support for setFromIK - simply by using getRigidlyConnectedParentLinkModel(), which already supported that. There is one drawback of this approach: A repeated application of setFromIK with the same target frame and JMG (as in computeCartesianPath()), will repeat the search for the common fixed parent link. Additionally, the passed RobotState needs to be up-to-date. We could mitigate this by pulling the corresponding code into a separate function and calling it once in computeCartesianPath(). * Merge PR moveit#3470: Avoid global transforms in getRigidlyConnectedParentLinkModel() Fixes moveit#3388 * Merge pull request #3539 from v4hn/find-links-with-slashes-again find links with slashes again * Ports to ROS2 and fixes problems introduced in merge conflicts. * Fixes formatting. * Makes robot_state_test.cpp include gmock. * Updates trajectory_msgs::JointTrajectory to trajectory_msgs::msg::JointTrajectory. * Adds braces to make clang-tidy happy. * Removes test-only arguments; adds more comments. * Fixes formatting. * Fixes formatting. * Adds missing class scope. --------- Co-authored-by: Robert Haschke <[email protected]> Co-authored-by: Robert Haschke <[email protected]> Co-authored-by: Michael Görner <[email protected]> Co-authored-by: Sebastian Jahr <[email protected]>
1 parent ba35aaa commit 1794b8e

File tree

10 files changed

+395
-246
lines changed

10 files changed

+395
-246
lines changed

moveit_core/robot_model/include/moveit/robot_model/robot_model.hpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -255,6 +255,9 @@ class RobotModel
255255
LinkModel* getLinkModel(const std::string& link, bool* has_link = nullptr);
256256

257257
/** \brief Get the latest link upwards the kinematic tree, which is only connected via fixed joints
258+
*
259+
* If jmg is given, all links that are not active in this JMG are considered fixed.
260+
* Otherwise only fixed joints are considered fixed.
258261
*
259262
* This is useful, if the link should be warped to a specific pose using updateStateWithLinkAt().
260263
* As updateStateWithLinkAt() warps only the specified link and its descendants, you might not
@@ -265,7 +268,8 @@ class RobotModel
265268
* what you went for. Instead, updateStateWithLinkAt(getRigidlyConnectedParentLinkModel(grasp_frame), ...)
266269
* will actually warp wrist (and all its descendants).
267270
*/
268-
static const moveit::core::LinkModel* getRigidlyConnectedParentLinkModel(const LinkModel* link);
271+
static const LinkModel* getRigidlyConnectedParentLinkModel(const LinkModel* link,
272+
const JointModelGroup* jmg = nullptr);
269273

270274
/** \brief Get the array of links */
271275
const std::vector<const LinkModel*>& getLinkModels() const

moveit_core/robot_model/src/robot_model.cpp

+20-2
Original file line numberDiff line numberDiff line change
@@ -1364,14 +1364,32 @@ LinkModel* RobotModel::getLinkModel(const std::string& name, bool* has_link)
13641364
return nullptr;
13651365
}
13661366

1367-
const LinkModel* RobotModel::getRigidlyConnectedParentLinkModel(const LinkModel* link)
1367+
const LinkModel* RobotModel::getRigidlyConnectedParentLinkModel(const LinkModel* link, const JointModelGroup* jmg)
13681368
{
13691369
if (!link)
13701370
return link;
1371+
13711372
const moveit::core::LinkModel* parent_link = link->getParentLinkModel();
13721373
const moveit::core::JointModel* joint = link->getParentJointModel();
1374+
decltype(jmg->getJointModels().cbegin()) begin{}, end{};
1375+
if (jmg)
1376+
{
1377+
begin = jmg->getJointModels().cbegin();
1378+
end = jmg->getJointModels().cend();
1379+
}
1380+
1381+
// Returns whether `joint` is part of the rigidly connected chain.
1382+
// This is only false if the joint is both in `jmg` and not fixed.
1383+
auto is_fixed_or_not_in_jmg = [begin, end](const JointModel* joint) {
1384+
if (joint->getType() == JointModel::FIXED)
1385+
return true;
1386+
if (begin != end && // we do have a non-empty jmg
1387+
std::find(begin, end, joint) == end) // joint does not belong to jmg
1388+
return true;
1389+
return false;
1390+
};
13731391

1374-
while (parent_link && joint->getType() == moveit::core::JointModel::FIXED)
1392+
while (parent_link && is_fixed_or_not_in_jmg(joint))
13751393
{
13761394
link = parent_link;
13771395
joint = link->getParentJointModel();

moveit_core/robot_state/CMakeLists.txt

+1-1
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@ if(BUILD_TESTING)
3737
"${CMAKE_CURRENT_BINARY_DIR};${CMAKE_CURRENT_BINARY_DIR}/../utils")
3838
endif()
3939

40-
ament_add_gtest(test_robot_state test/robot_state_test.cpp
40+
ament_add_gmock(test_robot_state test/robot_state_test.cpp
4141
APPEND_LIBRARY_DIRS "${APPEND_LIBRARY_DIRS}")
4242

4343
target_link_libraries(test_robot_state moveit_test_utils moveit_utils

moveit_core/robot_state/include/moveit/robot_state/attached_body.hpp

-7
Original file line numberDiff line numberDiff line change
@@ -167,13 +167,6 @@ class AttachedBody
167167
* The returned transform is guaranteed to be a valid isometry. */
168168
const Eigen::Isometry3d& getSubframeTransform(const std::string& frame_name, bool* found = nullptr) const;
169169

170-
/** \brief Get the fixed transform to a named subframe on this body (relative to the robot link)
171-
*
172-
* The frame_name needs to have the object's name prepended (e.g. "screwdriver/tip" returns true if the object's
173-
* name is "screwdriver"). Returns an identity transform if frame_name is unknown (and set found to false).
174-
* The returned transform is guaranteed to be a valid isometry. */
175-
const Eigen::Isometry3d& getSubframeTransformInLinkFrame(const std::string& frame_name, bool* found = nullptr) const;
176-
177170
/** \brief Get the fixed transform to a named subframe on this body, relative to the world frame.
178171
* The frame_name needs to have the object's name prepended (e.g. "screwdriver/tip" returns true if the object's
179172
* name is "screwdriver"). Returns an identity transform if frame_name is unknown (and set found to false).

moveit_core/robot_state/include/moveit/robot_state/robot_state.hpp

+9-1
Original file line numberDiff line numberDiff line change
@@ -1231,7 +1231,8 @@ class RobotState
12311231
* This behaves the same as RobotModel::getRigidlyConnectedParentLinkModel,
12321232
* but can additionally resolve parents for attached objects / subframes.
12331233
*/
1234-
const moveit::core::LinkModel* getRigidlyConnectedParentLinkModel(const std::string& frame) const;
1234+
const moveit::core::LinkModel*
1235+
getRigidlyConnectedParentLinkModel(const std::string& frame, const moveit::core::JointModelGroup* jmg = nullptr) const;
12351236

12361237
/** \brief Get the link transform w.r.t. the root link (model frame) of the RobotModel.
12371238
* This is typically the root link of the URDF unless a virtual joint is present.
@@ -1712,6 +1713,13 @@ class RobotState
17121713
/** \brief This function is only called in debug mode */
17131714
bool checkCollisionTransforms() const;
17141715

1716+
/** \brief Get the closest link in the kinematic tree to `frame`.
1717+
*
1718+
* Helper function for getRigidlyConnectedParentLinkModel,
1719+
* which resolves attached objects / subframes.
1720+
*/
1721+
const moveit::core::LinkModel* getLinkModelIncludingAttachedBodies(const std::string& frame) const;
1722+
17151723
RobotModelConstPtr robot_model_;
17161724

17171725
std::vector<double> position_;

moveit_core/robot_state/src/cartesian_interpolator.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -455,6 +455,7 @@ CartesianInterpolator::Percentage CartesianInterpolator::computeCartesianPath(
455455
if (start_state->setFromIK(group, pose * offset, link->getName(), consistency_limits, 0.0, validCallback, options,
456456
cost_function))
457457
{
458+
start_state->update();
458459
path.push_back(std::make_shared<moveit::core::RobotState>(*start_state));
459460
}
460461
else

moveit_core/robot_state/src/robot_state.cpp

+34-7
Original file line numberDiff line numberDiff line change
@@ -907,14 +907,41 @@ void RobotState::updateStateWithLinkAt(const LinkModel* link, const Eigen::Isome
907907
}
908908
}
909909

910-
const LinkModel* RobotState::getRigidlyConnectedParentLinkModel(const std::string& frame) const
910+
const LinkModel* RobotState::getLinkModelIncludingAttachedBodies(const std::string& frame) const
911911
{
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);
918945
}
919946

920947
const Eigen::Isometry3d& RobotState::getJointTransform(const JointModel* joint)

0 commit comments

Comments
 (0)