Skip to content

Commit 0b92e3d

Browse files
authored
bullet-featherstone: Fix finding free group for a body with fixed base (#700)
Signed-off-by: Ian Chen <ichen@openrobotics.org>
1 parent 0fb5974 commit 0b92e3d

File tree

2 files changed

+129
-12
lines changed

2 files changed

+129
-12
lines changed

bullet-featherstone/src/FreeGroupFeatures.cc

+14-12
Original file line numberDiff line numberDiff line change
@@ -85,37 +85,39 @@ Identity FreeGroupFeatures::FindFreeGroupForModel(
8585
{
8686
const auto *model = this->ReferenceInterface<ModelInfo>(_modelID);
8787

88-
// Reject if the model has fixed base
89-
if (model->body->hasFixedBase())
90-
return this->GenerateInvalidId();
91-
92-
// Also reject if the model is a child of a fixed constraint
93-
// (detachable joint)
9488
for (const auto & joint : this->joints)
9589
{
90+
// Also reject if the model is a child of a fixed constraint
91+
// (detachable joint)
9692
if (joint.second->fixedConstraint)
9793
{
9894
if (joint.second->fixedConstraint->getMultiBodyB() == model->body.get())
9995
{
10096
return this->GenerateInvalidId();
10197
}
10298
}
99+
// Reject if the model has a world joint
100+
if (std::size_t(joint.second->model) == std::size_t(_modelID))
101+
{
102+
const auto *identifier =
103+
std::get_if<RootJoint>(&joint.second->identifier);
104+
if (identifier)
105+
{
106+
return this->GenerateInvalidId();
107+
}
108+
}
103109
}
104110

105-
106111
return _modelID;
107112
}
108113

109114
/////////////////////////////////////////////////
110115
Identity FreeGroupFeatures::FindFreeGroupForLink(
111116
const Identity &_linkID) const
112117
{
118+
// Free groups in bullet-featherstone are currently represented by ModelInfo
113119
const auto *link = this->ReferenceInterface<LinkInfo>(_linkID);
114-
const auto *model = this->ReferenceInterface<ModelInfo>(link->model);
115-
if (model->body->hasFixedBase())
116-
return this->GenerateInvalidId();
117-
118-
return link->model;
120+
return this->FindFreeGroupForModel(link->model);
119121
}
120122

121123
/////////////////////////////////////////////////

test/common_test/free_joint_features.cc

+115
Original file line numberDiff line numberDiff line change
@@ -316,6 +316,121 @@ TEST_F(FreeGroupFeaturesTest, FreeGroupSetWorldPosePrincipalAxesOffset)
316316
}
317317
}
318318

319+
TEST_F(FreeGroupFeaturesTest, FreeGroupSetWorldPoseStaticAndFixedModel)
320+
{
321+
const std::string modelStaticStr = R"(
322+
<sdf version="1.11">
323+
<model name="sphere">
324+
<static>true</static>
325+
<pose>1 2 3.0 0 0 0</pose>
326+
<link name="link">
327+
<collision name="coll_sphere">
328+
<geometry>
329+
<sphere>
330+
<radius>0.1</radius>
331+
</sphere>
332+
</geometry>
333+
</collision>
334+
</link>
335+
</model>
336+
</sdf>)";
337+
338+
const std::string modelWorldFixedStr = R"(
339+
<sdf version="1.11">
340+
<model name="sphere_world_fixed">
341+
<static>false</static>
342+
<pose>3 2 3.0 0 0 0</pose>
343+
<link name="link">
344+
<collision name="coll_sphere">
345+
<geometry>
346+
<sphere>
347+
<radius>0.1</radius>
348+
</sphere>
349+
</geometry>
350+
</collision>
351+
</link>
352+
<joint name="world_fixed" type="fixed">
353+
<parent>world</parent>
354+
<child>link</child>
355+
</joint>
356+
</model>
357+
</sdf>)";
358+
359+
for (const std::string &name : pluginNames)
360+
{
361+
std::cout << "Testing plugin: " << name << std::endl;
362+
gz::plugin::PluginPtr plugin = loader.Instantiate(name);
363+
364+
auto engine = gz::physics::RequestEngine3d<TestFeatureList>::From(plugin);
365+
ASSERT_NE(nullptr, engine);
366+
367+
sdf::Root root;
368+
sdf::Errors errors = root.Load(
369+
common_test::worlds::kGroundSdf);
370+
EXPECT_EQ(0u, errors.size()) << errors;
371+
372+
EXPECT_EQ(1u, root.WorldCount());
373+
const sdf::World *sdfWorld = root.WorldByIndex(0);
374+
ASSERT_NE(nullptr, sdfWorld);
375+
376+
auto world = engine->ConstructWorld(*sdfWorld);
377+
ASSERT_NE(nullptr, world);
378+
379+
// create the static model
380+
errors = root.LoadSdfString(modelStaticStr);
381+
ASSERT_TRUE(errors.empty()) << errors;
382+
ASSERT_NE(nullptr, root.Model());
383+
world->ConstructModel(*root.Model());
384+
385+
auto modelStatic = world->GetModel("sphere");
386+
ASSERT_NE(nullptr, modelStatic);
387+
auto link = modelStatic->GetLink("link");
388+
ASSERT_NE(nullptr, link);
389+
auto frameDataLink = link->FrameDataRelativeToWorld();
390+
EXPECT_EQ(gz::math::Pose3d(1, 2, 3, 0, 0, 0),
391+
gz::math::eigen3::convert(frameDataLink.pose));
392+
393+
// get free group and set new pose
394+
auto freeGroup = modelStatic->FindFreeGroup();
395+
ASSERT_NE(nullptr, freeGroup);
396+
gz::math::Pose3d newPose(4, 5, 6, 0, 0, 1.57);
397+
freeGroup->SetWorldPose(
398+
gz::math::eigen3::convert(newPose));
399+
frameDataLink = link->FrameDataRelativeToWorld();
400+
// static model should move to new pose
401+
EXPECT_EQ(newPose,
402+
gz::math::eigen3::convert(frameDataLink.pose));
403+
404+
// create the model with world joint
405+
errors = root.LoadSdfString(modelWorldFixedStr);
406+
ASSERT_TRUE(errors.empty()) << errors;
407+
ASSERT_NE(nullptr, root.Model());
408+
world->ConstructModel(*root.Model());
409+
410+
auto modelFixed = world->GetModel("sphere_world_fixed");
411+
ASSERT_NE(nullptr, modelFixed);
412+
link = modelFixed->GetLink("link");
413+
ASSERT_NE(nullptr, link);
414+
frameDataLink = link->FrameDataRelativeToWorld();
415+
gz::math::Pose3d origPose(3, 2, 3, 0, 0, 0);
416+
EXPECT_EQ(origPose,
417+
gz::math::eigen3::convert(frameDataLink.pose));
418+
419+
// get free group and set new pose
420+
freeGroup = modelFixed->FindFreeGroup();
421+
ASSERT_NE(nullptr, freeGroup);
422+
freeGroup->SetWorldPose(
423+
gz::math::eigen3::convert(newPose));
424+
frameDataLink = link->FrameDataRelativeToWorld();
425+
// world fixed model should not be able to move to new pose
426+
if (this->PhysicsEngineName(name) != "tpe")
427+
{
428+
EXPECT_EQ(origPose,
429+
gz::math::eigen3::convert(frameDataLink.pose));
430+
}
431+
}
432+
}
433+
319434
int main(int argc, char *argv[])
320435
{
321436
::testing::InitGoogleTest(&argc, argv);

0 commit comments

Comments
 (0)