Skip to content

Commit ab34495

Browse files
TSNoblerr-tom-noblesjahr
authored
Allow RobotState::setFromIK to work with subframes (#3077)
* Adds regression tests for setFromIK with objects. Adds failing tests demonstrating failure with subframes * Modifies RobotState::setFromIK to account for subframes * Fixes formatting * Fixes formatting * Fixes formatting * Applies PR suggestions * Applies PR comments --------- Co-authored-by: Tom Noble <[email protected]> Co-authored-by: Sebastian Jahr <[email protected]>
1 parent 2490e51 commit ab34495

File tree

2 files changed

+200
-29
lines changed

2 files changed

+200
-29
lines changed

moveit_core/robot_state/src/robot_state.cpp

Lines changed: 21 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -1877,42 +1877,34 @@ bool RobotState::setFromIK(const JointModelGroup* jmg, const EigenSTL::vector_Is
18771877

18781878
if (pose_frame != solver_tip_frame)
18791879
{
1880-
if (hasAttachedBody(pose_frame))
1880+
auto* pose_parent = getRigidlyConnectedParentLinkModel(pose_frame);
1881+
if (!pose_parent)
18811882
{
1882-
const AttachedBody* body = getAttachedBody(pose_frame);
1883-
pose_frame = body->getAttachedLinkName();
1884-
pose = pose * body->getPose().inverse();
1883+
RCLCPP_ERROR_STREAM(getLogger(), "The following Pose Frame does not exist: " << pose_frame);
1884+
return false;
18851885
}
1886-
if (pose_frame != solver_tip_frame)
1886+
Eigen::Isometry3d pose_parent_to_frame = getFrameTransform(pose_frame);
1887+
auto* tip_parent = getRigidlyConnectedParentLinkModel(solver_tip_frame);
1888+
if (!tip_parent)
18871889
{
1888-
const LinkModel* link_model = getLinkModel(pose_frame);
1889-
if (!link_model)
1890-
{
1891-
RCLCPP_ERROR(getLogger(), "The following Pose Frame does not exist: %s", pose_frame.c_str());
1892-
return false;
1893-
}
1894-
const LinkTransformMap& fixed_links = link_model->getAssociatedFixedTransforms();
1895-
for (const std::pair<const LinkModel* const, Eigen::Isometry3d>& fixed_link : fixed_links)
1896-
{
1897-
if (Transforms::sameFrame(fixed_link.first->getName(), solver_tip_frame))
1898-
{
1899-
pose_frame = solver_tip_frame;
1900-
pose = pose * fixed_link.second;
1901-
break;
1902-
}
1903-
}
1890+
RCLCPP_ERROR_STREAM(getLogger(), "The following Solver Tip Frame does not exist: " << solver_tip_frame);
1891+
return false;
19041892
}
1905-
1906-
} // end if pose_frame
1907-
1908-
// Check if this pose frame works
1909-
if (pose_frame == solver_tip_frame)
1893+
Eigen::Isometry3d tip_parent_to_tip = getFrameTransform(solver_tip_frame);
1894+
if (pose_parent == tip_parent)
1895+
{
1896+
// transform goal pose as target for solver_tip_frame (instead of pose_frame)
1897+
pose = pose * pose_parent_to_frame.inverse() * tip_parent_to_tip;
1898+
found_valid_frame = true;
1899+
break;
1900+
}
1901+
}
1902+
else
19101903
{
19111904
found_valid_frame = true;
19121905
break;
1913-
}
1914-
1915-
} // end for solver_tip_frames
1906+
} // end if pose_frame
1907+
} // end for solver_tip_frames
19161908

19171909
// Make sure one of the tip frames worked
19181910
if (!found_valid_frame)

moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp

Lines changed: 179 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -135,6 +135,35 @@ class TrajectoryFunctionsTestBase : public testing::Test
135135
*/
136136
bool tfNear(const Eigen::Isometry3d& pose1, const Eigen::Isometry3d& pose2, double epsilon);
137137

138+
/**
139+
* @brief check if two sets of joint positions are close
140+
* @param joints1 the first set of joint positions to compare
141+
* @param joints2 the second set of joint positions to compare
142+
* @param epsilon the tolerance a all joint position diffs must satisfy
143+
* @return false if any joint diff exceeds tolerance. true otherwise
144+
*/
145+
bool jointsNear(const std::vector<double>& joints1, const std::vector<double>& joints2, double epsilon);
146+
147+
/**
148+
* @brief get the current joint values of the robot state
149+
* @param jmg the joint model group whose joints we are interested in
150+
* @param state the robot state to fetch the current joint positions for
151+
* @return the joint positions for joints from jmg, set to the positions determined from state
152+
*/
153+
std::vector<double> getJoints(const moveit::core::JointModelGroup* jmg, const moveit::core::RobotState& state);
154+
155+
/**
156+
* @brief attach a collision object and subframes to a link
157+
* @param state the state we are updating
158+
* @param link the link we are attaching the collision object to
159+
* @param object_name a unique name for the collision object
160+
* @param object_pose the pose of the object relative to the parent link
161+
* @param subframes subframe names and poses relative to the object they attach to
162+
*/
163+
void attachToLink(moveit::core::RobotState& state, const moveit::core::LinkModel* link,
164+
const std::string& object_name, const Eigen::Isometry3d& object_pose,
165+
const moveit::core::FixedTransformsMap& subframes);
166+
138167
protected:
139168
// ros stuff
140169
rclcpp::Node::SharedPtr node_;
@@ -167,6 +196,43 @@ bool TrajectoryFunctionsTestBase::tfNear(const Eigen::Isometry3d& pose1, const E
167196
return true;
168197
}
169198

199+
bool TrajectoryFunctionsTestBase::jointsNear(const std::vector<double>& joints1, const std::vector<double>& joints2,
200+
double epsilon)
201+
{
202+
if (joints1.size() != joints2.size())
203+
{
204+
return false;
205+
}
206+
for (std::size_t i = 0; i < joints1.size(); ++i)
207+
{
208+
if (fabs(joints1.at(i) - joints2.at(i)) > fabs(epsilon))
209+
{
210+
return false;
211+
}
212+
}
213+
return true;
214+
}
215+
216+
std::vector<double> TrajectoryFunctionsTestBase::getJoints(const moveit::core::JointModelGroup* jmg,
217+
const moveit::core::RobotState& state)
218+
{
219+
std::vector<double> joints;
220+
for (const auto& name : jmg->getActiveJointModelNames())
221+
{
222+
joints.push_back(state.getVariablePosition(name));
223+
}
224+
return joints;
225+
}
226+
227+
void TrajectoryFunctionsTestBase::attachToLink(moveit::core::RobotState& state, const moveit::core::LinkModel* link,
228+
const std::string& object_name, const Eigen::Isometry3d& object_pose,
229+
const moveit::core::FixedTransformsMap& subframes)
230+
{
231+
state.attachBody(std::make_unique<moveit::core::AttachedBody>(
232+
link, object_name, object_pose, std::vector<shapes::ShapeConstPtr>{}, EigenSTL::vector_Isometry3d{},
233+
std::set<std::string>{}, trajectory_msgs::msg::JointTrajectory{}, subframes));
234+
}
235+
170236
/**
171237
* @brief Parametrized class for tests with and without gripper.
172238
*/
@@ -338,6 +404,119 @@ TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIKRobotState)
338404
}
339405
}
340406

407+
TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIKRobotStateWithIdentityCollisionObject)
408+
{
409+
// Set up a default robot
410+
moveit::core::RobotState state(robot_model_);
411+
state.setToDefaultValues();
412+
const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(planning_group_);
413+
414+
std::vector<double> default_joints = getJoints(jmg, state);
415+
const moveit::core::LinkModel* tip_link = robot_model_->getLinkModel(tcp_link_);
416+
Eigen::Isometry3d tip_pose_in_base = state.getFrameTransform(tcp_link_);
417+
418+
// Attach an object with no subframes, and no transform
419+
Eigen::Isometry3d object_pose_in_tip = Eigen::Isometry3d::Identity();
420+
attachToLink(state, tip_link, "object", object_pose_in_tip, { {} });
421+
422+
// The RobotState should be able to use an object pose to set the joints
423+
Eigen::Isometry3d object_pose_in_base = tip_pose_in_base * object_pose_in_tip;
424+
bool success = state.setFromIK(jmg, object_pose_in_base, "object");
425+
EXPECT_TRUE(success);
426+
427+
// Given the target pose is the default pose of the object, the joints should be unchanged
428+
std::vector<double> ik_joints = getJoints(jmg, state);
429+
EXPECT_TRUE(jointsNear(ik_joints, default_joints, 4 * IK_SEED_OFFSET));
430+
}
431+
432+
TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIKRobotStateWithTransformedCollisionObject)
433+
{
434+
// Set up a default robot
435+
moveit::core::RobotState state(robot_model_);
436+
state.setToDefaultValues();
437+
const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(planning_group_);
438+
439+
std::vector<double> default_joints = getJoints(jmg, state);
440+
const moveit::core::LinkModel* tip_link = robot_model_->getLinkModel(tcp_link_);
441+
Eigen::Isometry3d tip_pose_in_base = state.getFrameTransform(tcp_link_);
442+
443+
// Attach an object with no subframes, and a non-trivial transform
444+
Eigen::Isometry3d object_pose_in_tip;
445+
object_pose_in_tip = Eigen::Translation3d(1, 2, 3);
446+
object_pose_in_tip *= Eigen::AngleAxis(M_PI_2, Eigen::Vector3d::UnitX());
447+
448+
attachToLink(state, tip_link, "object", object_pose_in_tip, { {} });
449+
450+
// The RobotState should be able to use an object pose to set the joints
451+
Eigen::Isometry3d object_pose_in_base = tip_pose_in_base * object_pose_in_tip;
452+
bool success = state.setFromIK(jmg, object_pose_in_base, "object");
453+
EXPECT_TRUE(success);
454+
455+
// Given the target pose is the default pose of the object, the joints should be unchanged
456+
std::vector<double> ik_joints = getJoints(jmg, state);
457+
EXPECT_TRUE(jointsNear(ik_joints, default_joints, 4 * IK_SEED_OFFSET));
458+
}
459+
460+
TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIKRobotStateWithIdentitySubframe)
461+
{
462+
// Set up a default robot
463+
moveit::core::RobotState state(robot_model_);
464+
state.setToDefaultValues();
465+
const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(planning_group_);
466+
467+
std::vector<double> default_joints = getJoints(jmg, state);
468+
const moveit::core::LinkModel* tip_link = robot_model_->getLinkModel(tcp_link_);
469+
Eigen::Isometry3d tip_pose_in_base = state.getFrameTransform(tcp_link_);
470+
471+
// Attach an object and subframe with no transforms
472+
Eigen::Isometry3d object_pose_in_tip = Eigen::Isometry3d::Identity();
473+
Eigen::Isometry3d subframe_pose_in_object = Eigen::Isometry3d::Identity();
474+
moveit::core::FixedTransformsMap subframes({ { "subframe", subframe_pose_in_object } });
475+
attachToLink(state, tip_link, "object", object_pose_in_tip, subframes);
476+
477+
// The RobotState should be able to use a subframe pose to set the joints
478+
Eigen::Isometry3d subframe_pose_in_base = tip_pose_in_base * object_pose_in_tip * subframe_pose_in_object;
479+
bool success = state.setFromIK(jmg, subframe_pose_in_base, "object/subframe");
480+
EXPECT_TRUE(success);
481+
482+
// Given the target pose is the default pose of the subframe, the joints should be unchanged
483+
std::vector<double> ik_joints = getJoints(jmg, state);
484+
EXPECT_TRUE(jointsNear(ik_joints, default_joints, 4 * IK_SEED_OFFSET));
485+
}
486+
487+
TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIKRobotStateWithTransformedSubframe)
488+
{
489+
// Set up a default robot
490+
moveit::core::RobotState state(robot_model_);
491+
state.setToDefaultValues();
492+
const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(planning_group_);
493+
494+
std::vector<double> default_joints = getJoints(jmg, state);
495+
const moveit::core::LinkModel* tip_link = robot_model_->getLinkModel(tcp_link_);
496+
Eigen::Isometry3d tip_pose_in_base = state.getFrameTransform(tcp_link_);
497+
498+
// Attach an object and subframe with non-trivial transforms
499+
Eigen::Isometry3d object_pose_in_tip;
500+
object_pose_in_tip = Eigen::Translation3d(1, 2, 3);
501+
object_pose_in_tip *= Eigen::AngleAxis(M_PI_2, Eigen::Vector3d::UnitX());
502+
503+
Eigen::Isometry3d subframe_pose_in_object;
504+
subframe_pose_in_object = Eigen::Translation3d(4, 5, 6);
505+
subframe_pose_in_object *= Eigen::AngleAxis(M_PI_2, Eigen::Vector3d::UnitY());
506+
507+
moveit::core::FixedTransformsMap subframes({ { "subframe", subframe_pose_in_object } });
508+
attachToLink(state, tip_link, "object", object_pose_in_tip, subframes);
509+
510+
// The RobotState should be able to use a subframe pose to set the joints
511+
Eigen::Isometry3d subframe_pose_in_base = tip_pose_in_base * object_pose_in_tip * subframe_pose_in_object;
512+
bool success = state.setFromIK(jmg, subframe_pose_in_base, "object/subframe");
513+
EXPECT_TRUE(success);
514+
515+
// Given the target pose is the default pose of the subframe, the joints should be unchanged
516+
std::vector<double> ik_joints = getJoints(jmg, state);
517+
EXPECT_TRUE(jointsNear(ik_joints, default_joints, 4 * IK_SEED_OFFSET));
518+
}
519+
341520
/**
342521
* @brief Test the wrapper function to compute inverse kinematics using robot
343522
* model

0 commit comments

Comments
 (0)