Skip to content

Commit

Permalink
fix linting issues
Browse files Browse the repository at this point in the history
Signed-off-by: Rômulo Cerqueira <romulogcerqueira@gmail.com>
  • Loading branch information
romulogcerqueira committed May 16, 2024
1 parent 0676f0f commit a040032
Show file tree
Hide file tree
Showing 5 changed files with 46 additions and 28 deletions.
7 changes: 5 additions & 2 deletions dartsim/src/SimulationFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
*
*/

#include <limits>
#include <memory>
#include <string>
#include <unordered_map>
Expand Down Expand Up @@ -192,8 +193,10 @@ SimulationFeatures::GetRayIntersectionFromLastStep(
else
{
// Set invalid measurements to NaN according to REP-117
intersection.point = Eigen::Vector3d::Constant(std::numeric_limits<double>::quiet_NaN());
intersection.normal = Eigen::Vector3d::Constant(std::numeric_limits<double>::quiet_NaN());
intersection.point =
Eigen::Vector3d::Constant(std::numeric_limits<double>::quiet_NaN());
intersection.normal =
Eigen::Vector3d::Constant(std::numeric_limits<double>::quiet_NaN());
intersection.fraction = std::numeric_limits<double>::quiet_NaN();
}

Expand Down
4 changes: 2 additions & 2 deletions dartsim/src/SimulationFeatures.hh
Original file line number Diff line number Diff line change
Expand Up @@ -99,8 +99,8 @@ class SimulationFeatures :
public: using GetContactsFromLastStepFeature::Implementation<FeaturePolicy3d>
::ContactInternal;

public: using GetRayIntersectionFromLastStepFeature::Implementation<FeaturePolicy3d>
::RayIntersection;
public: using GetRayIntersectionFromLastStepFeature::Implementation<
FeaturePolicy3d>::RayIntersection;

public: SimulationFeatures() = default;
public: ~SimulationFeatures() override = default;
Expand Down
39 changes: 24 additions & 15 deletions dartsim/src/SimulationFeatures_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -86,21 +86,26 @@ TEST_P(RayIntersectionSupportedFixture, RayIntersection)
world->SetCollisionDetector(GetParam());

// ray hits the sphere
auto result = world->GetRayIntersectionFromLastStep(Eigen::Vector3d(-2, 0, 2),
Eigen::Vector3d( 2, 0, 2));
auto result = world->GetRayIntersectionFromLastStep(
Eigen::Vector3d(-2, 0, 2), Eigen::Vector3d( 2, 0, 2));

auto rayIntersection =
result.template Get<gz::physics::World3d<TestFeatureList>::RayIntersection>();
result.template
Get<gz::physics::World3d<TestFeatureList>::RayIntersection>();

double epsilon = 1e-3;
EXPECT_TRUE(rayIntersection.point.isApprox(Eigen::Vector3d(-1, 0, 2), epsilon));
EXPECT_TRUE(rayIntersection.normal.isApprox(Eigen::Vector3d(-1, 0, 0), epsilon));
EXPECT_TRUE(
rayIntersection.point.isApprox(Eigen::Vector3d(-1, 0, 2), epsilon));
EXPECT_TRUE(
rayIntersection.normal.isApprox(Eigen::Vector3d(-1, 0, 0), epsilon));
EXPECT_DOUBLE_EQ(rayIntersection.fraction, 0.25);

// ray does not hit the sphere
result = world->GetRayIntersectionFromLastStep(Eigen::Vector3d( 2, 0, 10),
Eigen::Vector3d(-2, 0, 10));
result = world->GetRayIntersectionFromLastStep(
Eigen::Vector3d( 2, 0, 10), Eigen::Vector3d(-2, 0, 10));
rayIntersection =
result.template Get<gz::physics::World3d<TestFeatureList>::RayIntersection>();
result.template
Get<gz::physics::World3d<TestFeatureList>::RayIntersection>();

ASSERT_TRUE(rayIntersection.point.array().isNaN().any());
ASSERT_TRUE(rayIntersection.normal.array().isNaN().any());
Expand All @@ -112,20 +117,24 @@ TEST_P(RayIntersectionNotSupportedFixture, RayIntersection)
const auto world = LoadWorld(this->engine, common_test::worlds::kSphereSdf);
world->SetCollisionDetector(GetParam());

// ray would hit the sphere, but the collision detector does not support ray intersection
auto result = world->GetRayIntersectionFromLastStep(Eigen::Vector3d(-2, 0, 2),
Eigen::Vector3d(2, 0, 2));
// ray would hit the sphere, but the collision detector does
// not support ray intersection
auto result = world->GetRayIntersectionFromLastStep(
Eigen::Vector3d(-2, 0, 2), Eigen::Vector3d(2, 0, 2));
auto rayIntersection =
result.template Get<gz::physics::World3d<TestFeatureList>::RayIntersection>();
result.template
Get<gz::physics::World3d<TestFeatureList>::RayIntersection>();

ASSERT_TRUE(rayIntersection.point.array().isNaN().any());
ASSERT_TRUE(rayIntersection.normal.array().isNaN().any());
ASSERT_TRUE(std::isnan(rayIntersection.fraction));
}

// Parameterized instantiation of test suites
INSTANTIATE_TEST_SUITE_P(CollisionDetectorsSupported, RayIntersectionSupportedFixture,
INSTANTIATE_TEST_SUITE_P(CollisionDetectorsSupported,
RayIntersectionSupportedFixture,
::testing::Values("bullet"));

INSTANTIATE_TEST_SUITE_P(CollisionDetectorsNotSupported, RayIntersectionNotSupportedFixture,
::testing::Values("ode", "dart", "fcl", "banana"));
INSTANTIATE_TEST_SUITE_P(CollisionDetectorsNotSupported,
RayIntersectionNotSupportedFixture,
::testing::Values("ode", "dart", "fcl", "banana"));
16 changes: 10 additions & 6 deletions include/gz/physics/GetRayIntersection.hh
Original file line number Diff line number Diff line change
Expand Up @@ -28,16 +28,17 @@ namespace gz
{
namespace physics
{
/// \brief GetRayIntersectionFromLastStepFeature is a feature for retrieving the a
/// ray intersection generated in the previous simulation step.
/// \brief GetRayIntersectionFromLastStepFeature is a feature for retrieving
/// the a ray intersection generated in the previous simulation step.
class GZ_PHYSICS_VISIBLE GetRayIntersectionFromLastStepFeature
: public virtual FeatureWithRequirements<ForwardStep>
{
public: template <typename PolicyT>
struct RayIntersectionT
{
public: using Scalar = typename PolicyT::Scalar;
public: using VectorType = typename FromPolicy<PolicyT>::template Use<LinearVector>;
public: using VectorType =
typename FromPolicy<PolicyT>::template Use<LinearVector>;

/// \brief The hit point in the world coordinates
VectorType point;
Expand All @@ -52,9 +53,11 @@ class GZ_PHYSICS_VISIBLE GetRayIntersectionFromLastStepFeature
public: template <typename PolicyT, typename FeaturesT>
class World : public virtual Feature::World<PolicyT, FeaturesT>
{
public: using VectorType = typename FromPolicy<PolicyT>::template Use<LinearVector>;
public: using VectorType =
typename FromPolicy<PolicyT>::template Use<LinearVector>;
public: using RayIntersection = RayIntersectionT<PolicyT>;
public: using RayIntersectionData = SpecifyData<RequireData<RayIntersection>>;
public: using RayIntersectionData =
SpecifyData<RequireData<RayIntersection>>;

/// \brief Get ray intersection generated in the previous simulation step
public: RayIntersectionData GetRayIntersectionFromLastStep(
Expand All @@ -65,7 +68,8 @@ class GZ_PHYSICS_VISIBLE GetRayIntersectionFromLastStepFeature
class Implementation : public virtual Feature::Implementation<PolicyT>
{
public: using RayIntersection = RayIntersectionT<PolicyT>;
public: using VectorType = typename FromPolicy<PolicyT>::template Use<LinearVector>;
public: using VectorType =
typename FromPolicy<PolicyT>::template Use<LinearVector>;

public: virtual RayIntersection GetRayIntersectionFromLastStep(
const Identity &_worldID,
Expand Down
8 changes: 5 additions & 3 deletions include/gz/physics/detail/GetRayIntersection.hh
Original file line number Diff line number Diff line change
Expand Up @@ -30,10 +30,12 @@ namespace physics
template <typename PolicyT, typename FeaturesT>
auto GetRayIntersectionFromLastStepFeature::World<
PolicyT, FeaturesT>::GetRayIntersectionFromLastStep(
const VectorType &_from, const VectorType &_to) const -> RayIntersectionData
const VectorType &_from,
const VectorType &_to) const -> RayIntersectionData
{
auto result = this->template Interface<GetRayIntersectionFromLastStepFeature>()
->GetRayIntersectionFromLastStep(this->identity, _from, _to);
auto result =
this->template Interface<GetRayIntersectionFromLastStepFeature>()
->GetRayIntersectionFromLastStep(this->identity, _from, _to);

RayIntersection intersection{result.point, result.fraction, result.normal};

Expand Down

0 comments on commit a040032

Please sign in to comment.