Skip to content

Commit

Permalink
parsing: Fix joint pose computation when using frames as joint parent…
Browse files Browse the repository at this point in the history
… or child
  • Loading branch information
azeey committed Jul 8, 2021
1 parent 0cdb179 commit 04c7b4f
Show file tree
Hide file tree
Showing 3 changed files with 137 additions and 3 deletions.
46 changes: 43 additions & 3 deletions multibody/parsing/detail_sdf_parser.cc
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,44 @@ std::pair<ModelInstanceIndex, std::string> GetResolvedModelInstanceAndLocalName(

return {resolved_model_instance, unscoped_local_name};
}
// Returns true if `str` starts with `prefix`. The length of `prefix` has to be
// strictly less than the size of `str`.
bool StartsWith(const std::string_view str, const std::string_view prefix) {
return prefix.size() < str.size() &&
std::equal(str.begin(), str.begin() + prefix.size(), prefix.begin());
}

// Calculates the scoped name of a body relative to the model instance @p
// relative_to_model_instance. If the body is a direct child of the model,
// this simply returns the local name of the body. However, if the body is
// a child of a nested model, the local name of the body is prefixed with the
// scoped name of the nested model.
std::string GetRelativeBodyName(
const Body<double>& body,
ModelInstanceIndex relative_to_model_instance,
const MultibodyPlant<double>& plant) {
const std::string& relative_to_model_absolute_name =
plant.GetModelInstanceName(relative_to_model_instance);
// If the body is inside a nested model, we need to prefix the
// name with the relative name of the nested model.
if (body.model_instance() != relative_to_model_instance) {
const std::string& nested_model_absolute_name =
plant.GetModelInstanceName(body.model_instance());
// The relative_to_model_absolute_name must be a prefix of the
// nested_model_absolute_name. Otherwise the nested model is not a
// descendent of the model relative to which we are computing the name.
const std::string required_prefix =
relative_to_model_absolute_name + sdf::kSdfScopeDelimiter;
DRAKE_DEMAND(StartsWith(nested_model_absolute_name, required_prefix));

const std::string nested_model_relative_name =
nested_model_absolute_name.substr(required_prefix.size());

return sdf::JoinName(nested_model_relative_name, body.name());
} else {
return body.name();
}
}

// Given an ignition::math::Inertial object, extract a RotationalInertia object
// for the rotational inertia of body B, about its center of mass Bcm and,
Expand Down Expand Up @@ -415,8 +453,9 @@ void AddJointFromSpecification(
// Get the pose of frame J in the frame of the child link C, as specified in
// <joint> <pose> ... </pose></joint>. The default `relative_to` pose of a
// joint will be the child link.
const RigidTransformd X_CJ =
ResolveRigidTransform(joint_spec.SemanticPose());
const RigidTransformd X_CJ = ResolveRigidTransform(
joint_spec.SemanticPose(),
GetRelativeBodyName(child_body, model_instance, *plant));

// Pose of the frame J in the parent body frame P.
std::optional<RigidTransformd> X_PJ;
Expand All @@ -429,7 +468,8 @@ void AddJointFromSpecification(
X_PJ = X_WM * X_MJ; // Since P == W.
} else {
X_PJ = ResolveRigidTransform(
joint_spec.SemanticPose(), joint_spec.ParentLinkName());
joint_spec.SemanticPose(),
GetRelativeBodyName(parent_body, model_instance, *plant));
}

// If P and J are coincident, we won't create a new frame for J, but use frame
Expand Down
54 changes: 54 additions & 0 deletions multibody/parsing/test/detail_sdf_parser_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1808,6 +1808,60 @@ GTEST_TEST(SdfParser, SupportNonDefaultCanonicalLink) {
EXPECT_EQ(GetModelFrameByName(*plant, "a::c").body().index(),
plant->GetBodyByName("f").index());
}

// Verify that frames can be used for //joint/parent and //joint/child
GTEST_TEST(SdfParser, FramesAsJointParentOrChild) {
const std::string full_name = FindResourceOrThrow(
"drake/multibody/parsing/test/sdf_parser_test/"
"frames_as_joint_parent_or_child.sdf");
MultibodyPlant<double> plant(0.0);

PackageMap package_map;
package_map.PopulateUpstreamToDrake(full_name);
AddModelsFromSdfFile(full_name, package_map, &plant);
ASSERT_TRUE(plant.HasModelInstanceNamed("parent_model"));

plant.Finalize();
auto context = plant.CreateDefaultContext();

// Frames attached to links in the same model
{
const auto& joint_J1 = plant.GetJointByName("J1");

// J1p and J1c are the frames of J1 on its parent and child links
// respectively. The absolute poses of both frames should be identical.
const RigidTransformd X_WJ1_expected(RollPitchYawd(0, 0, 0),
Vector3d(4, 5, 6));

const RigidTransformd X_WJ1p =
joint_J1.frame_on_parent().CalcPoseInWorld(*context);
EXPECT_TRUE(CompareMatrices(X_WJ1_expected.GetAsMatrix4(),
X_WJ1p.GetAsMatrix4(), kEps));

const RigidTransformd X_WJ1c =
joint_J1.frame_on_child().CalcPoseInWorld(*context);
EXPECT_TRUE(CompareMatrices(X_WJ1_expected.GetAsMatrix4(),
X_WJ1c.GetAsMatrix4(), kEps));
}
// Frames attached to links in the other (nested) models
{
const auto& joint_J2 = plant.GetJointByName("J2");

// J2p and J2c are the frames of J2 on its parent and child links
// respectively. The absolute poses of both frames should be identical.
const RigidTransformd X_WJ2_expected(RollPitchYawd(0, 0, 0),
Vector3d(4, 5, 6));
const RigidTransformd X_WJ2p =
joint_J2.frame_on_parent().CalcPoseInWorld(*context);
EXPECT_TRUE(CompareMatrices(X_WJ2_expected.GetAsMatrix4(),
X_WJ2p.GetAsMatrix4(), kEps));

const RigidTransformd X_WJ2c =
joint_J2.frame_on_child().CalcPoseInWorld(*context);
EXPECT_TRUE(CompareMatrices(X_WJ2_expected.GetAsMatrix4(),
X_WJ2c.GetAsMatrix4(), kEps));
}
}
} // namespace
} // namespace internal
} // namespace multibody
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
<?xml version="1.0"?>
<sdf version="1.8">
<model name='parent_model'>
<!-- Testing frames attached to links in the same model -->
<link name='L1'/>
<link name='L2'/>

<frame name='L1_offset' attached_to='L1'>
<pose>1 2 3 0 0 0</pose>
</frame>
<frame name='L2_offset' attached_to='L2'>
<pose>4 5 6 0 0 0</pose>
</frame>

<joint name='J1' type='fixed'>
<parent>L1_offset</parent>
<child>L2_offset</child>
</joint>

<!-- Testing frames attached to links in the other (nested) models -->
<model name='M1'>
<link name='base_link'/>
</model>
<model name='M2'>
<link name='base_link'/>
</model>

<frame name='M1_base_link_offset' attached_to='M1::base_link'>
<pose>1 2 3 0 0 0</pose>
</frame>
<frame name='M2_base_link_offset' attached_to='M2::base_link'>
<pose>4 5 6 0 0 0</pose>
</frame>

<joint name='J2' type='fixed'>
<parent>M1_base_link_offset</parent>
<child>M2_base_link_offset</child>
</joint>
</model>
</sdf>

0 comments on commit 04c7b4f

Please sign in to comment.