From 8ad6eb0005510f20dbc752fc2d9912335c8c87ec Mon Sep 17 00:00:00 2001 From: Patrick Roncagliolo Date: Wed, 8 Jan 2025 16:56:08 +0100 Subject: [PATCH] Expose header for `GzServer` MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Patrick Roncagliolo Co-authored-by: Alejandro Hernández Cordero --- ros_gz_sim/include/ros_gz_sim/gzserver.hpp | 44 +++++++++++++ ros_gz_sim/src/gzserver.cpp | 77 ++++++++++------------ 2 files changed, 77 insertions(+), 44 deletions(-) create mode 100644 ros_gz_sim/include/ros_gz_sim/gzserver.hpp diff --git a/ros_gz_sim/include/ros_gz_sim/gzserver.hpp b/ros_gz_sim/include/ros_gz_sim/gzserver.hpp new file mode 100644 index 00000000..b7f87c76 --- /dev/null +++ b/ros_gz_sim/include/ros_gz_sim/gzserver.hpp @@ -0,0 +1,44 @@ +// Copyright 2025 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 ROS_GZ_SIM__GZSERVER_HPP_ +#define ROS_GZ_SIM__GZSERVER_HPP_ + +#include +#include + +// ROS node that executes a gz-sim Server given a world SDF file or string. +namespace ros_gz_sim +{ +class GzServer : public rclcpp::Node +{ +public: + // Class constructor. + explicit GzServer(const rclcpp::NodeOptions & options); + +public: + // Class destructor. + ~GzServer(); + +public: + /// \brief Run the gz sim server. + void OnStart(); + +private: + /// \brief We don't want to block the ROS thread. + std::thread thread_; +}; +} // namespace ros_gz_sim + +#endif // ROS_GZ_SIM__GZSERVER_HPP_ diff --git a/ros_gz_sim/src/gzserver.cpp b/ros_gz_sim/src/gzserver.cpp index aa4361f5..08d5057e 100644 --- a/ros_gz_sim/src/gzserver.cpp +++ b/ros_gz_sim/src/gzserver.cpp @@ -13,7 +13,6 @@ // limitations under the License. #include -#include #include #include #include @@ -21,60 +20,50 @@ #include #include -// ROS node that executes a gz-sim Server given a world SDF file or string. +#include + namespace ros_gz_sim { -class GzServer : public rclcpp::Node + +GzServer::GzServer(const rclcpp::NodeOptions & options) +: Node("gzserver", options) { -public: - // Class constructor. - explicit GzServer(const rclcpp::NodeOptions & options) - : Node("gzserver", options) - { - thread_ = std::thread(std::bind(&GzServer::OnStart, this)); - } + thread_ = std::thread(std::bind(&GzServer::OnStart, this)); +} -public: - // Class destructor. - ~GzServer() - { - // Make sure to join the thread on shutdown. - if (thread_.joinable()) { - thread_.join(); - } +GzServer::~GzServer() +{ + // Make sure to join the thread on shutdown. + if (thread_.joinable()) { + thread_.join(); } +} -public: - /// \brief Run the gz sim server. - void OnStart() - { - auto world_sdf_file = this->declare_parameter("world_sdf_file", ""); - auto world_sdf_string = this->declare_parameter("world_sdf_string", ""); - - gz::common::Console::SetVerbosity(4); - gz::sim::ServerConfig server_config; +void GzServer::OnStart() +{ + auto world_sdf_file = this->declare_parameter("world_sdf_file", ""); + auto world_sdf_string = this->declare_parameter("world_sdf_string", ""); - if (!world_sdf_file.empty()) { - server_config.SetSdfFile(world_sdf_file); - } else if (!world_sdf_string.empty()) { - server_config.SetSdfString(world_sdf_string); - } else { - RCLCPP_ERROR( - this->get_logger(), - "Must specify either 'world_sdf_file' or 'world_sdf_string'"); - rclcpp::shutdown(); - return; - } + gz::common::Console::SetVerbosity(4); + gz::sim::ServerConfig server_config; - gz::sim::Server server(server_config); - server.Run(true /*blocking*/, 0, false /*paused*/); + if (!world_sdf_file.empty()) { + server_config.SetSdfFile(world_sdf_file); + } else if (!world_sdf_string.empty()) { + server_config.SetSdfString(world_sdf_string); + } else { + RCLCPP_ERROR( + this->get_logger(), + "Must specify either 'world_sdf_file' or 'world_sdf_string'"); rclcpp::shutdown(); + return; } -private: - /// \brief We don't want to block the ROS thread. - std::thread thread_; -}; + gz::sim::Server server(server_config); + server.Run(true /*blocking*/, 0, false /*paused*/); + rclcpp::shutdown(); +} + } // namespace ros_gz_sim RCLCPP_COMPONENTS_REGISTER_NODE(ros_gz_sim::GzServer)