Skip to content

Commit

Permalink
Add gazebo Entity id to rendering sensor's user data (#1381)
Browse files Browse the repository at this point in the history
Adds the gazebo::Entity id to a rendering::Sensor's UserData object. The main use case is so that we can get back the corresponding gazebo Entity in the rendering thread when processing sensors.

Signed-off-by: Ian Chen <ichen@osrfoundation.org>

Co-authored-by: Nate Koenig <nkoenig@users.noreply.github.com>
Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
  • Loading branch information
3 people committed Mar 15, 2022
1 parent 0f45c17 commit a9563f5
Show file tree
Hide file tree
Showing 3 changed files with 72 additions and 0 deletions.
3 changes: 3 additions & 0 deletions src/rendering/SceneManager.cc
Expand Up @@ -1776,6 +1776,9 @@ bool SceneManager::AddSensor(Entity _gazeboId, const std::string &_sensorName,
return false;
}

// \todo(anyone) change to uint64_t once UserData supports this type
sensor->SetUserData("gazebo-entity", static_cast<int>(_gazeboId));

if (parent)
{
sensor->RemoveParent();
Expand Down
6 changes: 6 additions & 0 deletions test/integration/CMakeLists.txt
Expand Up @@ -139,3 +139,9 @@ set_tests_properties(INTEGRATION_tracked_vehicle_system PROPERTIES TIMEOUT 300)
if(TARGET INTEGRATION_examples_build)
set_tests_properties(INTEGRATION_examples_build PROPERTIES TIMEOUT 320)
endif()

if(VALID_DISPLAY AND VALID_DRI_DISPLAY)
target_link_libraries(INTEGRATION_sensors_system
ignition-rendering${IGN_RENDERING_VER}::ignition-rendering${IGN_RENDERING_VER}
)
endif()
63 changes: 63 additions & 0 deletions test/integration/sensors_system.cc
Expand Up @@ -18,6 +18,7 @@
#include <gtest/gtest.h>

#include <string>
#include <unordered_set>
#include <vector>

#include <sdf/Model.hh>
Expand All @@ -27,6 +28,11 @@
#include <ignition/transport/Node.hh>
#include <ignition/utilities/ExtraTestMacros.hh>

#include <ignition/rendering/Camera.hh>
#include <ignition/rendering/RenderEngine.hh>
#include <ignition/rendering/RenderingIface.hh>
#include <ignition/rendering/Scene.hh>

#include "ignition/gazebo/EntityComponentManager.hh"
#include "ignition/gazebo/EventManager.hh"
#include "ignition/gazebo/SdfEntityCreator.hh"
Expand All @@ -37,15 +43,57 @@

#include "ignition/gazebo/components/Model.hh"
#include "ignition/gazebo/components/Name.hh"
#include "ignition/gazebo/components/Sensor.hh"
#include "ignition/gazebo/components/World.hh"

#include "ignition/gazebo/rendering/Events.hh"

#include "plugins/MockSystem.hh"
#include "../helpers/EnvTestFixture.hh"

using namespace ignition;
using namespace std::chrono_literals;
namespace components = ignition::gazebo::components;

std::unordered_set<gazebo::Entity> g_sensorEntityIds;
rendering::ScenePtr g_scene;

/////////////////////////////////////////////////
void OnPostRender()
{
if (!g_scene)
{
g_scene = rendering::sceneFromFirstRenderEngine();
}
ASSERT_TRUE(g_scene);

EXPECT_LT(0u, g_scene->SensorCount());
for (unsigned int i = 0; i < g_scene->SensorCount(); ++i)
{
auto sensor = g_scene->SensorByIndex(i);
ASSERT_TRUE(sensor);
EXPECT_TRUE(sensor->HasUserData("gazebo-entity"));
auto variant = sensor->UserData("gazebo-entity");

// todo(anyone) change int to uint64_t once user data supports it
const int *value = std::get_if<int>(&variant);
ASSERT_TRUE(value);
g_sensorEntityIds.insert(*value);
}
}

/////////////////////////////////////////////////
void testSensorEntityIds(const gazebo::EntityComponentManager &_ecm,
const std::unordered_set<gazebo::Entity> &_ids)
{
EXPECT_FALSE(_ids.empty());
for (const auto & id : _ids)
{
auto sensorComp = _ecm.Component<gazebo::components::Sensor>(id);
EXPECT_TRUE(sensorComp);
}
}

//////////////////////////////////////////////////
class SensorsFixture : public InternalFixture<InternalFixture<::testing::Test>>
{
Expand Down Expand Up @@ -127,20 +175,35 @@ TEST_F(SensorsFixture, IGN_UTILS_TEST_DISABLED_ON_MAC(HandleRemovedEntities))

gazebo::Server server(serverConfig);

common::ConnectionPtr postRenderConn;

// A pointer to the ecm. This will be valid once we run the mock system
gazebo::EntityComponentManager *ecm = nullptr;
this->mockSystem->preUpdateCallback =
[&ecm](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm)
{
ecm = &_ecm;
};
this->mockSystem->configureCallback =
[&](const gazebo::Entity &,
const std::shared_ptr<const sdf::Element> &,
gazebo::EntityComponentManager &,
gazebo::EventManager &_eventMgr)
{
postRenderConn = _eventMgr.Connect<gazebo::events::PostRender>(
std::bind(&::OnPostRender));
};

server.AddSystem(this->systemPtr);
server.Run(true, 50, false);
ASSERT_NE(nullptr, ecm);

testDefaultTopics();

testSensorEntityIds(*ecm, g_sensorEntityIds);
g_sensorEntityIds.clear();
g_scene.reset();

// We won't use the event manager but it's required to create an
// SdfEntityCreator
gazebo::EventManager dummyEventMgr;
Expand Down

0 comments on commit a9563f5

Please sign in to comment.