Skip to content

Commit

Permalink
Link.hh: add Sensor accessor APIs
Browse files Browse the repository at this point in the history
This adds SensorByName, Sensors, and SensorCount accessors
to the Link class.

Signed-off-by: Steve Peters <scpeters@openrobotics.org>
  • Loading branch information
scpeters committed Dec 6, 2024
1 parent aa76c3e commit 3ef40ee
Show file tree
Hide file tree
Showing 4 changed files with 135 additions and 0 deletions.
20 changes: 20 additions & 0 deletions include/gz/sim/Link.hh
Original file line number Diff line number Diff line change
Expand Up @@ -136,6 +136,14 @@ namespace gz
public: sim::Entity CollisionByName(const EntityComponentManager &_ecm,
const std::string &_name) const;

/// \brief Get the ID of a sensor entity which is an immediate child of
/// this link.
/// \param[in] _ecm Entity-component manager.
/// \param[in] _name Sensor name.
/// \return Sensor entity.
public: sim::Entity SensorByName(const EntityComponentManager &_ecm,
const std::string &_name) const;

/// \brief Get the ID of a visual entity which is an immediate child of
/// this link.
/// \param[in] _ecm Entity-component manager.
Expand All @@ -150,6 +158,12 @@ namespace gz
public: std::vector<sim::Entity> Collisions(
const EntityComponentManager &_ecm) const;

/// \brief Get all sensors which are immediate children of this link.
/// \param[in] _ecm Entity-component manager.
/// \return All sensors in this link.
public: std::vector<sim::Entity> Sensors(
const EntityComponentManager &_ecm) const;

/// \brief Get all visuals which are immediate children of this link.
/// \param[in] _ecm Entity-component manager.
/// \return All visuals in this link.
Expand All @@ -162,6 +176,12 @@ namespace gz
/// \return Number of collisions in this link.
public: uint64_t CollisionCount(const EntityComponentManager &_ecm) const;

/// \brief Get the number of sensors which are immediate children of this
/// link.
/// \param[in] _ecm Entity-component manager.
/// \return Number of sensors in this link.
public: uint64_t SensorCount(const EntityComponentManager &_ecm) const;

/// \brief Get the number of visuals which are immediate children of this
/// link.
/// \param[in] _ecm Entity-component manager.
Expand Down
25 changes: 25 additions & 0 deletions src/Link.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
#include "gz/sim/components/Name.hh"
#include "gz/sim/components/ParentEntity.hh"
#include "gz/sim/components/Pose.hh"
#include "gz/sim/components/Sensor.hh"
#include "gz/sim/components/Visual.hh"
#include "gz/sim/components/WindMode.hh"
#include "gz/sim/Util.hh"
Expand Down Expand Up @@ -126,6 +127,16 @@ Entity Link::CollisionByName(const EntityComponentManager &_ecm,
components::Collision());
}

//////////////////////////////////////////////////
Entity Link::SensorByName(const EntityComponentManager &_ecm,
const std::string &_name) const
{
return _ecm.EntityByComponents(
components::ParentEntity(this->dataPtr->id),
components::Name(_name),
components::Sensor());
}

//////////////////////////////////////////////////
Entity Link::VisualByName(const EntityComponentManager &_ecm,
const std::string &_name) const
Expand All @@ -144,6 +155,14 @@ std::vector<Entity> Link::Collisions(const EntityComponentManager &_ecm) const
components::Collision());
}

//////////////////////////////////////////////////
std::vector<Entity> Link::Sensors(const EntityComponentManager &_ecm) const
{
return _ecm.EntitiesByComponents(
components::ParentEntity(this->dataPtr->id),
components::Sensor());
}

//////////////////////////////////////////////////
std::vector<Entity> Link::Visuals(const EntityComponentManager &_ecm) const
{
Expand All @@ -158,6 +177,12 @@ uint64_t Link::CollisionCount(const EntityComponentManager &_ecm) const
return this->Collisions(_ecm).size();
}

//////////////////////////////////////////////////
uint64_t Link::SensorCount(const EntityComponentManager &_ecm) const
{
return this->Sensors(_ecm).size();
}

//////////////////////////////////////////////////
uint64_t Link::VisualCount(const EntityComponentManager &_ecm) const
{
Expand Down
65 changes: 65 additions & 0 deletions src/Link_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,12 @@

#include <gtest/gtest.h>

#include "gz/sim/EntityComponentManager.hh"
#include "gz/sim/Link.hh"
#include "gz/sim/components/Link.hh"
#include "gz/sim/components/Name.hh"
#include "gz/sim/components/ParentEntity.hh"
#include "gz/sim/components/Sensor.hh"

/////////////////////////////////////////////////
TEST(LinkTest, Constructor)
Expand Down Expand Up @@ -74,3 +79,63 @@ TEST(LinkTest, MoveAssignmentOperator)
linkMoved = std::move(link);
EXPECT_EQ(id, linkMoved.Entity());
}

/////////////////////////////////////////////////
TEST(LinkTest, Sensors)
{
// linkA
// - sensorAA
// - sensorAB
//
// linkC

gz::sim::EntityComponentManager ecm;

// Link A
auto linkAEntity = ecm.CreateEntity();
ecm.CreateComponent(linkAEntity, gz::sim::components::Link());
ecm.CreateComponent(linkAEntity,
gz::sim::components::Name("linkA_name"));

// Sensor AA - Child of Link A
auto sensorAAEntity = ecm.CreateEntity();
ecm.CreateComponent(sensorAAEntity, gz::sim::components::Sensor());
ecm.CreateComponent(sensorAAEntity,
gz::sim::components::Name("sensorAA_name"));
ecm.CreateComponent(sensorAAEntity,
gz::sim::components::ParentEntity(linkAEntity));

// Sensor AB - Child of Link A
auto sensorABEntity = ecm.CreateEntity();
ecm.CreateComponent(sensorABEntity, gz::sim::components::Sensor());
ecm.CreateComponent(sensorABEntity,
gz::sim::components::Name("sensorAB_name"));
ecm.CreateComponent(sensorABEntity,
gz::sim::components::ParentEntity(linkAEntity));

// Link C
auto linkCEntity = ecm.CreateEntity();
ecm.CreateComponent(linkCEntity, gz::sim::components::Link());
ecm.CreateComponent(linkCEntity,
gz::sim::components::Name("linkC_name"));

std::size_t foundSensors = 0;

gz::sim::Link linkA(linkAEntity);
auto sensors = linkA.Sensors(ecm);
EXPECT_EQ(2u, sensors.size());
for (const auto &sensor : sensors)
{
if (sensor == sensorAAEntity || sensor == sensorABEntity)
foundSensors++;
}
EXPECT_EQ(foundSensors, sensors.size());

EXPECT_EQ(sensorAAEntity, linkA.SensorByName(ecm, "sensorAA_name"));
EXPECT_EQ(sensorABEntity, linkA.SensorByName(ecm, "sensorAB_name"));
EXPECT_EQ(gz::sim::kNullEntity, linkA.SensorByName(ecm, "invalid"));

gz::sim::Link linkC(linkCEntity);
EXPECT_EQ(0u, linkC.Sensors(ecm).size());
EXPECT_EQ(gz::sim::kNullEntity, linkC.SensorByName(ecm, "invalid"));
}
25 changes: 25 additions & 0 deletions test/integration/link.cc
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
#include <gz/sim/components/Name.hh>
#include <gz/sim/components/ParentEntity.hh>
#include <gz/sim/components/Pose.hh>
#include <gz/sim/components/Sensor.hh>
#include <gz/sim/components/Visual.hh>

#include <gz/sim/EntityComponentManager.hh>
Expand Down Expand Up @@ -170,6 +171,30 @@ TEST_F(LinkIntegrationTest, VisualByName)
EXPECT_EQ(1u, link.VisualCount(ecm));
}

//////////////////////////////////////////////////
TEST_F(LinkIntegrationTest, SensorByName)
{
EntityComponentManager ecm;

// Link
auto eLink = ecm.CreateEntity();
Link link(eLink);
EXPECT_EQ(eLink, link.Entity());
EXPECT_EQ(0u, link.SensorCount(ecm));

// Sensor
auto eSensor = ecm.CreateEntity();
ecm.CreateComponent<components::Sensor>(eSensor, components::Sensor());
ecm.CreateComponent<components::ParentEntity>(eSensor,
components::ParentEntity(eLink));
ecm.CreateComponent<components::Name>(eSensor,
components::Name("sensor_name"));

// Check link
EXPECT_EQ(eSensor, link.SensorByName(ecm, "sensor_name"));
EXPECT_EQ(1u, link.SensorCount(ecm));
}

//////////////////////////////////////////////////
TEST_F(LinkIntegrationTest, CollisionByName)
{
Expand Down

0 comments on commit 3ef40ee

Please sign in to comment.