Skip to content

Commit

Permalink
Add test, some cleanup
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina committed Jul 2, 2021
1 parent cb656ee commit 3a5ae75
Show file tree
Hide file tree
Showing 2 changed files with 226 additions and 11 deletions.
32 changes: 21 additions & 11 deletions src/plugins/camera_tracking/CameraTracking.cc
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,10 @@
/// \brief Private data class for CameraTracking
class ignition::gui::plugins::CameraTrackingPrivate
{
/// \brief Perform rendering calls in the rendering thread.
public: void OnRender();

/// \brief Initialize transport
public: void Initialize();

/// \brief Callback for a move to request
Expand Down Expand Up @@ -89,8 +91,11 @@ class ignition::gui::plugins::CameraTrackingPrivate
/// \brief Callback when a move to pose animation is complete
private: void OnMoveToPoseComplete();

/// \brief Process key releases
/// \param[in] _e Key release event
public: void HandleKeyRelease(events::KeyReleaseOnScene *_e);

/// \brief Protects variable changed through services.
public: std::mutex mutex;

//// \brief Pointer to the rendering scene
Expand Down Expand Up @@ -122,7 +127,7 @@ class ignition::gui::plugins::CameraTrackingPrivate
public: std::chrono::time_point<std::chrono::system_clock> prevMoveToTime;

/// \brief User camera
public: rendering::CameraPtr camera;
public: rendering::CameraPtr camera{nullptr};

/// \brief Target to move the user camera to
public: std::string moveToTarget;
Expand Down Expand Up @@ -154,8 +159,8 @@ class ignition::gui::plugins::CameraTrackingPrivate
/// \brief Camera pose publisher
public: transport::Node::Publisher cameraPosePub;

/// \brief Timer to keep publishing
public: QTimer *timer;
/// \brief Timer to keep publishing camera poses.
public: QTimer *timer{nullptr};
};

using namespace ignition;
Expand All @@ -165,19 +170,17 @@ using namespace plugins;
/////////////////////////////////////////////////
void CameraTrackingPrivate::Initialize()
{
// Attach to the first camera we find
for (unsigned int i = 0; i < scene->NodeCount(); ++i)
{
auto cam = std::dynamic_pointer_cast<rendering::Camera>(
scene->NodeByIndex(i));
if (cam)
{
if (cam->Name().find("scene::Camera") != std::string::npos)
{
this->camera = cam;
igndbg << "CameraTrackingPrivate plugin is moving camera ["
<< this->camera->Name() << "]" << std::endl;
break;
}
this->camera = cam;
igndbg << "CameraTrackingPrivate plugin is moving camera ["
<< this->camera->Name() << "]" << std::endl;
break;
}
}
if (!this->camera)
Expand Down Expand Up @@ -227,6 +230,7 @@ void CameraTrackingPrivate::Initialize()
bool CameraTrackingPrivate::OnMoveTo(const msgs::StringMsg &_msg,
msgs::Boolean &_res)
{
std::lock_guard<std::mutex> lock(this->mutex);
this->moveToTarget = _msg.data();

_res.set_data(true);
Expand All @@ -237,6 +241,7 @@ bool CameraTrackingPrivate::OnMoveTo(const msgs::StringMsg &_msg,
bool CameraTrackingPrivate::OnFollow(const msgs::StringMsg &_msg,
msgs::Boolean &_res)
{
std::lock_guard<std::mutex> lock(this->mutex);
this->followTarget = _msg.data();

_res.set_data(true);
Expand All @@ -261,6 +266,7 @@ void CameraTrackingPrivate::OnMoveToPoseComplete()
bool CameraTrackingPrivate::OnFollowOffset(const msgs::Vector3d &_msg,
msgs::Boolean &_res)
{
std::lock_guard<std::mutex> lock(this->mutex);
if (!this->followTarget.empty())
{
this->newFollowOffset = true;
Expand All @@ -275,6 +281,7 @@ bool CameraTrackingPrivate::OnFollowOffset(const msgs::Vector3d &_msg,
bool CameraTrackingPrivate::OnMoveToPose(const msgs::GUICamera &_msg,
msgs::Boolean &_res)
{
std::lock_guard<std::mutex> lock(this->mutex);
math::Pose3d pose = msgs::Convert(_msg.pose());

// If there is no orientation in the message, then set a Rot value in the
Expand Down Expand Up @@ -309,6 +316,9 @@ void CameraTrackingPrivate::OnRender()
this->Initialize();
}

if (!this->camera)
return;

// Move To
{
IGN_PROFILE("CameraTrackingPrivate::OnRender MoveTo");
Expand Down Expand Up @@ -455,7 +465,7 @@ CameraTracking::~CameraTracking()
void CameraTracking::LoadConfig(const tinyxml2::XMLElement *)
{
if (this->title.empty())
this->title = "Camera Controller Manager";
this->title = "Camera tracking";

App()->findChild<MainWindow *>()->installEventFilter(this);
}
Expand Down
205 changes: 205 additions & 0 deletions test/integration/camera_tracking.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,205 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#include <gtest/gtest.h>

#include <ignition/common/Console.hh>
#include <ignition/math/Pose3.hh>
#include <ignition/msgs/pose.pb.h>
#include <ignition/rendering/Camera.hh>
#include <ignition/rendering/RenderEngine.hh>
#include <ignition/rendering/RenderingIface.hh>
#include <ignition/rendering/Scene.hh>
#include <ignition/transport/Node.hh>
#include <ignition/utilities/ExtraTestMacros.hh>

#include "test_config.h" // NOLINT(build/include)
#include "ignition/gui/Application.hh"
#include "ignition/gui/GuiEvents.hh"
#include "ignition/gui/Plugin.hh"
#include "ignition/gui/MainWindow.hh"

int g_argc = 1;
char* g_argv[] =
{
reinterpret_cast<char*>(const_cast<char*>("./camera_tracking")),
};

using namespace ignition;
using namespace gui;
using namespace std::chrono_literals;

/////////////////////////////////////////////////
TEST(MinimalSceneTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Config))
{
common::Console::SetVerbosity(4);

Application app(g_argc, g_argv);
app.AddPluginPath(std::string(PROJECT_BINARY_PATH) + "/lib");

// Load plugins
const char *pluginStr =
"<plugin filename=\"MinimalScene\">"
"<engine>ogre</engine>"
"<scene>banana</scene>"
"<ambient_light>1.0 0 0</ambient_light>"
"<background_color>0 1 0</background_color>"
"<camera_pose>1 2 3 0 0 0</camera_pose>"
"</plugin>";

tinyxml2::XMLDocument pluginDoc;
pluginDoc.Parse(pluginStr);
EXPECT_TRUE(app.LoadPlugin("MinimalScene",
pluginDoc.FirstChildElement("plugin")));

pluginStr =
"<plugin filename=\"CameraTracking\">"
"</plugin>";

pluginDoc.Parse(pluginStr);
EXPECT_TRUE(app.LoadPlugin("CameraTracking",
pluginDoc.FirstChildElement("plugin")));

// Get main window
auto win = app.findChild<MainWindow *>();
ASSERT_NE(nullptr, win);

// Get plugin
auto plugins = win->findChildren<Plugin *>();
EXPECT_EQ(plugins.size(), 2);

auto plugin = plugins[0];
EXPECT_EQ(plugin->Title(), "3D Scene");

plugin = plugins[1];
EXPECT_EQ(plugin->Title(), "Camera tracking");

// Show, but don't exec, so we don't block
win->QuickWindow()->show();

// Get camera pose
msgs::Pose poseMsg;
auto poseCb = std::function<void(const msgs::Pose &)>(
[&](const auto &_msg)
{
poseMsg = _msg;
});

transport::Node node;
node.Subscribe("/gui/camera/pose", poseCb);

int sleep = 0;
int maxSleep = 30;
while (!poseMsg.has_position() && sleep++ < maxSleep)
{
std::this_thread::sleep_for(100ms);
QCoreApplication::processEvents();
}
EXPECT_LT(sleep, maxSleep);
EXPECT_TRUE(poseMsg.has_position());
EXPECT_TRUE(poseMsg.has_orientation());

auto engine = rendering::engine("ogre");
ASSERT_NE(nullptr, engine);

auto scene = engine->SceneByName("banana");
ASSERT_NE(nullptr, scene);

auto root = scene->RootVisual();
ASSERT_NE(nullptr, root);

auto camera = std::dynamic_pointer_cast<rendering::Camera>(
root->ChildByIndex(0));
ASSERT_NE(nullptr, camera);

EXPECT_EQ(camera->WorldPose(), msgs::Convert(poseMsg));
EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 0), msgs::Convert(poseMsg));

// Add object to be tracked
auto trackedVis = scene->CreateVisual("track_me");
ASSERT_NE(nullptr, trackedVis);
trackedVis->SetWorldPose({100, 100, 100, 0, 0, 0});

// Move to
msgs::StringMsg req;
msgs::Boolean rep;

req.set_data("track_me");

bool result;
unsigned int timeout = 2000;
bool executed = node.Request("/gui/move_to", req, timeout, rep, result);
EXPECT_TRUE(executed);
EXPECT_TRUE(result);
EXPECT_TRUE(rep.data());

sleep = 0;
while (abs(camera->WorldPose().Pos().X() - 100) > 10 && sleep++ < maxSleep)
{
std::this_thread::sleep_for(100ms);
QCoreApplication::processEvents();
}
EXPECT_LT(sleep, maxSleep);

EXPECT_GT(10, abs(camera->WorldPose().Pos().X() - 100));
EXPECT_GT(10, abs(camera->WorldPose().Pos().Y() - 100));
EXPECT_GT(10, abs(camera->WorldPose().Pos().Z() - 100));

// Move target object to new position
trackedVis->SetWorldPose({130, 130, 130, 0, 0, 0});

// Follow
result = false;
executed = node.Request("/gui/follow", req, timeout, rep, result);
EXPECT_TRUE(executed);
EXPECT_TRUE(result);
EXPECT_TRUE(rep.data());

msgs::Vector3d reqOffset;
reqOffset.set_x(1.0);
reqOffset.set_y(1.0);
reqOffset.set_z(1.0);
result = false;
executed = node.Request("/gui/follow/offset", reqOffset, timeout, rep,
result);
EXPECT_TRUE(executed);
EXPECT_TRUE(result);
EXPECT_TRUE(rep.data());

// Many update loops to process many events
maxSleep = 300;
for (auto it : {150.0, 200.0})
{
// Move target
trackedVis->SetWorldPose({it, it, it, 0, 0, 0});

// Check camera moved
sleep = 0;
while (abs(camera->WorldPose().Pos().X() - it) > 10 &&
sleep++ < maxSleep)
{
std::this_thread::sleep_for(10ms);
QCoreApplication::processEvents();
}
EXPECT_LT(sleep, maxSleep);

EXPECT_GT(10, abs(camera->WorldPose().Pos().X() - it));
EXPECT_GT(10, abs(camera->WorldPose().Pos().Y() - it));
EXPECT_GT(10, abs(camera->WorldPose().Pos().Z() - it));
}
}

0 comments on commit 3a5ae75

Please sign in to comment.