Skip to content

Commit

Permalink
Remaining plugins to use implptr
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <mjcarroll@intrinsic.ai>
  • Loading branch information
mjcarroll committed Oct 6, 2023
1 parent c00d759 commit 6a617e0
Show file tree
Hide file tree
Showing 38 changed files with 254 additions and 274 deletions.
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
46 changes: 23 additions & 23 deletions src/plugins/camera_tracking/CameraTracking.cc
Original file line number Diff line number Diff line change
Expand Up @@ -160,7 +160,7 @@ class CameraTracking::Implementation
};

/////////////////////////////////////////////////
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 @@ -170,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 @@ -184,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 @@ -210,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 @@ -230,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 @@ -241,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 @@ -268,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 @@ -295,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 @@ -313,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 @@ -323,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 @@ -345,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 @@ -367,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
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 @@ struct GridParam
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 @@ class GridConfigPrivate

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

Expand Down
4 changes: 3 additions & 1 deletion src/plugins/grid_config/GridConfig.hh
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@

#include <gz/gui/Plugin.hh>

#include <gz/utils/ImplPtr.hh>

namespace gz::gui::plugins
{
class GridConfigPrivate;
Expand Down Expand Up @@ -139,7 +141,7 @@ class GridConfig : public gz::gui::Plugin

/// \internal
/// \brief Pointer to private data.
private: std::unique_ptr<GridConfigPrivate> dataPtr;
private: GZ_UTILS_UNIQUE_IMPL_PTR(dataPtr)
};
} // 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()
: Plugin(), dataPtr(new ImageDisplayPrivate)
: dataPtr(gz::utils::MakeUniqueImpl<Implementation>())
{
}

Expand Down
6 changes: 3 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 @@ -130,7 +130,7 @@ class ImageDisplay_EXPORTS_API ImageDisplay : public Plugin

/// \internal
/// \brief Pointer to private data.
private: std::unique_ptr<ImageDisplayPrivate> dataPtr;
GZ_UTILS_UNIQUE_IMPL_PTR(dataPtr)
};
} // namespace gz::gui::plugins
#endif // GZ_GUI_PLUGINS_IMAGEDISPLAY_HH_
26 changes: 13 additions & 13 deletions src/plugins/interactive_view_control/InteractiveViewControl.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <gz/msgs/double.pb.h>
#include <gz/msgs/stringmsg.pb.h>

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

Expand Down Expand Up @@ -46,7 +47,7 @@
namespace gz::gui::plugins
{
/// \brief Private data class for InteractiveViewControl
class InteractiveViewControlPrivate
class InteractiveViewControl::Implementation
{
/// \brief Perform rendering calls in the rendering thread.
public: void OnRender();
Expand Down Expand Up @@ -147,7 +148,7 @@ class InteractiveViewControlPrivate
};

/////////////////////////////////////////////////
void InteractiveViewControlPrivate::OnRender()
void InteractiveViewControl::Implementation::OnRender()
{
if (!this->scene)
{
Expand Down Expand Up @@ -315,7 +316,7 @@ void InteractiveViewControlPrivate::OnRender()
}

/////////////////////////////////////////////////
void InteractiveViewControlPrivate::UpdateReferenceVisual()
void InteractiveViewControl::Implementation::UpdateReferenceVisual()
{
if (!this->refVisual || !this->enableRefVisual)
return;
Expand All @@ -331,8 +332,8 @@ void InteractiveViewControlPrivate::UpdateReferenceVisual()
}

/////////////////////////////////////////////////
bool InteractiveViewControlPrivate::OnViewControl(const msgs::StringMsg &_msg,
msgs::Boolean &_res)
bool InteractiveViewControl::Implementation::OnViewControl(
const msgs::StringMsg &_msg, msgs::Boolean &_res)
{
std::lock_guard<std::mutex> lock(this->mutex);

Expand All @@ -355,8 +356,8 @@ bool InteractiveViewControlPrivate::OnViewControl(const msgs::StringMsg &_msg,
}

/////////////////////////////////////////////////
bool InteractiveViewControlPrivate::OnReferenceVisual(const msgs::Boolean &_msg,
msgs::Boolean &_res)
bool InteractiveViewControl::Implementation::OnReferenceVisual(
const msgs::Boolean &_msg, msgs::Boolean &_res)
{
std::lock_guard<std::mutex> lock(this->mutex);
this->enableRefVisual = _msg.data();
Expand All @@ -366,7 +367,7 @@ bool InteractiveViewControlPrivate::OnReferenceVisual(const msgs::Boolean &_msg,
}

/////////////////////////////////////////////////
bool InteractiveViewControlPrivate::OnViewControlSensitivity(
bool InteractiveViewControl::Implementation::OnViewControlSensitivity(
const msgs::Double &_msg, msgs::Boolean &_res)
{
std::lock_guard<std::mutex> lock(this->mutex);
Expand All @@ -387,7 +388,7 @@ bool InteractiveViewControlPrivate::OnViewControlSensitivity(

/////////////////////////////////////////////////
InteractiveViewControl::InteractiveViewControl()
: Plugin(), dataPtr(std::make_unique<InteractiveViewControlPrivate>())
: dataPtr(gz::utils::MakeUniqueImpl<Implementation>())
{
}

Expand All @@ -404,15 +405,15 @@ void InteractiveViewControl::LoadConfig(
// camera view control mode
this->dataPtr->cameraViewControlService = "/gui/camera/view_control";
this->dataPtr->node.Advertise(this->dataPtr->cameraViewControlService,
&InteractiveViewControlPrivate::OnViewControl, this->dataPtr.get());
&Implementation::OnViewControl, this->dataPtr.get());
gzmsg << "Camera view controller topic advertised on ["
<< this->dataPtr->cameraViewControlService << "]" << std::endl;

// camera reference visual
this->dataPtr->cameraRefVisualService =
"/gui/camera/view_control/reference_visual";
this->dataPtr->node.Advertise(this->dataPtr->cameraRefVisualService,
&InteractiveViewControlPrivate::OnReferenceVisual, this->dataPtr.get());
&Implementation::OnReferenceVisual, this->dataPtr.get());
gzmsg << "Camera reference visual topic advertised on ["
<< this->dataPtr->cameraRefVisualService << "]" << std::endl;

Expand All @@ -421,7 +422,7 @@ void InteractiveViewControl::LoadConfig(
"/gui/camera/view_control/sensitivity";
this->dataPtr->node.Advertise(
this->dataPtr->cameraViewControlSensitivityService,
&InteractiveViewControlPrivate::OnViewControlSensitivity,
&Implementation::OnViewControlSensitivity,
this->dataPtr.get());
gzmsg << "Camera view control sensitivity advertised on ["
<< this->dataPtr->cameraViewControlSensitivityService << "]"
Expand Down Expand Up @@ -501,7 +502,6 @@ bool InteractiveViewControl::eventFilter(QObject *_obj, QEvent *_event)
return QObject::eventFilter(_obj, _event);
}
} // namespace gz::gui::plugins

// Register this plugin
GZ_ADD_PLUGIN(gz::gui::plugins::InteractiveViewControl,
gz::gui::Plugin)
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@

#include "gz/gui/Plugin.hh"

#include <gz/utils/ImplPtr.hh>

namespace gz::gui::plugins
{
class InteractiveViewControlPrivate;
Expand Down Expand Up @@ -64,7 +66,7 @@ class InteractiveViewControl : public Plugin

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

0 comments on commit 6a617e0

Please sign in to comment.