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: Fix bounding box for collisions with pose offset #647

Merged
merged 3 commits into from
Jun 5, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
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
103 changes: 54 additions & 49 deletions bullet-featherstone/src/KinematicsFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,30 +22,40 @@
namespace physics {
namespace bullet_featherstone {


FrameData3d getNonBaseLinkFrameData(const ModelInfo *_modelInfo,
const LinkInfo *_linkInfo)
{
const auto index = _linkInfo->indexInModel.value();
FrameData3d data;
data.pose = GetWorldTransformOfLink(*_modelInfo, *_linkInfo);
const auto &link = _modelInfo->body->getLink(index);
data.linearVelocity = convert(link.m_absFrameTotVelocity.getLinear());
data.angularVelocity = convert(link.m_absFrameTotVelocity.getAngular());
return data;
}

/////////////////////////////////////////////////
FrameData3d KinematicsFeatures::FrameDataRelativeToWorld(
const FrameID &_id) const
{
const auto linkIt = this->links.find(_id.ID());
bool isModel = false;
bool isCollision = false;
const ModelInfo *model = nullptr;
Eigen::Isometry3d collisionPoseOffset = Eigen::Isometry3d();

const auto linkIt = this->links.find(_id.ID());
if (linkIt != this->links.end())
{
const auto &linkInfo = linkIt->second;
const auto indexOpt = linkInfo->indexInModel;
model = this->ReferenceInterface<ModelInfo>(linkInfo->model);

if (indexOpt.has_value())
if (linkInfo->indexInModel.has_value())
{
const auto index = *indexOpt;
FrameData data;
data.pose = GetWorldTransformOfLink(*model, *linkInfo);
const auto &link = model->body->getLink(index);
data.linearVelocity = convert(link.m_absFrameTotVelocity.getLinear());
data.angularVelocity = convert(link.m_absFrameTotVelocity.getAngular());
return data;
return getNonBaseLinkFrameData(model, linkInfo.get());
}

// If indexOpt is nullopt then the link is the base link which will be
// If indexInModel is nullopt then the link is the base link which will be
// calculated below.
}
else
Expand All @@ -59,60 +69,55 @@
if (linkIt2 != this->links.end())
{
const auto &linkInfo2 = linkIt2->second;
const auto indexOpt2 = linkInfo2->indexInModel;
model = this->ReferenceInterface<ModelInfo>(linkInfo2->model);

if (indexOpt2.has_value())
if (linkInfo2->indexInModel.has_value())
{
const auto index2 = *indexOpt2;
FrameData data;
data.pose = GetWorldTransformOfLink(*model, *linkInfo2);
const auto &link = model->body->getLink(index2);
data.linearVelocity = convert(
link.m_absFrameTotVelocity.getLinear());
data.angularVelocity = convert(
link.m_absFrameTotVelocity.getAngular());
return data;
return getNonBaseLinkFrameData(model, linkInfo2.get());
}
}
}

auto collisionIt = this->collisions.find(_id.ID());
if (collisionIt != this->collisions.end())
else
{
const auto &collisionInfo = collisionIt->second;

const auto linkIt2 = this->links.find(collisionInfo->link);
if (linkIt2 != this->links.end())
auto collisionIt = this->collisions.find(_id.ID());
if (collisionIt != this->collisions.end())
{
const auto &linkInfo2 = linkIt2->second;
const auto indexOpt2 = linkInfo2->indexInModel;
model = this->ReferenceInterface<ModelInfo>(linkInfo2->model);
isCollision = true;
const auto &collisionInfo = collisionIt->second;

if (indexOpt2.has_value())
const auto linkIt2 = this->links.find(collisionInfo->link);
if (linkIt2 != this->links.end())
{
const auto index2 = *indexOpt2;
FrameData data;
data.pose = GetWorldTransformOfLink(*model, *linkInfo2);
const auto &link = model->body->getLink(index2);
data.linearVelocity = convert(
link.m_absFrameTotVelocity.getLinear());
data.angularVelocity = convert(
link.m_absFrameTotVelocity.getAngular());
return data;
const auto &linkInfo2 = linkIt2->second;
model = this->ReferenceInterface<ModelInfo>(linkInfo2->model);
collisionPoseOffset = collisionInfo->linkToCollision;
if (linkInfo2->indexInModel.has_value())
{
auto data = getNonBaseLinkFrameData(model, linkInfo2.get());
data.pose = data.pose * collisionPoseOffset;
azeey marked this conversation as resolved.
Show resolved Hide resolved
return data;

Check warning on line 97 in bullet-featherstone/src/KinematicsFeatures.cc

View check run for this annotation

Codecov / codecov/patch

bullet-featherstone/src/KinematicsFeatures.cc#L95-L97

Added lines #L95 - L97 were not covered by tests
}
}
}
else
{
auto modelIt = this->models.find(_id.ID());
if (modelIt != this->models.end())
{
model = modelIt->second.get();
isModel = true;
}
}
}

if (!model || model->body == nullptr)
model = this->FrameInterface<ModelInfo>(_id);
}

FrameData data;
if(model && model->body)
if (model && model->body)
{
data.pose = convert(model->body->getBaseWorldTransform())
* model->baseInertiaToLinkFrame;
data.pose = convert(model->body->getBaseWorldTransform());
Copy link
Contributor

Choose a reason for hiding this comment

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

Don't we have to account for

  • The offset from the model to the base link, i.e, the links pose in SDF? Do we have a test that covers this?
  • The offset of the link frame to the center of mass? I thought that's what model->baseInertiaToLinkFrame was there for .

Copy link
Contributor Author

@iche033 iche033 Jun 4, 2024

Choose a reason for hiding this comment

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

This line computes the pose for the model. The next 2 lines takes into account the pose of the link (and inertia offset if any) which uses model->baseInertiaToLinkFrame. I think that's correct? I added a test in 5c6ec0f that checks the frame data for a link and a collision, both of which have a pose offset.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

expanded test to cover both base and non-base links. 84054fa

Copy link
Contributor

Choose a reason for hiding this comment

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

It looks like this test is not testing model frame semantics at all. Fortunately, we currently don't use it in gz-sim, but it would be good to fix (not in this PR). I've added a failing test in the azeey/kinematic_feature_failing_test branch. Evidently, dartsim fails the test as well.

if (!isModel)
data.pose = data.pose * model->baseInertiaToLinkFrame;
if (isCollision)
azeey marked this conversation as resolved.
Show resolved Hide resolved
data.pose = data.pose * collisionPoseOffset;
data.linearVelocity = convert(model->body->getBaseVel());
data.angularVelocity = convert(model->body->getBaseOmega());
}
Expand Down
3 changes: 2 additions & 1 deletion bullet-featherstone/src/KinematicsFeatures.hh
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,8 @@ namespace bullet_featherstone {
struct KinematicsFeatureList : gz::physics::FeatureList<
LinkFrameSemantics,
ModelFrameSemantics,
FreeGroupFrameSemantics
FreeGroupFrameSemantics,
ShapeFrameSemantics
> { };

class KinematicsFeatures :
Expand Down
2 changes: 0 additions & 2 deletions bullet-featherstone/src/ShapeFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,6 @@ AlignedBox3d ShapeFeatures::GetShapeAxisAlignedBoundingBox(
t.setIdentity();
btVector3 minBox(0, 0, 0);
btVector3 maxBox(0, 0, 0);
btVector3 minBox2(0, 0, 0);
btVector3 maxBox2(0, 0, 0);
collider->collider->getAabb(t, minBox, maxBox);
return math::eigen3::convert(math::AxisAlignedBox(
math::Vector3d(minBox[0], minBox[1], minBox[2]),
Expand Down
22 changes: 14 additions & 8 deletions test/common_test/link_features.cc
Original file line number Diff line number Diff line change
Expand Up @@ -293,14 +293,26 @@ TYPED_TEST(LinkFeaturesTest, JointSetCommand)
}
}

TYPED_TEST(LinkFeaturesTest, AxisAlignedBoundingBox)
using LinkBoundingBoxFeaturesList = gz::physics::FeatureList<
gz::physics::ForwardStep,
gz::physics::sdf::ConstructSdfWorld,
gz::physics::GetEntities,
gz::physics::GetLinkBoundingBox,
gz::physics::GetModelBoundingBox
>;

using LinkBoundingBoxFeaturesTestTypes =
LinkFeaturesTest<LinkBoundingBoxFeaturesList>;

TEST_F(LinkBoundingBoxFeaturesTestTypes, AxisAlignedBoundingBox)
{
for (const std::string &name : this->pluginNames)
{
std::cout << "Testing plugin: " << name << std::endl;
gz::plugin::PluginPtr plugin = this->loader.Instantiate(name);

auto engine = gz::physics::RequestEngine3d<LinkFeaturesList>::From(plugin);
auto engine =
gz::physics::RequestEngine3d<LinkBoundingBoxFeaturesList>::From(plugin);
ASSERT_NE(nullptr, engine);

sdf::Root root;
Expand All @@ -313,9 +325,6 @@ TYPED_TEST(LinkFeaturesTest, AxisAlignedBoundingBox)
auto world = engine->ConstructWorld(*root.WorldByIndex(0));
EXPECT_NE(nullptr, world);

EXPECT_NE(nullptr, world);
world->SetGravity(Eigen::Vector3d{0, 0, -9.8});

auto model = world->GetModel("double_pendulum_with_base");
auto baseLink = model->GetLink("base");
auto bbox = baseLink->GetAxisAlignedBoundingBox();
Expand Down Expand Up @@ -364,9 +373,6 @@ TYPED_TEST(LinkFeaturesTest, ModelAxisAlignedBoundingBox)
auto world = engine->ConstructWorld(*root.WorldByIndex(0));
EXPECT_NE(nullptr, world);

EXPECT_NE(nullptr, world);
world->SetGravity(Eigen::Vector3d{0, 0, -9.8});

auto model = world->GetModel("sphere");
auto bbox = model->GetAxisAlignedBoundingBox();
AssertVectorApprox vectorPredicate(1e-4);
Expand Down
Loading