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

Add support to get link AABB from its collisions #2787

Open
wants to merge 4 commits into
base: gz-sim9
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 2 commits
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
22 changes: 22 additions & 0 deletions include/gz/sim/Link.hh
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
#include <gz/math/Pose3.hh>
#include <gz/math/Quaternion.hh>
#include <gz/math/Vector3.hh>
#include <gz/math/AxisAlignedBox.hh>

#include <gz/sim/config.hh>
#include <gz/sim/EntityComponentManager.hh>
Expand Down Expand Up @@ -356,6 +357,27 @@ namespace gz
const math::Vector3d &_torque,
const math::Vector3d &_offset) const;

/// \brief Get the axis-aligned bounding box of the link.
/// It generates an axis-aligned bounding box for a link based on the
/// collision shapes attached to the it. The link bounding box is
/// generated by merging all the bounding boxes of the collision
/// geometries.
/// \param _ecm
Copy link
Contributor

Choose a reason for hiding this comment

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

Suggested change
/// \param _ecm
/// \param _ecm Entity-component manager.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Done in 7cbf8a3

/// \return Link's axis-aligned bounding box in the link frame or
/// nullopt if the link does not have collisions. It may return an
/// empty bounding box if all of the link collisions are empty.
public: std::optional<math::AxisAlignedBox> AxisAlignedBox(
const EntityComponentManager &_ecm) const;

/// \brief Get the link's axis-aligned bounding box in the world frame
/// \param _ecm Entity-component manager.
/// \return Link's axis-aligned bounding box in the world frame or
/// nullopt if the link does not have collisions. It may return an
/// empty bounding box if all of the link collisions are empty.
/// \sa AxisAlignedBox
public: std::optional<math::AxisAlignedBox> WorldAxisAlignedBox(
const EntityComponentManager &_ecm) const;

/// \brief Pointer to private data.
private: std::unique_ptr<LinkPrivate> dataPtr;
};
Expand Down
15 changes: 15 additions & 0 deletions include/gz/sim/Util.hh
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include <vector>

#include <gz/common/Mesh.hh>
#include <gz/math/AxisAlignedBox.hh>
#include <gz/math/Pose3.hh>
#include <sdf/Mesh.hh>

Expand Down Expand Up @@ -323,6 +324,20 @@ namespace gz
GZ_SIM_VISIBLE const common::Mesh *optimizeMesh(const sdf::Mesh &_meshSdf,
const common::Mesh &_mesh);

/// \brief Transform an axis-aligned bounding box by a pose.
/// \param[in] _aabb Axis-aligned bounding box to transform.
/// \param[in] _pose Pose to transform the bounding box by.
/// \return The axis-aligned bounding box in the pose target frame.
GZ_SIM_VISIBLE math::AxisAlignedBox transformAxisAlignedBox(
const math::AxisAlignedBox & _aabb,
const math::Pose3d & _pose);

/// \brief Compute the axis-aligned bounding box of a mesh.
/// \param _sdfMesh Mesh SDF DOM.
/// \return The AABB of the mesh in its local frame.
GZ_SIM_VISIBLE math::AxisAlignedBox meshAxisAlignedBox(
const sdf::Mesh _sdfMesh);

/// \brief Environment variable holding resource paths.
const std::string kResourcePathEnv{"GZ_SIM_RESOURCE_PATH"};

Expand Down
6 changes: 6 additions & 0 deletions python/src/gz/sim/Link.cc
Original file line number Diff line number Diff line change
Expand Up @@ -191,6 +191,12 @@ void defineSimLink(py::object module)
"Add a wrench expressed in world coordinates and applied to "
"the link at an offset from the link's origin. This wrench is applied "
"for one simulation step.")
.def("axis_aligned_box", &gz::sim::Link::AxisAlignedBox,
py::arg("ecm"),
"Get the Link's axis-aligned box represented in the link frame.")
.def("world_axis_aligned_box", &gz::sim::Link::WorldAxisAlignedBox,
py::arg("ecm"),
"Get the Link's axis-aligned box represented in the world frame.")
.def("__copy__",
[](const gz::sim::Link &self)
{
Expand Down
14 changes: 13 additions & 1 deletion python/test/link_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@

from gz_test_deps.common import set_verbosity
from gz_test_deps.sim import K_NULL_ENTITY, TestFixture, Link, Model, World, world_entity
from gz_test_deps.math import Inertiald, Matrix3d, Vector3d, Pose3d
from gz_test_deps.math import AxisAlignedBox, Inertiald, Matrix3d, Vector3d, Pose3d

class TestModel(unittest.TestCase):
post_iterations = 0
Expand Down Expand Up @@ -88,6 +88,18 @@ def on_pre_udpate_cb(_info, _ecm):
self.assertEqual(0, link.world_kinetic_energy(_ecm))
link.enable_velocity_checks(_ecm, False)
link.enable_acceleration_checks(_ecm, False)
# Axis Aligned Box Test
# Offset of 0.5 meters along z-axis
self.assertEqual(
AxisAlignedBox(Vector3d(-0.5, -0.5, 0), Vector3d(0.5, 0.5, 1)),
link.axis_aligned_box(_ecm)
)
# World Axis Aligned Box Test
# Same as above since the link is at the origin
self.assertEqual(
AxisAlignedBox(Vector3d(-0.5, -0.5, 0), Vector3d(0.5, 0.5, 1)),
link.world_axis_aligned_box(_ecm)
)


def on_udpate_cb(_info, _ecm):
Expand Down
54 changes: 54 additions & 0 deletions src/Link.cc
Original file line number Diff line number Diff line change
Expand Up @@ -513,3 +513,57 @@ void Link::AddWorldWrench(EntityComponentManager &_ecm,
msgs::Convert(linkWrenchComp->Data().torque()) + torqueWithOffset);
}
}

//////////////////////////////////////////////////
std::optional<math::AxisAlignedBox> Link::AxisAlignedBox(
const gz::sim::EntityComponentManager & ecm) const
{
math::AxisAlignedBox linkAabb;
auto collisions = this->Collisions(ecm);

if (collisions.empty())
{
return std::nullopt;
}

for (auto & entity : collisions)
{
auto collision = ecm.ComponentData<components::CollisionElement>(entity);
auto geom = collision.value().Geom();
auto geomAabb = geom->AxisAlignedBox(&sim::meshAxisAlignedBox);

if (!geomAabb.has_value() || geomAabb == math::AxisAlignedBox())
{
gzwarn << "Failed to get bounding box for collision entity ["
<< entity << "]. It will be ignored in the computation "
<< "of the link bounding box." << std::endl;
continue;
}

// Merge geometry AABB (expressed in link frame) into link AABB
linkAabb += sim::transformAxisAlignedBox(
geomAabb.value(),
ecm.ComponentData<components::Pose>(entity).value()
);
}

return linkAabb;
}

//////////////////////////////////////////////////
std::optional<math::AxisAlignedBox> Link::WorldAxisAlignedBox(
const gz::sim::EntityComponentManager & ecm) const
{
auto linkAabb = this->AxisAlignedBox(ecm);

if (!linkAabb.has_value())
{
return std::nullopt;
}

// Return the link AABB in the world frame
return sim::transformAxisAlignedBox(
linkAabb.value(),
this->WorldPose(ecm).value()
);
}
28 changes: 28 additions & 0 deletions src/Util.cc
Original file line number Diff line number Diff line change
Expand Up @@ -989,6 +989,34 @@ const common::Mesh *optimizeMesh(const sdf::Mesh &_meshSdf,
return optimizedMesh;
}

math::AxisAlignedBox meshAxisAlignedBox(sdf::Mesh _sdfMesh)
{
auto mesh = loadMesh(_sdfMesh);
if (!mesh)
{
gzwarn << "Mesh could not be loaded. Invalidating its bounding box."
<< std::endl;

return math::AxisAlignedBox();
}

// Get the mesh's bounding box
math::Vector3d meshCenter, meshMin, meshMax;
mesh->AABB(meshCenter, meshMin, meshMax);

return math::AxisAlignedBox(meshMin, meshMax);
}

math::AxisAlignedBox transformAxisAlignedBox(
const math::AxisAlignedBox & _aabb,
const math::Pose3d & _pose)
{
return math::AxisAlignedBox(
_pose.CoordPositionAdd(_aabb.Min()),
_pose.CoordPositionAdd(_aabb.Max())
);
}

}
}
}
80 changes: 80 additions & 0 deletions src/Util_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1032,3 +1032,83 @@ TEST_F(UtilTest, LoadMesh)
EXPECT_NE(nullptr, optimizedMesh);
EXPECT_EQ(16u, optimizedMesh->SubMeshCount());
}

/////////////////////////////////////////////////
TEST_F(UtilTest, MeshAxisAlignedBoundingBox)
{
sdf::Mesh meshSdf;
math::AxisAlignedBox emptyBox, aab;
EXPECT_EQ(emptyBox, meshAxisAlignedBox(meshSdf));

meshSdf.SetUri("invalid_uri");
meshSdf.SetFilePath("invalid_filepath");
EXPECT_EQ(emptyBox, meshAxisAlignedBox(meshSdf));

meshSdf.SetUri("name://unit_box");
aab = meshAxisAlignedBox(meshSdf);
EXPECT_NE(emptyBox, aab);
EXPECT_EQ(aab.Size(), math::Vector3d::One);
EXPECT_EQ(aab.Min(), math::Vector3d(-0.5, -0.5, -0.5));
EXPECT_EQ(aab.Max(), math::Vector3d(0.5, 0.5, 0.5));
EXPECT_EQ(aab.Center(), math::Vector3d::Zero);

meshSdf.SetUri("duck.dae");
std::string filePath = common::joinPaths(std::string(PROJECT_SOURCE_PATH),
Copy link
Contributor

Choose a reason for hiding this comment

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

include <string>

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Done in 469a446

"test", "media", "duck.dae");
meshSdf.SetFilePath(filePath);
aab = meshAxisAlignedBox(meshSdf);
EXPECT_NE(emptyBox, aab);

// Expected values obtained from the mesh file using Blender:
auto minExp = math::Vector3d(-69.2985, 9.92937, -61.3282) * 1e-2;
auto maxExp = math::Vector3d(96.1799, 163.9700, 53.9252) * 1e-2;

EXPECT_EQ(minExp, aab.Min());
EXPECT_EQ(maxExp, aab.Max());
EXPECT_EQ((minExp + maxExp) / 2, aab.Center());
EXPECT_EQ(maxExp - minExp, aab.Size());
}

/////////////////////////////////////////////////
TEST_F(UtilTest, TransformAxisAlignedBoxFrame)
{
// Creates a pseudo-random vector with values between -max and max
std::srand(std::time(nullptr));
Copy link
Contributor

Choose a reason for hiding this comment

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

include <cstdlib> and <ctime>

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Done in 469a446

auto randomVector3d = [](int max = 1) -> math::Vector3d
{
return (
math::Vector3d(
static_cast<double>(std::rand()),
static_cast<double>(std::rand()),
static_cast<double>(std::rand())
) / RAND_MAX - 0.5 * math::Vector3d::One
) * 2 * max;
};

math::AxisAlignedBox aab(randomVector3d(3), randomVector3d(2));

// Trivial case: identity transform should not change the box
math::Pose3d transform = math::Pose3d::Zero;
math::AxisAlignedBox aabExp = aab;
EXPECT_EQ(aabExp, transformAxisAlignedBox(aab, transform));

// Pure translation offset
transform.Pos() = randomVector3d(10);
aabExp = aab + transform.Pos();
EXPECT_EQ(aabExp, transformAxisAlignedBox(aab, transform));

// Pure rotation of 90 degrees around the z-axis
// x -> y, y -> -x, z -> z
transform.Reset();
transform.Rot() = math::Quaterniond(0, 0, GZ_PI_2);
aabExp = math::AxisAlignedBox(
math::Vector3d(-aab.Max().Y(), aab.Min().X(), aab.Min().Z()),
math::Vector3d(-aab.Min().Y(), aab.Max().X(), aab.Max().Z())
);
EXPECT_EQ(aabExp, transformAxisAlignedBox(aab, transform));

// Full transform: translation and rotation
transform.Pos() = randomVector3d(150);
aabExp = aabExp + transform.Pos();
EXPECT_EQ(aabExp, transformAxisAlignedBox(aab, transform));
}
Loading