Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

bullet-featherstone: Support nested models #574

Merged
merged 40 commits into from
Mar 6, 2024
Merged
Show file tree
Hide file tree
Changes from 20 commits
Commits
Show all changes
40 commits
Select commit Hold shift + click to select a range
17cb3cd
Fix how links are flattened in bullet featherstone ConstructSdfModel
shameekganguly Oct 17, 2023
4e73056
common_test/world_features: don't use TYPED_TEST
scpeters Nov 2, 2023
49de232
Add test to show seg-fault with unsorted links
scpeters Nov 2, 2023
48b369e
Merge branch 'scpeters/bullet_outoforderlinks_test' into bullet_outof…
scpeters Nov 2, 2023
e689f8b
add comments and fix style
iche033 Nov 6, 2023
00358f7
Merge branch 'gz-physics6' into bullet_outoforderlinks_fix
iche033 Nov 6, 2023
0a88d1d
wip
iche033 Nov 8, 2023
ef0ef82
change to use struct, rename world file to sdf, code cleanup
iche033 Nov 8, 2023
dd4c4be
Merge branch 'bullet_outoforderlinks_fix' into bullet_nested_model
iche033 Nov 8, 2023
a3fb96c
Merge branch 'gz-physics6' into bullet_nested_model
iche033 Nov 8, 2023
811bb13
working
iche033 Nov 10, 2023
08e7bd5
merge from gz-physics6
iche033 Nov 10, 2023
65770b5
Fix link/joint to model ref, tests passing
iche033 Nov 11, 2023
b228f17
support world model feature
iche033 Nov 13, 2023
d335865
clean up
iche033 Nov 13, 2023
679ed5d
more clean up
iche033 Nov 14, 2023
ab31c26
more cleanup
iche033 Nov 14, 2023
00dba93
lint
iche033 Nov 14, 2023
1e2bcdd
update remove logic, cleanup
iche033 Nov 14, 2023
53e1ee5
fix removing model with constraints in bullet-featherstone (#577)
iche033 Nov 15, 2023
2c85f5e
Support ConstructSdfJoint feature and add all links
iche033 Nov 17, 2023
116fc2a
Merge remote-tracking branch 'refs/remotes/origin/bullet_nested_model…
iche033 Nov 17, 2023
06016b7
add warning msg for floating bodies / subtrees
iche033 Nov 17, 2023
bc1219a
typo and style
iche033 Nov 17, 2023
88962e8
add ifdef for bullet version in 20.04
iche033 Nov 17, 2023
1292f73
fix build and warning
iche033 Nov 17, 2023
250ced5
Merge branch 'gz-physics6' into bullet_nested_model
scpeters Nov 20, 2023
26471eb
typo
iche033 Nov 29, 2023
15aab54
expand test
iche033 Nov 30, 2023
2681ea0
add bullet ver check in test
iche033 Nov 30, 2023
575e73b
update bullet ver check in test, simplify joint to link pose function…
iche033 Dec 2, 2023
a283778
style
iche033 Dec 2, 2023
b963af1
update bullet ver target def
iche033 Dec 4, 2023
f287996
Merge branch 'gz-physics6' into bullet_nested_model
iche033 Dec 8, 2023
9ec4207
Merge branch 'gz-physics6' into bullet_nested_model
scpeters Jan 19, 2024
2123ad0
Merge branch 'gz-physics6' into bullet_nested_model
iche033 Jan 30, 2024
8e99116
fix merge
iche033 Jan 30, 2024
44e0958
Merge branch 'gz-physics6' into bullet_nested_model
iche033 Feb 21, 2024
ca1715e
typos, comments, style
iche033 Mar 5, 2024
d08d0ef
check null model, update test
iche033 Mar 5, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
145 changes: 134 additions & 11 deletions bullet-featherstone/src/Base.hh
Original file line number Diff line number Diff line change
Expand Up @@ -84,12 +84,14 @@ struct ModelInfo
Identity world;
int indexInWorld;
Eigen::Isometry3d baseInertiaToLinkFrame;
std::unique_ptr<btMultiBody> body;
std::shared_ptr<btMultiBody> body;

std::vector<std::size_t> linkEntityIds;
std::vector<std::size_t> jointEntityIds;
std::vector<std::size_t> nestedModelEntityIds;
std::unordered_map<std::string, std::size_t> linkNameToEntityId;
std::unordered_map<std::string, std::size_t> jointNameToEntityId;
std::unordered_map<std::string, std::size_t> nestedModelNameToEntityId;

/// These are joints that connect this model to other models, e.g. fixed
/// constraints.
Expand All @@ -99,7 +101,7 @@ struct ModelInfo
std::string _name,
Identity _world,
Eigen::Isometry3d _baseInertiaToLinkFrame,
std::unique_ptr<btMultiBody> _body)
std::shared_ptr<btMultiBody> _body)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why was this ownership change (here and elsewhere) necessary? Is a unique_ptr not still sufficient here?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

yeah, all we now use a single btMultiBody to store links from both the top level model and also nested models. So the nested model now keeps a shared pointer to it.

: name(std::move(_name)),
world(std::move(_world)),
baseInertiaToLinkFrame(_baseInertiaToLinkFrame),
Expand Down Expand Up @@ -273,14 +275,24 @@ class Base : public Implements3d<FeatureList<Feature>>
const auto id = this->GetNextEntity();
auto world = std::make_shared<WorldInfo>(std::move(_worldInfo));
this->worlds[id] = world;
return this->GenerateIdentity(id, world);
auto worldID = this->GenerateIdentity(id, world);

auto worldModel = std::make_shared<ModelInfo>(
world->name, worldID,
Eigen::Isometry3d::Identity(), nullptr);
this->models[id] = worldModel;
world->modelNameToEntityId[worldModel->name] = id;
worldModel->indexInWorld = -1;
world->modelIndexToEntityId[worldModel->indexInWorld] = id;

return worldID;
}

public: inline Identity AddModel(
std::string _name,
Identity _worldID,
Eigen::Isometry3d _baseInertialToLinkFrame,
std::unique_ptr<btMultiBody> _body)
std::shared_ptr<btMultiBody> _body)
{
const auto id = this->GetNextEntity();
auto model = std::make_shared<ModelInfo>(
Expand All @@ -292,6 +304,30 @@ class Base : public Implements3d<FeatureList<Feature>>
world->modelNameToEntityId[model->name] = id;
model->indexInWorld = world->nextModelIndex++;
world->modelIndexToEntityId[model->indexInWorld] = id;

auto worldModel = this->models.at(model->world);
worldModel->nestedModelEntityIds.push_back(id);
worldModel->nestedModelNameToEntityId[model->name] = id;

return this->GenerateIdentity(id, model);
}

public: inline Identity AddNestedModel(
std::string _name,
Identity _parentID,
Identity _worldID,
Eigen::Isometry3d _baseInertialToLinkFrame,
std::shared_ptr<btMultiBody> _body)
{
const auto id = this->GetNextEntity();
auto model = std::make_shared<ModelInfo>(
std::move(_name), std::move(_worldID),
std::move(_baseInertialToLinkFrame), std::move(_body));

this->models[id] = model;
const auto parentModel = this->models.at(_parentID);
parentModel->nestedModelEntityIds.push_back(id);
parentModel->nestedModelNameToEntityId[model->name] = id;
return this->GenerateIdentity(id, model);
}

Expand All @@ -303,13 +339,7 @@ class Base : public Implements3d<FeatureList<Feature>>

auto *model = this->ReferenceInterface<ModelInfo>(_linkInfo.model);
model->linkNameToEntityId[link->name] = id;
if (link->indexInModel.has_value())
{
// We expect the links to be added in order
assert(static_cast<std::size_t>(*link->indexInModel + 1) ==
model->linkEntityIds.size());
}
else
if (!link->indexInModel.has_value())
{
// We are adding the root link. This means the model should not already
// have a root link
Expand Down Expand Up @@ -357,6 +387,99 @@ class Base : public Implements3d<FeatureList<Feature>>
return this->GenerateIdentity(id, joint);
}

public: bool RemoveModelImpl(const Identity &_parentID,
const Identity &_modelID)
{
auto *model = this->ReferenceInterface<ModelInfo>(_modelID);
if (!model)
return false;

bool isNested = this->worlds.find(_parentID) == this->worlds.end();

// Remove nested models
for (auto &nestedModelID : model->nestedModelEntityIds)
{
this->RemoveModelImpl(_modelID, this->GenerateIdentity(nestedModelID,
this->models.at(nestedModelID)));
}
model->nestedModelEntityIds.clear();

// remove references in parent model or world model
auto parentModelIt = this->models.find(_parentID);
if (parentModelIt != this->models.end())
{
auto parentModel = parentModelIt->second;
auto nestedModelIt =
parentModel->nestedModelNameToEntityId.find(model->name);
if (nestedModelIt !=
parentModel->nestedModelNameToEntityId.end())
{
std::size_t nestedModelID = nestedModelIt->second;
parentModel->nestedModelNameToEntityId.erase(nestedModelIt);
parentModel->nestedModelEntityIds.erase(std::remove(
parentModel->nestedModelEntityIds.begin(),
parentModel->nestedModelEntityIds.end(), nestedModelID),
parentModel->nestedModelEntityIds.end());
}
}

// If nested, we are done here. No need to remove multibody
iche033 marked this conversation as resolved.
Show resolved Hide resolved
if (isNested)
{
return true;
}

// Remove model from world
auto *world = this->ReferenceInterface<WorldInfo>(model->world);
if (!world)
return false;
if (world->modelIndexToEntityId.erase(model->indexInWorld) == 0)
{
// The model has already been removed at some point
return false;
}
world->modelNameToEntityId.erase(model->name);

// Remove all constraints related to this model
for (const auto jointID : model->jointEntityIds)
{
const auto joint = this->joints.at(jointID);
if (joint->motor)
{
world->world->removeMultiBodyConstraint(joint->motor.get());
}
if (joint->fixedConstraint)
{
world->world->removeMultiBodyConstraint(joint->fixedConstraint.get());
}
if (joint->jointLimits)
{
world->world->removeMultiBodyConstraint(joint->jointLimits.get());
}
this->joints.erase(jointID);
}
// \todo(iche033) Remove external constraints related to this model
// (model->external_constraints) once this is supported

world->world->removeMultiBody(model->body.get());
for (const auto linkID : model->linkEntityIds)
{
const auto &link = this->links.at(linkID);
if (link->collider)
{
world->world->removeCollisionObject(link->collider.get());
for (const auto shapeID : link->collisionEntityIds)
this->collisions.erase(shapeID);
}

this->links.erase(linkID);
}

this->models.erase(_modelID);

return true;
}

public: ~Base() override {
// The order of destruction between meshesGImpact and triangleMeshes is
// important.
Expand Down
154 changes: 112 additions & 42 deletions bullet-featherstone/src/EntityManagementFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -206,53 +206,16 @@ Identity EntityManagementFeatures::ConstructEmptyWorld(
bool EntityManagementFeatures::RemoveModel(const Identity &_modelID)
{
auto *model = this->ReferenceInterface<ModelInfo>(_modelID);
auto *world = this->ReferenceInterface<WorldInfo>(model->world);
if (world->modelIndexToEntityId.erase(model->indexInWorld) == 0)
{
// The model has already been removed at some point.
if (!model)
return false;
Comment on lines 208 to 210
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

nit: I think this check could be removed, since RemoveModelImpl performs the same check for the existence of the model

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

removed. ca1715e

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

well, now I think I was wrong, since I didn't notice that we are dereferencing model on the next line. Those two lines from ca1715e should probably come back. Thanks for your patience

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

ah yes, reverted change. d08d0ef

}

world->modelNameToEntityId.erase(model->name);

// Remove all constraints related to this model
for (auto constraint_index : model->external_constraints)
{
const auto joint = this->joints.at(constraint_index);
const auto &constraint =
std::get<std::unique_ptr<btMultiBodyConstraint>>(joint->identifier);
world->world->removeMultiBodyConstraint(constraint.get());
this->joints.erase(constraint_index);
}

world->world->removeMultiBody(model->body.get());
for (const auto linkID : model->linkEntityIds)
{
const auto &link = this->links.at(linkID);
if (link->collider)
{
world->world->removeCollisionObject(link->collider.get());
for (const auto shapeID : link->collisionEntityIds)
this->collisions.erase(shapeID);
}

this->links.erase(linkID);
}

for (const auto jointID : model->jointEntityIds)
this->joints.erase(jointID);

this->models.erase(_modelID);
return true;
return this->RemoveModelImpl(model->world, _modelID);
}

/////////////////////////////////////////////////
bool EntityManagementFeatures::ModelRemoved(
const Identity &_modelID) const
{
auto *model = this->ReferenceInterface<ModelInfo>(_modelID);
auto *world = this->ReferenceInterface<WorldInfo>(model->world);
return world->modelIndexToEntityId.count(model->indexInWorld) == 0;
return this->models.find(_modelID) == this->models.end();
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -283,6 +246,55 @@ bool EntityManagementFeatures::RemoveModelByName(
this->GenerateIdentity(it->second, this->models.at(it->second)));
}

/////////////////////////////////////////////////
bool EntityManagementFeatures::RemoveNestedModelByIndex(
const Identity &_modelID, std::size_t _nestedModelIndex)
{
auto *model = this->ReferenceInterface<ModelInfo>(_modelID);
if (!model)
return false;
if (_nestedModelIndex >= model->nestedModelEntityIds.size())
return false;
const auto nestedModelID = model->nestedModelEntityIds[_nestedModelIndex];

auto modelIt = this->models.find(nestedModelID);
if (modelIt != this->models.end())
{
return RemoveModelImpl(_modelID,
this->GenerateIdentity(modelIt->first, modelIt->second));
}
return false;
}

/////////////////////////////////////////////////
bool EntityManagementFeatures::RemoveNestedModelByName(const Identity &_modelID,
const std::string &_modelName)
{
auto *model = this->ReferenceInterface<ModelInfo>(_modelID);
if (!model)
return false;

unsigned int nestedModelID = 0u;
auto nestedModelIt = model->nestedModelNameToEntityId.find(_modelName);
if (nestedModelIt != model->nestedModelNameToEntityId.end())
{
nestedModelID = nestedModelIt->second;
}
else
{
return false;
}

auto modelIt = this->models.find(nestedModelID);
if (modelIt != this->models.end())
{
return RemoveModelImpl(_modelID,
this->GenerateIdentity(modelIt->first, modelIt->second));
}
return false;
}


/////////////////////////////////////////////////
const std::string &EntityManagementFeatures::GetEngineName(
const Identity &) const
Expand Down Expand Up @@ -359,9 +371,15 @@ Identity EntityManagementFeatures::GetEngineOfWorld(

/////////////////////////////////////////////////
std::size_t EntityManagementFeatures::GetModelCount(
const Identity &) const
const Identity &_worldID) const
{
return this->models.size();
// Get world model and return its nested model count
auto modelIt = this->models.find(_worldID);
if (modelIt != this->models.end())
{
return modelIt->second->nestedModelEntityIds.size();
}
return 0u;
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -414,6 +432,58 @@ Identity EntityManagementFeatures::GetWorldOfModel(
return this->ReferenceInterface<ModelInfo>(_modelID)->world;
}

/////////////////////////////////////////////////
std::size_t EntityManagementFeatures::GetNestedModelCount(
const Identity &_modelID) const
{
return this->ReferenceInterface<ModelInfo>(
_modelID)->nestedModelEntityIds.size();
}

/////////////////////////////////////////////////
Identity EntityManagementFeatures::GetNestedModel(
const Identity &_modelID, const std::size_t _modelIndex) const
{
const auto modelInfo = this->ReferenceInterface<ModelInfo>(_modelID);
if (_modelIndex >= modelInfo->nestedModelEntityIds.size())
{
return this->GenerateInvalidId();
}

const auto nestedModelID = modelInfo->nestedModelEntityIds[_modelIndex];

// If the model doesn't exist in "models", it means the containing entity has
// been removed.
if (this->models.find(nestedModelID) != this->models.end())
{
return this->GenerateIdentity(nestedModelID,
this->models.at(nestedModelID));
}
else
{
return this->GenerateInvalidId();
}
}

/////////////////////////////////////////////////
Identity EntityManagementFeatures::GetNestedModel(
const Identity &_modelID, const std::string &_modelName) const
{
const auto modelInfo = this->ReferenceInterface<ModelInfo>(_modelID);
auto modelIt = modelInfo->nestedModelNameToEntityId.find(_modelName);
if (modelIt == modelInfo->nestedModelNameToEntityId.end())
return this->GenerateInvalidId();
auto nestedModelID = modelIt->second;
return this->GenerateIdentity(nestedModelID,
this->models.at(nestedModelID));
}

/////////////////////////////////////////////////
Identity EntityManagementFeatures::GetWorldModel(const Identity &_worldID) const
{
return this->GenerateIdentity(_worldID, this->models.at(_worldID));
}

} // namespace bullet_featherstone
} // namespace physics
} // namespace gz
Loading