diff --git a/CMakeLists.txt b/CMakeLists.txt index 5539c04bd..dbc00198a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -44,7 +44,7 @@ set(IGN_MATH_VER ${ignition-math6_VERSION_MAJOR}) #-------------------------------------- # Find ignition-common -ign_find_package(ignition-common4 REQUIRED VERSION 4.1) +ign_find_package(ignition-common4 REQUIRED COMPONENTS profiler VERSION 4.1) set(IGN_COMMON_VER ${ignition-common4_VERSION_MAJOR}) #-------------------------------------- diff --git a/examples/config/scene3d.config b/examples/config/scene3d.config index 537a8e3c0..1f6caa286 100644 --- a/examples/config/scene3d.config +++ b/examples/config/scene3d.config @@ -32,6 +32,19 @@ /example/delete /example/scene + + + + + + + false + 5 + 5 + floating + false + + Controls diff --git a/examples/standalone/scene_provider/README.md b/examples/standalone/scene_provider/README.md index 676f9614d..d60425399 100644 --- a/examples/standalone/scene_provider/README.md +++ b/examples/standalone/scene_provider/README.md @@ -34,3 +34,32 @@ ign gui -c examples/config/scene3d.config You should see a black box moving around the scene. +## Testing other plugins + +### Camera tracking + +Some commands to test camera tracking with this demo: + +Move to box: + +``` +ign service -s /gui/move_to --reqtype ignition.msgs.StringMsg --reptype ignition.msgs.Boolean --timeout 2000 --req 'data: "box_model"' +``` + +Echo camera pose: + +``` +ign topic -e -t /gui/camera/pose +``` + +Follow box: + +``` +ign service -s /gui/follow --reqtype ignition.msgs.StringMsg --reptype ignition.msgs.Boolean --timeout 2000 --req 'data: "box_model"' +``` + +Update follow offset: + +``` +ign service -s /gui/follow/offset --reqtype ignition.msgs.Vector3d --reptype ignition.msgs.Boolean --timeout 2000 --req 'x: 5, y: 5, z: 5' +``` diff --git a/src/plugins/CMakeLists.txt b/src/plugins/CMakeLists.txt index 14c72bc17..68464ff2f 100644 --- a/src/plugins/CMakeLists.txt +++ b/src/plugins/CMakeLists.txt @@ -114,6 +114,7 @@ function(ign_gui_add_plugin plugin_name) endfunction() # Plugins +add_subdirectory(camera_tracking) add_subdirectory(grid_3d) add_subdirectory(grid_config) add_subdirectory(image_display) diff --git a/src/plugins/camera_tracking/CMakeLists.txt b/src/plugins/camera_tracking/CMakeLists.txt new file mode 100644 index 000000000..f235b22f3 --- /dev/null +++ b/src/plugins/camera_tracking/CMakeLists.txt @@ -0,0 +1,11 @@ +ign_gui_add_plugin(CameraTracking + SOURCES + CameraTracking.cc + QT_HEADERS + CameraTracking.hh + TEST_SOURCES + # CameraTracking_TEST.cc + PUBLIC_LINK_LIBS + ignition-rendering${IGN_RENDERING_VER}::ignition-rendering${IGN_RENDERING_VER} + ignition-common${IGN_COMMON_VER}::profiler +) diff --git a/src/plugins/camera_tracking/CameraTracking.cc b/src/plugins/camera_tracking/CameraTracking.cc new file mode 100644 index 000000000..7a01746af --- /dev/null +++ b/src/plugins/camera_tracking/CameraTracking.cc @@ -0,0 +1,509 @@ +/* + * 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 +#include + +#include +#include +#include + +// TODO(anyone) Remove these pragmas once ign-rendering and ign-msgs +// are disabling the warnings +#ifdef _MSC_VER +#pragma warning(push, 0) +#endif +#include +#include + +#include +#include +#include +#include + +#ifdef _MSC_VER +#pragma warning(pop) +#endif + +#include "ignition/gui/Application.hh" +#include "ignition/gui/Conversions.hh" +#include "ignition/gui/GuiEvents.hh" +#include "ignition/gui/MainWindow.hh" + +#include + +#include "CameraTracking.hh" + +/// \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 + /// \param[in] _msg Request message to set the target to move to. + /// \param[in] _res Response data + /// \return True if the request is received + public: bool OnMoveTo(const msgs::StringMsg &_msg, + msgs::Boolean &_res); + + /// \brief Callback for a follow request + /// \param[in] _msg Request message to set the target to follow. + /// \param[in] _res Response data + /// \return True if the request is received + public: bool OnFollow(const msgs::StringMsg &_msg, + msgs::Boolean &_res); + + /// \brief Callback for a move to pose request. + /// \param[in] _msg GUICamera request message. + /// \param[in] _res Response data + /// \return True if the request is received + public: bool OnMoveToPose(const msgs::GUICamera &_msg, + msgs::Boolean &_res); + + /// \brief Callback for a follow offset request + /// \param[in] _msg Request message to set the camera's follow offset. + /// \param[in] _res Response data + /// \return True if the request is received + public: bool OnFollowOffset(const msgs::Vector3d &_msg, + msgs::Boolean &_res); + + /// \brief Callback when a move to animation is complete + private: void OnMoveToComplete(); + + /// \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 + public: rendering::ScenePtr scene = nullptr; + + /// \brief Target to follow + public: std::string followTarget; + + /// \brief Wait for follow target + public: bool followTargetWait = false; + + /// \brief Offset of camera from target being followed + public: math::Vector3d followOffset = math::Vector3d(-5, 0, 3); + + /// \brief Flag to indicate the follow offset needs to be updated + public: bool followOffsetDirty = false; + + /// \brief Flag to indicate the follow offset has been updated + public: bool newFollowOffset = true; + + /// \brief Follow P gain + public: double followPGain = 0.01; + + /// \brief True follow the target at an offset that is in world frame, + /// false to follow in target's local frame + public: bool followWorldFrame = false; + + /// \brief Last move to animation time + public: std::chrono::time_point prevMoveToTime; + + /// \brief User camera + public: rendering::CameraPtr camera{nullptr}; + + /// \brief Target to move the user camera to + public: std::string moveToTarget; + + /// \brief Helper object to move user camera + public: ignition::rendering::MoveToHelper moveToHelper; + + /// \brief Transport node + public: transport::Node node; + + /// \brief Move to service + public: std::string moveToService; + + /// \brief The pose set from the move to pose service. + public: std::optional moveToPoseValue; + + /// \brief Follow service + public: std::string followService; + + /// \brief Follow offset service + public: std::string followOffsetService; + + /// \brief Camera pose topic + public: std::string cameraPoseTopic; + + /// \brief Move to pose service + public: std::string moveToPoseService; + + /// \brief Camera pose publisher + public: transport::Node::Publisher cameraPosePub; + + /// \brief Timer to keep publishing camera poses. + public: QTimer *timer{nullptr}; +}; + +using namespace ignition; +using namespace gui; +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( + scene->NodeByIndex(i)); + if (cam) + { + this->camera = cam; + igndbg << "CameraTrackingPrivate plugin is moving camera [" + << this->camera->Name() << "]" << std::endl; + break; + } + } + if (!this->camera) + { + ignerr << "Camera is not available" << std::endl; + return; + } + + // move to + this->moveToService = "/gui/move_to"; + this->node.Advertise(this->moveToService, + &CameraTrackingPrivate::OnMoveTo, this); + ignmsg << "Move to service on [" + << this->moveToService << "]" << std::endl; + + // follow + this->followService = "/gui/follow"; + this->node.Advertise(this->followService, + &CameraTrackingPrivate::OnFollow, this); + ignmsg << "Follow service on [" + << this->followService << "]" << std::endl; + + // move to pose service + this->moveToPoseService = + "/gui/move_to/pose"; + this->node.Advertise(this->moveToPoseService, + &CameraTrackingPrivate::OnMoveToPose, this); + ignmsg << "Move to pose service on [" + << this->moveToPoseService << "]" << std::endl; + + // camera position topic + this->cameraPoseTopic = "/gui/camera/pose"; + this->cameraPosePub = + this->node.Advertise(this->cameraPoseTopic); + ignmsg << "Camera pose topic advertised on [" + << this->cameraPoseTopic << "]" << std::endl; + + // follow offset + this->followOffsetService = "/gui/follow/offset"; + this->node.Advertise(this->followOffsetService, + &CameraTrackingPrivate::OnFollowOffset, this); + ignmsg << "Follow offset service on [" + << this->followOffsetService << "]" << std::endl; +} + +///////////////////////////////////////////////// +bool CameraTrackingPrivate::OnMoveTo(const msgs::StringMsg &_msg, + msgs::Boolean &_res) +{ + std::lock_guard lock(this->mutex); + this->moveToTarget = _msg.data(); + + _res.set_data(true); + return true; +} + +///////////////////////////////////////////////// +bool CameraTrackingPrivate::OnFollow(const msgs::StringMsg &_msg, + msgs::Boolean &_res) +{ + std::lock_guard lock(this->mutex); + this->followTarget = _msg.data(); + + _res.set_data(true); + return true; +} + +///////////////////////////////////////////////// +void CameraTrackingPrivate::OnMoveToComplete() +{ + std::lock_guard lock(this->mutex); + this->moveToTarget.clear(); +} + +///////////////////////////////////////////////// +void CameraTrackingPrivate::OnMoveToPoseComplete() +{ + std::lock_guard lock(this->mutex); + this->moveToPoseValue.reset(); +} + +///////////////////////////////////////////////// +bool CameraTrackingPrivate::OnFollowOffset(const msgs::Vector3d &_msg, + msgs::Boolean &_res) +{ + std::lock_guard lock(this->mutex); + if (!this->followTarget.empty()) + { + this->newFollowOffset = true; + this->followOffset = msgs::Convert(_msg); + } + + _res.set_data(true); + return true; +} + +///////////////////////////////////////////////// +bool CameraTrackingPrivate::OnMoveToPose(const msgs::GUICamera &_msg, + msgs::Boolean &_res) +{ + std::lock_guard 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 + // math::Pose3d object to infinite. This will prevent the orientation from + // being used when positioning the camera. + // See the MoveToHelper::MoveTo function + if (!_msg.pose().has_orientation()) + pose.Rot().X() = math::INF_D; + + // If there is no position in the message, then set a Pos value in the + // math::Pose3d object to infinite. This will prevent the orientation from + // being used when positioning the camera. + // See the MoveToHelper::MoveTo function + if (!_msg.pose().has_position()) + pose.Pos().X() = math::INF_D; + + this->moveToPoseValue = pose; + + _res.set_data(true); + return true; +} + +///////////////////////////////////////////////// +void CameraTrackingPrivate::OnRender() +{ + if (nullptr == this->scene) + { + this->scene = rendering::sceneFromFirstRenderEngine(); + if (nullptr == this->scene) + return; + + this->Initialize(); + } + + if (!this->camera) + return; + + // Move To + { + IGN_PROFILE("CameraTrackingPrivate::OnRender MoveTo"); + if (!this->moveToTarget.empty()) + { + if (this->moveToHelper.Idle()) + { + rendering::NodePtr target = scene->NodeByName( + this->moveToTarget); + if (target) + { + this->moveToHelper.MoveTo(this->camera, target, 0.5, + std::bind(&CameraTrackingPrivate::OnMoveToComplete, this)); + this->prevMoveToTime = std::chrono::system_clock::now(); + } + else + { + ignerr << "Unable to move to target. Target: '" + << this->moveToTarget << "' not found" << std::endl; + this->moveToTarget.clear(); + } + } + else + { + auto now = std::chrono::system_clock::now(); + std::chrono::duration dt = now - this->prevMoveToTime; + this->moveToHelper.AddTime(dt.count()); + this->prevMoveToTime = now; + } + } + } + + // Move to pose + { + IGN_PROFILE("CameraTrackingPrivate::OnRender MoveToPose"); + if (this->moveToPoseValue) + { + if (this->moveToHelper.Idle()) + { + this->moveToHelper.MoveTo(this->camera, + *(this->moveToPoseValue), + 0.5, std::bind(&CameraTrackingPrivate::OnMoveToPoseComplete, this)); + this->prevMoveToTime = std::chrono::system_clock::now(); + } + else + { + auto now = std::chrono::system_clock::now(); + std::chrono::duration dt = now - this->prevMoveToTime; + this->moveToHelper.AddTime(dt.count()); + this->prevMoveToTime = now; + } + } + } + + // Follow + { + IGN_PROFILE("CameraTrackingPrivate::OnRender Follow"); + // reset follow mode if target node got removed + if (!this->followTarget.empty()) + { + rendering::NodePtr target = this->scene->NodeByName(this->followTarget); + if (!target && !this->followTargetWait) + { + this->camera->SetFollowTarget(nullptr); + this->camera->SetTrackTarget(nullptr); + this->followTarget.clear(); + } + } + + if (!this->moveToTarget.empty()) + return; + rendering::NodePtr followTargetTmp = this->camera->FollowTarget(); + if (!this->followTarget.empty()) + { + rendering::NodePtr target = scene->NodeByName( + this->followTarget); + if (target) + { + if (!followTargetTmp || target != followTargetTmp + || this->newFollowOffset) + { + this->camera->SetFollowTarget(target, + this->followOffset, + this->followWorldFrame); + this->camera->SetFollowPGain(this->followPGain); + + this->camera->SetTrackTarget(target); + // found target, no need to wait anymore + this->newFollowOffset = false; + this->followTargetWait = false; + } + else if (this->followOffsetDirty) + { + math::Vector3d offset = + this->camera->WorldPosition() - target->WorldPosition(); + if (!this->followWorldFrame) + { + offset = target->WorldRotation().RotateVectorReverse(offset); + } + this->camera->SetFollowOffset(offset); + this->followOffsetDirty = false; + } + } + else if (!this->followTargetWait) + { + ignerr << "Unable to follow target. Target: '" + << this->followTarget << "' not found" << std::endl; + this->followTarget.clear(); + } + } + else if (followTargetTmp) + { + this->camera->SetFollowTarget(nullptr); + this->camera->SetTrackTarget(nullptr); + } + } +} + +///////////////////////////////////////////////// +CameraTracking::CameraTracking() + : Plugin(), dataPtr(new CameraTrackingPrivate) +{ + this->dataPtr->timer = new QTimer(this); + this->connect(this->dataPtr->timer, &QTimer::timeout, [=]() + { + if (!this->dataPtr->camera) + return; + if (this->dataPtr->cameraPosePub.HasConnections()) + { + auto poseMsg = msgs::Convert(this->dataPtr->camera->WorldPose()); + this->dataPtr->cameraPosePub.Publish(poseMsg); + } + }); + this->dataPtr->timer->setInterval(1000.0 / 50.0); + this->dataPtr->timer->start(); +} + +///////////////////////////////////////////////// +CameraTracking::~CameraTracking() +{ +} + +///////////////////////////////////////////////// +void CameraTracking::LoadConfig(const tinyxml2::XMLElement *) +{ + if (this->title.empty()) + this->title = "Camera tracking"; + + App()->findChild()->installEventFilter(this); +} + +///////////////////////////////////////////////// +void CameraTrackingPrivate::HandleKeyRelease(events::KeyReleaseOnScene *_e) +{ + if (_e->Key().Key() == Qt::Key_Escape) + { + if (!this->followTarget.empty()) + { + this->followTarget = std::string(); + + _e->accept(); + } + } +} + +///////////////////////////////////////////////// +bool CameraTracking::eventFilter(QObject *_obj, QEvent *_event) +{ + if (_event->type() == events::Render::kType) + { + this->dataPtr->OnRender(); + } + else if (_event->type() == events::KeyReleaseOnScene::kType) + { + events::KeyReleaseOnScene *keyEvent = + static_cast(_event); + if (keyEvent) + { + this->dataPtr->HandleKeyRelease(keyEvent); + } + } + // Standard event processing + return QObject::eventFilter(_obj, _event); +} + +// Register this plugin +IGNITION_ADD_PLUGIN(ignition::gui::plugins::CameraTracking, + ignition::gui::Plugin) diff --git a/src/plugins/camera_tracking/CameraTracking.hh b/src/plugins/camera_tracking/CameraTracking.hh new file mode 100644 index 000000000..f43405bbc --- /dev/null +++ b/src/plugins/camera_tracking/CameraTracking.hh @@ -0,0 +1,57 @@ +/* + * 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. + * +*/ + +#ifndef IGNITION_GUI_PLUGINS_CAMERATRACKING_HH_ +#define IGNITION_GUI_PLUGINS_CAMERATRACKING_HH_ + +#include + +#include "ignition/gui/Plugin.hh" + +namespace ignition +{ +namespace gui +{ +namespace plugins +{ + class CameraTrackingPrivate; + + class CameraTracking : public Plugin + { + Q_OBJECT + + /// \brief Constructor + public: CameraTracking(); + + /// \brief Destructor + public: virtual ~CameraTracking(); + + // Documentation inherited + public: virtual void LoadConfig(const tinyxml2::XMLElement *_pluginElem) + override; + + // Documentation inherited + private: bool eventFilter(QObject *_obj, QEvent *_event) override; + + /// \internal + /// \brief Pointer to private data. + private: std::unique_ptr dataPtr; + }; +} +} +} +#endif diff --git a/src/plugins/camera_tracking/CameraTracking.qml b/src/plugins/camera_tracking/CameraTracking.qml new file mode 100644 index 000000000..873da3001 --- /dev/null +++ b/src/plugins/camera_tracking/CameraTracking.qml @@ -0,0 +1,28 @@ +/* + * 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. + * +*/ + +import QtQuick 2.0 +import QtQuick.Controls 2.0 +import QtQuick.Layouts 1.3 + +// TODO: remove invisible rectangle, see +// https://github.com/ignitionrobotics/ign-gui/issues/220 +Rectangle { + visible: false + Layout.minimumWidth: 100 + Layout.minimumHeight: 100 +} diff --git a/src/plugins/camera_tracking/CameraTracking.qrc b/src/plugins/camera_tracking/CameraTracking.qrc new file mode 100644 index 000000000..f58398257 --- /dev/null +++ b/src/plugins/camera_tracking/CameraTracking.qrc @@ -0,0 +1,5 @@ + + + CameraTracking.qml + + diff --git a/src/plugins/transport_scene_manager/TransportSceneManager.cc b/src/plugins/transport_scene_manager/TransportSceneManager.cc index 01fabccda..47c2d5103 100644 --- a/src/plugins/transport_scene_manager/TransportSceneManager.cc +++ b/src/plugins/transport_scene_manager/TransportSceneManager.cc @@ -839,4 +839,3 @@ void TransportSceneManagerPrivate::DeleteEntity(const unsigned int _entity) // Register this plugin IGNITION_ADD_PLUGIN(ignition::gui::plugins::TransportSceneManager, ignition::gui::Plugin) - diff --git a/test/integration/camera_tracking.cc b/test/integration/camera_tracking.cc new file mode 100644 index 000000000..7b94e03d1 --- /dev/null +++ b/test/integration/camera_tracking.cc @@ -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 + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#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(const_cast("./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 = + "" + "ogre" + "banana" + "1.0 0 0" + "0 1 0" + "1 2 3 0 0 0" + ""; + + tinyxml2::XMLDocument pluginDoc; + pluginDoc.Parse(pluginStr); + EXPECT_TRUE(app.LoadPlugin("MinimalScene", + pluginDoc.FirstChildElement("plugin"))); + + pluginStr = + "" + ""; + + pluginDoc.Parse(pluginStr); + EXPECT_TRUE(app.LoadPlugin("CameraTracking", + pluginDoc.FirstChildElement("plugin"))); + + // Get main window + auto win = app.findChild(); + ASSERT_NE(nullptr, win); + + // Get plugin + auto plugins = win->findChildren(); + 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( + [&](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( + 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)); + } +} +