diff --git a/ros_gz_sim/include/ros_gz_sim/gzserver.hpp b/ros_gz_sim/include/ros_gz_sim/gzserver.hpp index b7f87c76..ac6ded0d 100644 --- a/ros_gz_sim/include/ros_gz_sim/gzserver.hpp +++ b/ros_gz_sim/include/ros_gz_sim/gzserver.hpp @@ -15,7 +15,7 @@ #ifndef ROS_GZ_SIM__GZSERVER_HPP_ #define ROS_GZ_SIM__GZSERVER_HPP_ -#include +#include #include // ROS node that executes a gz-sim Server given a world SDF file or string. @@ -36,8 +36,9 @@ class GzServer : public rclcpp::Node void OnStart(); private: - /// \brief We don't want to block the ROS thread. - std::thread thread_; + /// \internal + /// \brief Private data pointer. + GZ_UTILS_UNIQUE_IMPL_PTR(dataPtr) }; } // namespace ros_gz_sim diff --git a/ros_gz_sim/src/gzserver.cpp b/ros_gz_sim/src/gzserver.cpp index 08d5057e..d485971b 100644 --- a/ros_gz_sim/src/gzserver.cpp +++ b/ros_gz_sim/src/gzserver.cpp @@ -12,7 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "ros_gz_sim/gzserver.hpp" + #include +#include #include #include #include @@ -20,22 +23,29 @@ #include #include -#include namespace ros_gz_sim { +class GzServer::Implementation +{ + /// \brief We don't want to block the ROS thread. + +public: + std::thread thread; +}; + GzServer::GzServer(const rclcpp::NodeOptions & options) -: Node("gzserver", options) +: Node("gzserver", options), dataPtr(gz::utils::MakeUniqueImpl()) { - thread_ = std::thread(std::bind(&GzServer::OnStart, this)); + this->dataPtr->thread = std::thread(std::bind(&GzServer::OnStart, this)); } GzServer::~GzServer() { // Make sure to join the thread on shutdown. - if (thread_.joinable()) { - thread_.join(); + if (this->dataPtr->thread.joinable()) { + this->dataPtr->thread.join(); } }