Skip to content

Commit 5c200b2

Browse files
committed
Fix setting world pose to static free group
Signed-off-by: Ian Chen <ichen@openrobotics.org>
1 parent db1d5e0 commit 5c200b2

File tree

2 files changed

+67
-10
lines changed

2 files changed

+67
-10
lines changed

bullet-featherstone/src/FreeGroupFeatures.cc

+2-10
Original file line numberDiff line numberDiff line change
@@ -85,10 +85,6 @@ 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-
9288
// Also reject if the model is a child of a fixed constraint
9389
// (detachable joint)
9490
for (const auto & joint : this->joints)
@@ -102,20 +98,16 @@ Identity FreeGroupFeatures::FindFreeGroupForModel(
10298
}
10399
}
104100

105-
106101
return _modelID;
107102
}
108103

109104
/////////////////////////////////////////////////
110105
Identity FreeGroupFeatures::FindFreeGroupForLink(
111106
const Identity &_linkID) const
112107
{
108+
// Free groups in bullet-featherstone are currently represented by ModelInfo
113109
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;
110+
return FindFreeGroupForModel(link->model)
119111
}
120112

121113
/////////////////////////////////////////////////

test/common_test/free_joint_features.cc

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

319+
TEST_F(FreeGroupFeaturesTest, FreeGroupSetWorldPoseStaticModel)
320+
{
321+
const std::string modelStr = 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+
for (const std::string &name : pluginNames)
339+
{
340+
std::cout << "Testing plugin: " << name << std::endl;
341+
gz::plugin::PluginPtr plugin = loader.Instantiate(name);
342+
343+
auto engine = gz::physics::RequestEngine3d<TestFeatureList>::From(plugin);
344+
ASSERT_NE(nullptr, engine);
345+
346+
sdf::Root root;
347+
sdf::Errors errors = root.Load(
348+
common_test::worlds::kGroundSdf);
349+
EXPECT_EQ(0u, errors.size()) << errors;
350+
351+
EXPECT_EQ(1u, root.WorldCount());
352+
const sdf::World *sdfWorld = root.WorldByIndex(0);
353+
ASSERT_NE(nullptr, sdfWorld);
354+
355+
auto world = engine->ConstructWorld(*sdfWorld);
356+
ASSERT_NE(nullptr, world);
357+
358+
// create the model
359+
errors = root.LoadSdfString(modelStr);
360+
ASSERT_TRUE(errors.empty()) << errors;
361+
ASSERT_NE(nullptr, root.Model());
362+
world->ConstructModel(*root.Model());
363+
364+
auto model = world->GetModel("sphere");
365+
ASSERT_NE(nullptr, model);
366+
auto link = model->GetLink("link");
367+
ASSERT_NE(nullptr, link);
368+
auto frameDataLink = link->FrameDataRelativeToWorld();
369+
EXPECT_EQ(gz::math::Pose3d(1, 2, 3, 0, 0, 0),
370+
gz::math::eigen3::convert(frameDataLink.pose));
371+
372+
// get free group and set new pose
373+
auto freeGroup = model->FindFreeGroup();
374+
ASSERT_NE(nullptr, freeGroup);
375+
gz::math::Pose3d newPose(4, 5, 6, 0, 0, 1.57);
376+
freeGroup->SetWorldPose(
377+
gz::math::eigen3::convert(newPose));
378+
frameDataLink = link->FrameDataRelativeToWorld();
379+
EXPECT_EQ(newPose,
380+
gz::math::eigen3::convert(frameDataLink.pose));
381+
}
382+
}
383+
319384
int main(int argc, char *argv[])
320385
{
321386
::testing::InitGoogleTest(&argc, argv);

0 commit comments

Comments
 (0)