Skip to content

Commit

Permalink
Switch gz-gui plugins to use implptr
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <[email protected]>
  • Loading branch information
mjcarroll committed Nov 7, 2023
1 parent 4f98aa3 commit b84c93f
Show file tree
Hide file tree
Showing 45 changed files with 323 additions and 291 deletions.
1 change: 0 additions & 1 deletion include/gz/gui/Dialog.hh
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,5 @@ namespace gz::gui
/// \brief Private data pointer
GZ_UTILS_UNIQUE_IMPL_PTR(dataPtr)
};
};
} // namespace gz::gui
#endif // GZ_GUI_DIALOG_HH_
5 changes: 0 additions & 5 deletions include/gz/gui/MainWindow.hh
Original file line number Diff line number Diff line change
Expand Up @@ -667,9 +667,4 @@ namespace gz::gui
std::string plugins{""};
};
} // namespace gz::gui

#ifdef _MSC_VER
#pragma warning(pop)
#endif

#endif // GZ_GUI_MAINWINDOW_HH_
2 changes: 1 addition & 1 deletion src/MainWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ class MainWindow::Implementation
public: std::string controlService{"/server_control"};

/// \brief Communication node
public: gz::transport::Node node;
public: gz::transport::Node node {gz::transport::NodeOptions()};
};

/////////////////////////////////////////////////
Expand Down
2 changes: 1 addition & 1 deletion src/PlottingInterface.cc
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ class Topic::Implementation
class Transport::Implementation
{
/// \brief Node for Commincation
public: gz::transport::Node node;
public: gz::transport::Node node {gz::transport::NodeOptions()};

/// \brief subscribed topics
public: std::map<std::string, gz::gui::Topic*> topics;
Expand Down
5 changes: 3 additions & 2 deletions src/plugins/camera_fps/CameraFps.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
*
*/

#include <gz/utils/ImplPtr.hh>
#include <list>
#include <string>

Expand All @@ -32,7 +33,7 @@
namespace gz::gui::plugins
{
/// \brief Private data class for CameraFps
class CameraFpsPrivate
class CameraFps::Implementation
{
/// \brief Previous camera update time
public: std::optional<std::chrono::steady_clock::time_point>
Expand Down Expand Up @@ -82,7 +83,7 @@ void CameraFps::OnRender()

/////////////////////////////////////////////////
CameraFps::CameraFps()
: dataPtr(new CameraFpsPrivate)
: dataPtr(gz::utils::MakeUniqueImpl<Implementation>())
{
}

Expand Down
5 changes: 2 additions & 3 deletions src/plugins/camera_fps/CameraFps.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,14 +18,13 @@
#ifndef GZ_GUI_PLUGINS_CAMERAFPS_HH_
#define GZ_GUI_PLUGINS_CAMERAFPS_HH_

#include <gz/utils/ImplPtr.hh>
#include <memory>

#include "gz/gui/Plugin.hh"

namespace gz::gui::plugins
{
class CameraFpsPrivate;

/// \brief This plugin displays the GUI camera's Framerate Per Second (FPS)
class CameraFps : public Plugin
{
Expand Down Expand Up @@ -68,7 +67,7 @@ namespace gz::gui::plugins

/// \internal
/// \brief Pointer to private data.
private: std::unique_ptr<CameraFpsPrivate> dataPtr;
GZ_UTILS_UNIQUE_IMPL_PTR(dataPtr)
};
} // namespace gz::gui::plugins

Expand Down
54 changes: 28 additions & 26 deletions src/plugins/camera_tracking/CameraTracking.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
*
*/

#include <gz/utils/ImplPtr.hh>
#include <mutex>
#include <string>

Expand Down Expand Up @@ -44,7 +45,7 @@
namespace gz::gui::plugins
{
/// \brief Private data class for CameraTracking
class CameraTrackingPrivate
class CameraTracking::Implementation
{
/// \brief Perform rendering calls in the rendering thread.
public: void OnRender();
Expand Down Expand Up @@ -159,7 +160,7 @@ class CameraTrackingPrivate
};

/////////////////////////////////////////////////
void CameraTrackingPrivate::Initialize()
void CameraTracking::Implementation::Initialize()
{
// Attach to the first camera we find
for (unsigned int i = 0; i < scene->NodeCount(); ++i)
Expand All @@ -169,7 +170,7 @@ void CameraTrackingPrivate::Initialize()
if (cam)
{
this->camera = cam;
gzdbg << "CameraTrackingPrivate plugin is moving camera ["
gzdbg << "CameraTracking plugin is moving camera ["
<< this->camera->Name() << "]" << std::endl;
break;
}
Expand All @@ -183,22 +184,22 @@ void CameraTrackingPrivate::Initialize()
// move to
this->moveToService = "/gui/move_to";
this->node.Advertise(this->moveToService,
&CameraTrackingPrivate::OnMoveTo, this);
&Implementation::OnMoveTo, this);
gzmsg << "Move to service on ["
<< this->moveToService << "]" << std::endl;

// follow
this->followService = "/gui/follow";
this->node.Advertise(this->followService,
&CameraTrackingPrivate::OnFollow, this);
&Implementation::OnFollow, this);
gzmsg << "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);
&Implementation::OnMoveToPose, this);
gzmsg << "Move to pose service on ["
<< this->moveToPoseService << "]" << std::endl;

Expand All @@ -209,16 +210,16 @@ void CameraTrackingPrivate::Initialize()
gzmsg << "Camera pose topic advertised on ["
<< this->cameraPoseTopic << "]" << std::endl;

// follow offset
this->followOffsetService = "/gui/follow/offset";
this->node.Advertise(this->followOffsetService,
&CameraTrackingPrivate::OnFollowOffset, this);
gzmsg << "Follow offset service on ["
<< this->followOffsetService << "]" << std::endl;
// follow offset
this->followOffsetService = "/gui/follow/offset";
this->node.Advertise(this->followOffsetService,
&Implementation::OnFollowOffset, this);
gzmsg << "Follow offset service on ["
<< this->followOffsetService << "]" << std::endl;
}

/////////////////////////////////////////////////
bool CameraTrackingPrivate::OnMoveTo(const msgs::StringMsg &_msg,
bool CameraTracking::Implementation::OnMoveTo(const msgs::StringMsg &_msg,
msgs::Boolean &_res)
{
std::lock_guard<std::mutex> lock(this->mutex);
Expand All @@ -229,7 +230,7 @@ bool CameraTrackingPrivate::OnMoveTo(const msgs::StringMsg &_msg,
}

/////////////////////////////////////////////////
bool CameraTrackingPrivate::OnFollow(const msgs::StringMsg &_msg,
bool CameraTracking::Implementation::OnFollow(const msgs::StringMsg &_msg,
msgs::Boolean &_res)
{
std::lock_guard<std::mutex> lock(this->mutex);
Expand All @@ -240,19 +241,19 @@ bool CameraTrackingPrivate::OnFollow(const msgs::StringMsg &_msg,
}

/////////////////////////////////////////////////
void CameraTrackingPrivate::OnMoveToComplete()
void CameraTracking::Implementation::OnMoveToComplete()
{
this->moveToTarget.clear();
}

/////////////////////////////////////////////////
void CameraTrackingPrivate::OnMoveToPoseComplete()
void CameraTracking::Implementation::OnMoveToPoseComplete()
{
this->moveToPoseValue.reset();
}

/////////////////////////////////////////////////
bool CameraTrackingPrivate::OnFollowOffset(const msgs::Vector3d &_msg,
bool CameraTracking::Implementation::OnFollowOffset(const msgs::Vector3d &_msg,
msgs::Boolean &_res)
{
std::lock_guard<std::mutex> lock(this->mutex);
Expand All @@ -267,7 +268,7 @@ bool CameraTrackingPrivate::OnFollowOffset(const msgs::Vector3d &_msg,
}

/////////////////////////////////////////////////
bool CameraTrackingPrivate::OnMoveToPose(const msgs::GUICamera &_msg,
bool CameraTracking::Implementation::OnMoveToPose(const msgs::GUICamera &_msg,
msgs::Boolean &_res)
{
std::lock_guard<std::mutex> lock(this->mutex);
Expand All @@ -294,7 +295,7 @@ bool CameraTrackingPrivate::OnMoveToPose(const msgs::GUICamera &_msg,
}

/////////////////////////////////////////////////
void CameraTrackingPrivate::OnRender()
void CameraTracking::Implementation::OnRender()
{
std::lock_guard<std::mutex> lock(this->mutex);

Expand All @@ -312,7 +313,7 @@ void CameraTrackingPrivate::OnRender()

// Move To
{
GZ_PROFILE("CameraTrackingPrivate::OnRender MoveTo");
GZ_PROFILE("CameraTracking::Implementation::OnRender MoveTo");
if (!this->moveToTarget.empty())
{
if (this->moveToHelper.Idle())
Expand All @@ -322,7 +323,7 @@ void CameraTrackingPrivate::OnRender()
if (target)
{
this->moveToHelper.MoveTo(this->camera, target, 0.5,
std::bind(&CameraTrackingPrivate::OnMoveToComplete, this));
std::bind(&Implementation::OnMoveToComplete, this));
this->prevMoveToTime = std::chrono::system_clock::now();
}
else
Expand All @@ -344,14 +345,14 @@ void CameraTrackingPrivate::OnRender()

// Move to pose
{
GZ_PROFILE("CameraTrackingPrivate::OnRender MoveToPose");
GZ_PROFILE("CameraTracking::Implementation::OnRender MoveToPose");
if (this->moveToPoseValue)
{
if (this->moveToHelper.Idle())
{
this->moveToHelper.MoveTo(this->camera,
*(this->moveToPoseValue),
0.5, std::bind(&CameraTrackingPrivate::OnMoveToPoseComplete, this));
0.5, std::bind(&Implementation::OnMoveToPoseComplete, this));
this->prevMoveToTime = std::chrono::system_clock::now();
}
else
Expand All @@ -366,7 +367,7 @@ void CameraTrackingPrivate::OnRender()

// Follow
{
GZ_PROFILE("CameraTrackingPrivate::OnRender Follow");
GZ_PROFILE("CameraTracking::Implementation::OnRender Follow");
// reset follow mode if target node got removed
if (!this->followTarget.empty())
{
Expand Down Expand Up @@ -430,7 +431,7 @@ void CameraTrackingPrivate::OnRender()

/////////////////////////////////////////////////
CameraTracking::CameraTracking()
: dataPtr(new CameraTrackingPrivate)
: dataPtr(gz::utils::MakeUniqueImpl<Implementation>())
{
this->dataPtr->timer = new QTimer(this);
this->connect(this->dataPtr->timer, &QTimer::timeout, [=]()
Expand Down Expand Up @@ -461,7 +462,8 @@ void CameraTracking::LoadConfig(const tinyxml2::XMLElement *)
}

/////////////////////////////////////////////////
void CameraTrackingPrivate::HandleKeyRelease(events::KeyReleaseOnScene *_e)
void CameraTracking::Implementation::HandleKeyRelease(
events::KeyReleaseOnScene *_e)
{
if (_e->Key().Key() == Qt::Key_Escape)
{
Expand Down
5 changes: 2 additions & 3 deletions src/plugins/camera_tracking/CameraTracking.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,14 +18,13 @@
#ifndef GZ_GUI_PLUGINS_CAMERATRACKING_HH_
#define GZ_GUI_PLUGINS_CAMERATRACKING_HH_

#include <gz/utils/ImplPtr.hh>
#include <memory>

#include "gz/gui/Plugin.hh"

namespace gz::gui::plugins
{
class CameraTrackingPrivate;

/// \brief This plugin provides camera tracking capabilities such as "move to"
/// and "follow".
///
Expand Down Expand Up @@ -58,7 +57,7 @@ namespace gz::gui::plugins

/// \internal
/// \brief Pointer to private data.
private: std::unique_ptr<CameraTrackingPrivate> dataPtr;
GZ_UTILS_UNIQUE_IMPL_PTR(dataPtr)
};
} // namespace gz::gui::plugins

Expand Down
4 changes: 2 additions & 2 deletions src/plugins/grid_config/GridConfig.cc
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ namespace gz::gui
math::Color color{math::Color(0.7f, 0.7f, 0.7f, 1.0f)};
};

class GridConfigPrivate
class GridConfig::Implementation
{
/// \brief List of grid names.
public: QStringList nameList;
Expand Down Expand Up @@ -84,7 +84,7 @@ namespace gz::gui

/////////////////////////////////////////////////
GridConfig::GridConfig()
: dataPtr(std::make_unique<GridConfigPrivate>())
: dataPtr(gz::utils::MakeUniqueImpl<Implementation>())
{
}

Expand Down
11 changes: 6 additions & 5 deletions src/plugins/grid_config/GridConfig.hh
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,9 @@

#include <gz/gui/Plugin.hh>

namespace gz::gui
#include <gz/utils/ImplPtr.hh>

namespace gz::gui::plugins
{
class GridConfigPrivate;

Expand Down Expand Up @@ -139,8 +141,7 @@ namespace gz::gui

/// \internal
/// \brief Pointer to private data.
private: std::unique_ptr<GridConfigPrivate> dataPtr;
private: GZ_UTILS_UNIQUE_IMPL_PTR(dataPtr)
};
} // namespace gz::gui

#endif // GZ_GUI_GRIDCONFIG_HH_
} // namespace gz::gui::plugins
#endif // GZ_GUI_PLUGINS_GRIDCONFIG_HH_
4 changes: 2 additions & 2 deletions src/plugins/image_display/ImageDisplay.cc
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@

namespace gz::gui::plugins
{
class ImageDisplayPrivate
class ImageDisplay::Implementation
{
/// \brief List of topics publishing image messages.
public: QStringList topicList;
Expand All @@ -55,7 +55,7 @@ class ImageDisplayPrivate

/////////////////////////////////////////////////
ImageDisplay::ImageDisplay()
: dataPtr(new ImageDisplayPrivate)
: dataPtr(gz::utils::MakeUniqueImpl<Implementation>())
{
}

Expand Down
13 changes: 10 additions & 3 deletions src/plugins/image_display/ImageDisplay.hh
Original file line number Diff line number Diff line change
Expand Up @@ -36,10 +36,10 @@

#include "gz/gui/Plugin.hh"

#include <gz/utils/ImplPtr.hh>

namespace gz::gui::plugins
{
class ImageDisplayPrivate;

class ImageProvider : public QQuickImageProvider
{
public: ImageProvider()
Expand Down Expand Up @@ -128,9 +128,16 @@ namespace gz::gui::plugins
/// \param[in] _msg New image
private: void OnImageMsg(const gz::msgs::Image &_msg);

/// \brief Callback in main thread when image changes
private slots: void ProcessImage();

/// \brief Subscriber callback when new image is received
/// \param[in] _msg New image
private: void OnImageMsg(const gz::msgs::Image &_msg);

/// \internal
/// \brief Pointer to private data.
private: std::unique_ptr<ImageDisplayPrivate> dataPtr;
GZ_UTILS_UNIQUE_IMPL_PTR(dataPtr)
};
} // namespace gz::gui::plugins

Expand Down
Loading

0 comments on commit b84c93f

Please sign in to comment.