Skip to content

Commit

Permalink
Use PIMPL pattern in gzserver (#683)
Browse files Browse the repository at this point in the history
Signed-off-by: Addisu Z. Taddese <[email protected]>
  • Loading branch information
azeey authored Jan 15, 2025
1 parent e3bed25 commit 6156b3e
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 8 deletions.
7 changes: 4 additions & 3 deletions ros_gz_sim/include/ros_gz_sim/gzserver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef ROS_GZ_SIM__GZSERVER_HPP_
#define ROS_GZ_SIM__GZSERVER_HPP_

#include <thread>
#include <gz/utils/ImplPtr.hh>
#include <rclcpp/node.hpp>

// ROS node that executes a gz-sim Server given a world SDF file or string.
Expand All @@ -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

Expand Down
20 changes: 15 additions & 5 deletions ros_gz_sim/src/gzserver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,30 +12,40 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "ros_gz_sim/gzserver.hpp"

#include <functional>
#include <thread>
#include <gz/common/Console.hh>
#include <gz/sim/Server.hh>
#include <gz/sim/SystemLoader.hh>
#include <gz/sim/ServerConfig.hh>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_components/register_node_macro.hpp>

#include <ros_gz_sim/gzserver.hpp>

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<Implementation>())
{
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();
}
}

Expand Down

0 comments on commit 6156b3e

Please sign in to comment.