From 40378528feedfa55a0afbfe817ed234a2b60bf32 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Thu, 18 Aug 2022 17:09:56 -0700 Subject: [PATCH] Add redirection headers Signed-off-by: methylDragon --- CMakeLists.txt | 4 +- examples/factory.ign | 6 +-- examples/gazebo_plugins.ign | 18 +++---- examples/multi_factory.ign | 2 +- examples/plugins.ign | 10 ++-- examples/websocket.ign | 2 +- include/CMakeLists.txt | 3 +- include/gz/launch/Plugin.hh | 10 ++-- include/ignition/launch.hh | 19 +++++++ include/ignition/launch/Export.hh | 19 +++++++ include/ignition/launch/Plugin.hh | 19 +++++++ include/ignition/launch/config.hh | 51 +++++++++++++++++++ plugins/gazebo_factory/GazeboFactory.cc | 4 +- plugins/gazebo_factory/GazeboFactory.hh | 14 ++--- plugins/gazebo_gui/GazeboGui.cc | 6 +-- plugins/gazebo_gui/GazeboGui.hh | 12 ++--- plugins/gazebo_server/GazeboServer.cc | 8 +-- plugins/gazebo_server/GazeboServer.hh | 16 +++--- plugins/joy_to_twist/JoyToTwist.cc | 14 ++--- plugins/joy_to_twist/JoyToTwist.hh | 40 +++++++-------- plugins/joystick/Joystick.cc | 14 ++--- plugins/joystick/Joystick.hh | 20 ++++---- .../websocket_server/MessageDefinitions.hh.in | 6 +-- plugins/websocket_server/WebsocketServer.cc | 32 ++++++------ plugins/websocket_server/WebsocketServer.hh | 24 ++++----- plugins/websocket_server/combined.proto | 2 +- plugins/websocket_server/index-old.html | 2 +- plugins/websocket_server/index.html | 4 +- src/CMakeLists.txt | 10 ++-- src/Manager.cc | 24 ++++----- src/Manager.hh | 6 +-- src/Manager_TEST.cc | 34 ++++++------- src/gz.cc | 4 +- src/gz.hh | 4 +- src/gz_TEST.cc | 2 +- test/CMakeLists.txt | 1 + test/integration/deprecated_TEST.cc | 26 ++++++++++ test/integration/faulty_plugins.cc | 2 +- test/integration/plugins/bad_plugins.cc | 4 +- test/integration/plugins/bad_plugins.hh | 2 +- test/test_config.hh.in | 4 +- 41 files changed, 321 insertions(+), 183 deletions(-) create mode 100644 include/ignition/launch.hh create mode 100644 include/ignition/launch/Export.hh create mode 100644 include/ignition/launch/Plugin.hh create mode 100644 include/ignition/launch/config.hh create mode 100644 test/integration/deprecated_TEST.cc diff --git a/CMakeLists.txt b/CMakeLists.txt index 4b287a93..64f80a42 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,7 +14,9 @@ set(IGN_CMAKE_VER ${ignition-cmake2_VERSION_MAJOR}) #============================================================================ # Configure the project #============================================================================ -ign_configure_project() +ign_configure_project( + REPLACE_IGNITION_INCLUDE_PATH gz/launch +) #============================================================================ # Set project-specific options diff --git a/examples/factory.ign b/examples/factory.ign index cfb978a2..d06bc214 100644 --- a/examples/factory.ign +++ b/examples/factory.ign @@ -1,6 +1,6 @@ - x2 @@ -11,7 +11,7 @@ https://fuel.ignitionrobotics.org/1.0/openrobotics/models/X2 UGV/1 + name="gz::sim::systems::DiffDrive"> front_left_wheel_joint rear_left_wheel_joint front_right_wheel_joint @@ -22,7 +22,7 @@ + name="gz::sim::systems::JointStatePublisher"> diff --git a/examples/gazebo_plugins.ign b/examples/gazebo_plugins.ign index 477eb21d..d20c0e3f 100644 --- a/examples/gazebo_plugins.ign +++ b/examples/gazebo_plugins.ign @@ -19,7 +19,7 @@ - /dev/input/js0 false @@ -30,7 +30,7 @@ - /joy /model/vehicle_green/cmd_vel @@ -38,14 +38,14 @@ - /joy /model/vehicle_blue/cmd_vel - <%= worldName %>.sdf true @@ -79,18 +79,18 @@ + name="gz::sim::systems::Physics"> + name="gz::sim::systems::SceneBroadcaster"> + name="gz::sim::systems::DiffDrive"> left_wheel_joint right_wheel_joint 1.25 @@ -100,7 +100,7 @@ + name="gz::sim::systems::DiffDrive"> left_wheel_joint right_wheel_joint 1.25 @@ -111,7 +111,7 @@ - diff --git a/examples/multi_factory.ign b/examples/multi_factory.ign index 1f338232..48df749b 100644 --- a/examples/multi_factory.ign +++ b/examples/multi_factory.ign @@ -1,6 +1,6 @@ - x2 diff --git a/examples/plugins.ign b/examples/plugins.ign index 6fcd3867..7df01887 100644 --- a/examples/plugins.ign +++ b/examples/plugins.ign @@ -3,7 +3,7 @@ - /dev/input/js0 false @@ -14,7 +14,7 @@ - /joy /model/vehicle_green/cmd_vel @@ -22,12 +22,12 @@ - - + /joy - + /model/vehicle_blue/cmd_vel diff --git a/examples/websocket.ign b/examples/websocket.ign index 2e696bac..d76c42e1 100644 --- a/examples/websocket.ign +++ b/examples/websocket.ign @@ -3,7 +3,7 @@ - 30 9002 diff --git a/include/CMakeLists.txt b/include/CMakeLists.txt index 25ec8976..4b2bdd7b 100644 --- a/include/CMakeLists.txt +++ b/include/CMakeLists.txt @@ -1 +1,2 @@ -add_subdirectory(ignition) +add_subdirectory(gz) +install(DIRECTORY ignition DESTINATION ${IGN_INCLUDE_INSTALL_DIR_FULL}) diff --git a/include/gz/launch/Plugin.hh b/include/gz/launch/Plugin.hh index a3b66e97..a4435690 100644 --- a/include/gz/launch/Plugin.hh +++ b/include/gz/launch/Plugin.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_LAUNCH_PLUGIN_HH_ -#define IGNITION_LAUNCH_PLUGIN_HH_ +#ifndef GZ_LAUNCH_PLUGIN_HH_ +#define GZ_LAUNCH_PLUGIN_HH_ #include #include #include -namespace ignition +namespace gz { namespace launch { @@ -38,8 +38,8 @@ namespace ignition }; /// \brief Pointer to a launch plugin. - using PluginPtr = ignition::plugin::SpecializedPluginPtr< - ignition::launch::Plugin>; + using PluginPtr = gz::plugin::SpecializedPluginPtr< + gz::launch::Plugin>; } } } diff --git a/include/ignition/launch.hh b/include/ignition/launch.hh new file mode 100644 index 00000000..f98a82e2 --- /dev/null +++ b/include/ignition/launch.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 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. + * + */ + +#include +#include diff --git a/include/ignition/launch/Export.hh b/include/ignition/launch/Export.hh new file mode 100644 index 00000000..6d8f9e22 --- /dev/null +++ b/include/ignition/launch/Export.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 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. + * + */ + +#include +#include diff --git a/include/ignition/launch/Plugin.hh b/include/ignition/launch/Plugin.hh new file mode 100644 index 00000000..c373fd59 --- /dev/null +++ b/include/ignition/launch/Plugin.hh @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2022 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. + * + */ + +#include +#include diff --git a/include/ignition/launch/config.hh b/include/ignition/launch/config.hh new file mode 100644 index 00000000..40fea513 --- /dev/null +++ b/include/ignition/launch/config.hh @@ -0,0 +1,51 @@ +/* + * Copyright (C) 2022 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 IGNITION_LAUNCH__CONFIG_HH_ +#define IGNITION_LAUNCH__CONFIG_HH_ + +#include + +/* Version number */ +// #define IGNITION_LAUNCH_MAJOR_VERSION GZ_LAUNCH_MAJOR_VERSION +// #define IGNITION_LAUNCH_MINOR_VERSION GZ_LAUNCH_MINOR_VERSION +// #define IGNITION_LAUNCH_PATCH_VERSION GZ_LAUNCH_PATCH_VERSION + +// #define IGNITION_LAUNCH_VERSION GZ_LAUNCH_VERSION +// #define IGNITION_LAUNCH_VERSION_FULL GZ_LAUNCH_VERSION_FULL + +// #define IGNITION_LAUNCH_VERSION_HEADER GZ_LAUNCH_VERSION_HEADER + +// #define IGNITION_LAUNCH_INITIAL_CONFIG_PATH GZ_LAUNCH_INITIAL_CONFIG_PATH + +// #define IGNITION_LAUNCH_PLUGIN_INSTALL_PATH GZ_LAUNCH_PLUGIN_INSTALL_PATH + +/* #undef BUILD_TYPE_PROFILE */ +/* #undef BUILD_TYPE_DEBUG */ +/* #undef BUILD_TYPE_RELEASE */ + +namespace gz +{ +} + +namespace ignition +{ + using namespace gz; +} + + +#endif diff --git a/plugins/gazebo_factory/GazeboFactory.cc b/plugins/gazebo_factory/GazeboFactory.cc index ee4cd98a..bf0f2d46 100644 --- a/plugins/gazebo_factory/GazeboFactory.cc +++ b/plugins/gazebo_factory/GazeboFactory.cc @@ -22,8 +22,8 @@ #include #include "GazeboFactory.hh" -using namespace ignition; -using namespace ignition::launch; +using namespace gz; +using namespace gz::launch; ///////////////////////////////////////////////// GazeboFactory::GazeboFactory() diff --git a/plugins/gazebo_factory/GazeboFactory.hh b/plugins/gazebo_factory/GazeboFactory.hh index 1f9b56dd..b8fed89e 100644 --- a/plugins/gazebo_factory/GazeboFactory.hh +++ b/plugins/gazebo_factory/GazeboFactory.hh @@ -14,22 +14,22 @@ * limitations under the License. * */ -#ifndef IGNITION_LAUNCH_GAZEBOFACTORY_HH_ -#define IGNITION_LAUNCH_GAZEBOFACTORY_HH_ +#ifndef GZ_LAUNCH_GAZEBOFACTORY_HH_ +#define GZ_LAUNCH_GAZEBOFACTORY_HH_ #include #include #include #include "ignition/launch/Plugin.hh" -namespace ignition +namespace gz { namespace launch { /// \brief Spawns entities into simulation. /// /// # Example usage - /// /// /// @@ -50,7 +50,7 @@ namespace ignition /// https://fuel.ignitionrobotics.org/1.0/openrobotics/models/X2 UGV/1 /// /// + /// name="gz::sim::systems::StatePublisher"> /// /// /// @@ -59,7 +59,7 @@ namespace ignition /// ... /// /// - class GazeboFactory : public ignition::launch::Plugin + class GazeboFactory : public gz::launch::Plugin { /// \brief Constructor. public: GazeboFactory(); @@ -90,6 +90,6 @@ namespace ignition } // Register the plugin -IGNITION_ADD_PLUGIN(ignition::launch::GazeboFactory, ignition::launch::Plugin) +IGNITION_ADD_PLUGIN(gz::launch::GazeboFactory, gz::launch::Plugin) #endif diff --git a/plugins/gazebo_gui/GazeboGui.cc b/plugins/gazebo_gui/GazeboGui.cc index 1951d6a2..fe5c8c3e 100644 --- a/plugins/gazebo_gui/GazeboGui.cc +++ b/plugins/gazebo_gui/GazeboGui.cc @@ -27,8 +27,8 @@ #include "GazeboGui.hh" -using namespace ignition; -using namespace ignition::launch; +using namespace gz; +using namespace gz::launch; ///////////////////////////////////////////////// GazeboGui::GazeboGui() @@ -97,7 +97,7 @@ bool GazeboGui::Load(const tinyxml2::XMLElement *_elem) } } - auto app = gazebo::gui::createGui(argc, argv, defaultConfigFile.c_str(), + auto app = sim::gui::createGui(argc, argv, defaultConfigFile.c_str(), defaultConfigFile.c_str(), false); auto win = app->findChild()->QuickWindow(); diff --git a/plugins/gazebo_gui/GazeboGui.hh b/plugins/gazebo_gui/GazeboGui.hh index 0956ad5d..d7558429 100644 --- a/plugins/gazebo_gui/GazeboGui.hh +++ b/plugins/gazebo_gui/GazeboGui.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_LAUNCH_GAZEBOGUI_HH_ -#define IGNITION_LAUNCH_GAZEBOGUI_HH_ +#ifndef GZ_LAUNCH_GAZEBOGUI_HH_ +#define GZ_LAUNCH_GAZEBOGUI_HH_ #include #include #include #include -namespace ignition +namespace gz { namespace launch { @@ -38,7 +38,7 @@ namespace ignition /// /// /// - /// /// /// @@ -56,7 +56,7 @@ namespace ignition /// /// /// - class GazeboGui : public ignition::launch::Plugin + class GazeboGui : public gz::launch::Plugin { /// \brief Constructor. public: GazeboGui(); @@ -72,6 +72,6 @@ namespace ignition } // Register the plugin -IGNITION_ADD_PLUGIN(ignition::launch::GazeboGui, ignition::launch::Plugin) +IGNITION_ADD_PLUGIN(gz::launch::GazeboGui, gz::launch::Plugin) #endif diff --git a/plugins/gazebo_server/GazeboServer.cc b/plugins/gazebo_server/GazeboServer.cc index 394c8d01..ca21e3e0 100644 --- a/plugins/gazebo_server/GazeboServer.cc +++ b/plugins/gazebo_server/GazeboServer.cc @@ -19,8 +19,8 @@ #include #include "GazeboServer.hh" -using namespace ignition; -using namespace ignition::launch; +using namespace gz; +using namespace gz::launch; ///////////////////////////////////////////////// void copyElement(sdf::ElementPtr _sdf, const tinyxml2::XMLElement *_xml) @@ -59,7 +59,7 @@ GazeboServer::GazeboServer() ///////////////////////////////////////////////// bool GazeboServer::Load(const tinyxml2::XMLElement *_elem) { - gazebo::ServerConfig serverConfig; + sim::ServerConfig serverConfig; const tinyxml2::XMLElement *elem; // Get the world file @@ -342,7 +342,7 @@ bool GazeboServer::Load(const tinyxml2::XMLElement *_elem) } // Create and run the simulation server - this->server.reset(new gazebo::Server(serverConfig)); + this->server.reset(new sim::Server(serverConfig)); this->server->Run(false, 0, !run); igndbg << "Loaded GazeboServer plugin.\n"; diff --git a/plugins/gazebo_server/GazeboServer.hh b/plugins/gazebo_server/GazeboServer.hh index 2ba46fba..f65a405f 100644 --- a/plugins/gazebo_server/GazeboServer.hh +++ b/plugins/gazebo_server/GazeboServer.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_LAUNCH_GAZEBOSERVER_HH_ -#define IGNITION_LAUNCH_GAZEBOSERVER_HH_ +#ifndef GZ_LAUNCH_GAZEBOSERVER_HH_ +#define GZ_LAUNCH_GAZEBOSERVER_HH_ #include #include #include #include "ignition/launch/Plugin.hh" -namespace ignition +namespace gz { namespace launch { @@ -30,7 +30,7 @@ namespace ignition /// /// # Example usage /// - /// /// /// diff_drive.sdf @@ -39,12 +39,12 @@ namespace ignition /// + /// name="gz::sim::systems::v0::Physics"> /// /// /// /// - class GazeboServer : public ignition::launch::Plugin + class GazeboServer : public gz::launch::Plugin { /// \brief Constructor. public: GazeboServer(); @@ -57,12 +57,12 @@ namespace ignition const tinyxml2::XMLElement *_elem) override final; /// \brief Private data pointer - private: std::unique_ptr server; + private: std::unique_ptr server; }; } } // Register the plugin -IGNITION_ADD_PLUGIN(ignition::launch::GazeboServer, ignition::launch::Plugin) +IGNITION_ADD_PLUGIN(gz::launch::GazeboServer, gz::launch::Plugin) #endif diff --git a/plugins/joy_to_twist/JoyToTwist.cc b/plugins/joy_to_twist/JoyToTwist.cc index b262f25d..b255a3f1 100644 --- a/plugins/joy_to_twist/JoyToTwist.cc +++ b/plugins/joy_to_twist/JoyToTwist.cc @@ -25,16 +25,16 @@ #include "JoyToTwist.hh" -using namespace ignition::launch; +using namespace gz::launch; ////////////////////////////////////////////////// // String to vector helper function. void setVectorFromString(const std::string &_str, - ignition::math::Vector3d &_v) + gz::math::Vector3d &_v) { - std::string str = ignition::common::trimmed(_str); + std::string str = gz::common::trimmed(_str); - std::vector parts = ignition::common::split(str, " "); + std::vector parts = gz::common::split(str, " "); if (parts.size() == 3) { _v.X(std::stod(parts[0])); @@ -101,7 +101,7 @@ bool JoyToTwist::Load(const tinyxml2::XMLElement *_elem) if (elem) setVectorFromString(elem->GetText(), this->scaleAngularTurbo); - this->cmdVelPub = this->node.Advertise( + this->cmdVelPub = this->node.Advertise( this->outputTopic); igndbg << "Loaded JoyToTwist plugin with the following parameters:\n" @@ -114,12 +114,12 @@ bool JoyToTwist::Load(const tinyxml2::XMLElement *_elem) } ////////////////////////////////////////////////// -void JoyToTwist::OnJoy(const ignition::msgs::Joy &_msg) +void JoyToTwist::OnJoy(const gz::msgs::Joy &_msg) { if (!this->running) return; - ignition::msgs::Twist cmdVelMsg; + gz::msgs::Twist cmdVelMsg; // Turbo mode if (this->enableTurboButton >= 0 && _msg.buttons(this->enableTurboButton)) { diff --git a/plugins/joy_to_twist/JoyToTwist.hh b/plugins/joy_to_twist/JoyToTwist.hh index 517e802e..8853dbdd 100644 --- a/plugins/joy_to_twist/JoyToTwist.hh +++ b/plugins/joy_to_twist/JoyToTwist.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_LAUNCH_JOYTOTWIST_HH_ -#define IGNITION_LAUNCH_JOYTOTWIST_HH_ +#ifndef GZ_LAUNCH_JOYTOTWIST_HH_ +#define GZ_LAUNCH_JOYTOTWIST_HH_ #include #include @@ -25,23 +25,23 @@ #include #include -namespace ignition +namespace gz { namespace launch { - /// \brief Converts ignition::msgs::Joystick messages to - /// ignition::msgs::Twist. + /// \brief Converts gz::msgs::Joystick messages to + /// gz::msgs::Twist. /// /// # Example usage /// - /// - /// + /// /// + /// gz::msgs::Joystick messages --> /// /joy /// - /// + /// /// /model/vehicle_blue/cmd_vel /// /// /// 4 /// - class JoyToTwist : public ignition::launch::Plugin + class JoyToTwist : public gz::launch::Plugin { /// \brief Constructor public: JoyToTwist(); @@ -88,24 +88,24 @@ namespace ignition /// \brief Handle joystick messages. /// \param[in] _msg Joystick message. - private: void OnJoy(const ignition::msgs::Joy &_msg); + private: void OnJoy(const gz::msgs::Joy &_msg); private: int enableButton = 0; private: int enableTurboButton = -1; - private: ignition::math::Vector3d axisLinear{1.0, 0.0, 0.0}; - private: ignition::math::Vector3d scaleLinear{0.5, 0.0, 0.0}; - private: ignition::math::Vector3d scaleLinearTurbo{0.5, 0.0, 0.0}; + private: gz::math::Vector3d axisLinear{1.0, 0.0, 0.0}; + private: gz::math::Vector3d scaleLinear{0.5, 0.0, 0.0}; + private: gz::math::Vector3d scaleLinearTurbo{0.5, 0.0, 0.0}; - private: ignition::math::Vector3d axisAngular{0.0, 0.0, 0.0}; - private: ignition::math::Vector3d scaleAngular{0.0, 0.0, 0.5}; - private: ignition::math::Vector3d scaleAngularTurbo{0.0, 0.0, 0.5}; + private: gz::math::Vector3d axisAngular{0.0, 0.0, 0.0}; + private: gz::math::Vector3d scaleAngular{0.0, 0.0, 0.5}; + private: gz::math::Vector3d scaleAngularTurbo{0.0, 0.0, 0.5}; private: bool sentDisableMsg = false; private: bool running = false; private: std::thread *joyThread = nullptr; - private: ignition::transport::Node node; - private: ignition::transport::Node::Publisher cmdVelPub; + private: gz::transport::Node node; + private: gz::transport::Node::Publisher cmdVelPub; private: std::string inputTopic = "/joy"; private: std::string outputTopic = "/cmd_vel"; @@ -114,6 +114,6 @@ namespace ignition } // Register the plugin -IGNITION_ADD_PLUGIN(ignition::launch::JoyToTwist, ignition::launch::Plugin) +IGNITION_ADD_PLUGIN(gz::launch::JoyToTwist, gz::launch::Plugin) #endif diff --git a/plugins/joystick/Joystick.cc b/plugins/joystick/Joystick.cc index 99f8122f..595c6cbe 100644 --- a/plugins/joystick/Joystick.cc +++ b/plugins/joystick/Joystick.cc @@ -27,7 +27,7 @@ #include "Joystick.hh" -using namespace ignition::launch; +using namespace gz::launch; ///////////////////////////////////////////////// Joystick::Joystick() @@ -72,7 +72,7 @@ bool Joystick::Load(const tinyxml2::XMLElement *_elem) { try { - deadzone = ignition::math::clamp(std::stof(elem->GetText()), 0.0f, 0.9f); + deadzone = gz::math::clamp(std::stof(elem->GetText()), 0.0f, 0.9f); } catch(...) { @@ -168,7 +168,7 @@ bool Joystick::Load(const tinyxml2::XMLElement *_elem) this->axisScale = -1.0f / (1.0f - deadzone) / 32767.0f; // Create the publisher of joy messages - this->pub = this->node.Advertise("/joy"); + this->pub = this->node.Advertise("/joy"); this->run = true; this->joyThread = new std::thread(std::bind(&Joystick::Run, this)); @@ -192,9 +192,9 @@ void Joystick::Run() bool accumulate = false; bool accumulating = false; - ignition::msgs::Joy joyMsg; - ignition::msgs::Joy lastJoyMsg; - ignition::msgs::Joy stickyButtonsJoyMsg; + gz::msgs::Joy joyMsg; + gz::msgs::Joy lastJoyMsg; + gz::msgs::Joy stickyButtonsJoyMsg; while (this->run) { @@ -243,7 +243,7 @@ void Joystick::Run() // Update the button joyMsg.set_buttons(event.number, - !ignition::math::equal(value, 0.0f) ? 1 : 0); + !gz::math::equal(value, 0.0f) ? 1 : 0); // For initial events, wait a bit before sending to try to catch // all the initial events. diff --git a/plugins/joystick/Joystick.hh b/plugins/joystick/Joystick.hh index c70bf3bc..4ffef3a9 100644 --- a/plugins/joystick/Joystick.hh +++ b/plugins/joystick/Joystick.hh @@ -14,25 +14,25 @@ * limitations under the License. * */ -#ifndef IGNITION_LAUNCH_JOYSTICK_HH_ -#define IGNITION_LAUNCH_JOYSTICK_HH_ +#ifndef GZ_LAUNCH_JOYSTICK_HH_ +#define GZ_LAUNCH_JOYSTICK_HH_ #include #include #include #include -namespace ignition +namespace gz { namespace launch { /// \brief Reads from a USB joystick device and outputs - /// ignition::msgs::Joystick messages. + /// gz::msgs::Joystick messages. /// /// # Example usage /// - /// - /// + /// /// /// @@ -49,7 +49,7 @@ namespace ignition /// 1000 /// - class Joystick : public ignition::launch::Plugin + class Joystick : public gz::launch::Plugin { /// \brief Constructor public: Joystick(); @@ -73,13 +73,13 @@ namespace ignition private: float accumulationInterval = 0.001f; private: std::thread *joyThread = nullptr; - private: ignition::transport::Node node; - private: ignition::transport::Node::Publisher pub; + private: gz::transport::Node node; + private: gz::transport::Node::Publisher pub; }; } } // Register the plugin -IGNITION_ADD_PLUGIN(ignition::launch::Joystick, ignition::launch::Plugin) +IGNITION_ADD_PLUGIN(gz::launch::Joystick, gz::launch::Plugin) #endif diff --git a/plugins/websocket_server/MessageDefinitions.hh.in b/plugins/websocket_server/MessageDefinitions.hh.in index c6038d00..079059f6 100644 --- a/plugins/websocket_server/MessageDefinitions.hh.in +++ b/plugins/websocket_server/MessageDefinitions.hh.in @@ -14,10 +14,10 @@ * limitations under the License. * */ -#ifndef IGNITION_LAUNCH_WEBSOCKETSERVER_MESSAGEDEFINITIONS_HH_ -#define IGNITION_LAUNCH_WEBSOCKETSERVER_MESSAGEDEFINITIONS_HH_ +#ifndef GZ_LAUNCH_WEBSOCKETSERVER_MESSAGEDEFINITIONS_HH_ +#define GZ_LAUNCH_WEBSOCKETSERVER_MESSAGEDEFINITIONS_HH_ -namespace ignition +namespace gz { namespace launch { diff --git a/plugins/websocket_server/WebsocketServer.cc b/plugins/websocket_server/WebsocketServer.cc index 6b535543..01222951 100644 --- a/plugins/websocket_server/WebsocketServer.cc +++ b/plugins/websocket_server/WebsocketServer.cc @@ -23,7 +23,7 @@ #include "MessageDefinitions.hh" #include "WebsocketServer.hh" -using namespace ignition::launch; +using namespace gz::launch; /// \brief Construct a websocket frame header. /// \param[in] _op The operation string. @@ -310,7 +310,7 @@ int rootCallback(struct lws *_wsi, ///////////////////////////////////////////////// WebsocketServer::WebsocketServer() - : ignition::launch::Plugin() + : gz::launch::Plugin() { } @@ -465,7 +465,7 @@ bool WebsocketServer::Load(const tinyxml2::XMLElement *_elem) if (!sslCertFile.empty() && !sslPrivateKeyFile.empty()) { // Fail if the certificate file cannot be opened. - if (!ignition::common::exists(sslCertFile)) + if (!gz::common::exists(sslCertFile)) { ignerr << "SSL certificate file[" << sslCertFile << "] does not exist. Quitting.\n"; @@ -473,7 +473,7 @@ bool WebsocketServer::Load(const tinyxml2::XMLElement *_elem) } // Fail if the private key file cannot be opened. - if (!ignition::common::exists(sslPrivateKeyFile)) + if (!gz::common::exists(sslPrivateKeyFile)) { ignerr << "SSL private key file[" << sslPrivateKeyFile << "] does not exist. Quitting.\n"; @@ -650,15 +650,15 @@ void WebsocketServer::OnMessage(int _socketId, const std::string &_msg) igndbg << "Protos request received\n"; std::string allProtos = "syntax = \"proto3\";\n"; - allProtos += "package ignition.msgs;\n"; + allProtos += "package gz.msgs;\n"; std::vector types; - ignition::msgs::Factory::Types(types); + gz::msgs::Factory::Types(types); // Get all the messages, and build a single proto to send to the client. for (auto const &type : types) { - auto msg = ignition::msgs::Factory::New(type); + auto msg = gz::msgs::Factory::New(type); if (msg) { auto descriptor = msg->GetDescriptor(); @@ -682,7 +682,7 @@ void WebsocketServer::OnMessage(int _socketId, const std::string &_msg) else if (frameParts[0] == "topics") { igndbg << "Topic list request recieved\n"; - ignition::msgs::StringMsg_V msg; + gz::msgs::StringMsg_V msg; std::vector topics; @@ -694,7 +694,7 @@ void WebsocketServer::OnMessage(int _socketId, const std::string &_msg) msg.add_data(topic); std::string data = BUILD_MSG(this->operations[PUBLISH], frameParts[0], - std::string("ignition.msgs.StringMsg_V"), msg.SerializeAsString()); + std::string("gz.msgs.StringMsg_V"), msg.SerializeAsString()); // Queue the message for delivery. this->QueueMessage(this->connections[_socketId].get(), @@ -703,10 +703,10 @@ void WebsocketServer::OnMessage(int _socketId, const std::string &_msg) else if (frameParts[0] == "worlds") { igndbg << "World info request recieved\n"; - ignition::msgs::Empty req; + gz::msgs::Empty req; req.set_unused(true); - ignition::msgs::StringMsg_V rep; + gz::msgs::StringMsg_V rep; bool result; unsigned int timeout = 2000; @@ -714,7 +714,7 @@ void WebsocketServer::OnMessage(int _socketId, const std::string &_msg) req, timeout, rep, result); std::string data = BUILD_MSG(this->operations[PUBLISH], frameParts[0], - std::string("ignition.msgs.StringMsg_V"), rep.SerializeAsString()); + std::string("gz.msgs.StringMsg_V"), rep.SerializeAsString()); // Queue the message for delivery. this->QueueMessage(this->connections[_socketId].get(), @@ -724,10 +724,10 @@ void WebsocketServer::OnMessage(int _socketId, const std::string &_msg) { igndbg << "Scene info request recieved for world[" << frameParts[1] << "]\n"; - ignition::msgs::Empty req; + gz::msgs::Empty req; req.set_unused(true); - ignition::msgs::Scene rep; + gz::msgs::Scene rep; bool result; unsigned int timeout = 2000; @@ -742,7 +742,7 @@ void WebsocketServer::OnMessage(int _socketId, const std::string &_msg) } std::string data = BUILD_MSG(this->operations[PUBLISH], frameParts[0], - std::string("ignition.msgs.Scene"), rep.SerializeAsString()); + std::string("gz.msgs.Scene"), rep.SerializeAsString()); // Queue the message for delivery. this->QueueMessage(this->connections[_socketId].get(), @@ -766,7 +766,7 @@ void WebsocketServer::OnMessage(int _socketId, const std::string &_msg) ////////////////////////////////////////////////// void WebsocketServer::OnWebsocketSubscribedMessage( const char *_data, const size_t _size, - const ignition::transport::MessageInfo &_info) + const gz::transport::MessageInfo &_info) { std::map>::const_iterator iter = this->topicConnections.find(_info.Topic()); diff --git a/plugins/websocket_server/WebsocketServer.hh b/plugins/websocket_server/WebsocketServer.hh index 23bc50ea..1d68d9da 100644 --- a/plugins/websocket_server/WebsocketServer.hh +++ b/plugins/websocket_server/WebsocketServer.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_LAUNCH_WEBSOCKETSERVER_HH_ -#define IGNITION_LAUNCH_WEBSOCKETSERVER_HH_ +#ifndef GZ_LAUNCH_WEBSOCKETSERVER_HH_ +#define GZ_LAUNCH_WEBSOCKETSERVER_HH_ #include #include @@ -28,12 +28,12 @@ #include #include -namespace ignition +namespace gz { namespace launch { /// \brief Reads from a USB joystick device and outputs - /// ignition::msgs::WebsocketServer messages. + /// gz::msgs::WebsocketServer messages. /// /// # Plugin parameters /// @@ -95,7 +95,7 @@ namespace ignition /// /// The `message_type` component is mandatory for the "pub" operation. If /// present it names the Ignition Message type, such as - /// "ignition.msgs.Clock". + /// "gz.msgs.Clock". /// /// The `payload` component is mandatory for the "pub" operation. If /// present, it contains a serialized string of an Ignition Message. @@ -109,7 +109,7 @@ namespace ignition /// 3. Subscribe to the "/clock" topic: `sub,/clock,,` /// /// 4. Websocket server publishing data on the "/clock" topic: - /// `pub,/clock,ignition.msgs.Clock,` + /// `pub,/clock,gz.msgs.Clock,` /// /// # Example usage /// @@ -118,8 +118,8 @@ namespace ignition /// 1. Define a launch file by copying the following contents to a file /// called `websocket.ign`. /// - /// - /// + /// /// /// @@ -132,7 +132,7 @@ namespace ignition /// /// 3. Open the [index.html](https://github.com/ignitionrobotics/ign-launch/blob/ign-launch2/plugins/websocket_server/index.html) webpage. /// - class WebsocketServer : public ignition::launch::Plugin + class WebsocketServer : public gz::launch::Plugin { /// \brief Constructor public: WebsocketServer(); @@ -148,7 +148,7 @@ namespace ignition private: void OnWebsocketSubscribedMessage(const char *_data, const size_t _size, - const ignition::transport::MessageInfo &_info); + const gz::transport::MessageInfo &_info); /// \brief Callback that is triggered when a new connection is /// established. @@ -163,7 +163,7 @@ namespace ignition public: void OnRequestMessage(int _socketId, const std::string &_msg); - private: ignition::transport::Node node; + private: gz::transport::Node node; private: bool run = true; private: std::thread *thread = nullptr; @@ -261,6 +261,6 @@ namespace ignition } // Register the plugin -IGNITION_ADD_PLUGIN(ignition::launch::WebsocketServer, ignition::launch::Plugin) +IGNITION_ADD_PLUGIN(gz::launch::WebsocketServer, gz::launch::Plugin) #endif diff --git a/plugins/websocket_server/combined.proto b/plugins/websocket_server/combined.proto index a0d72f2d..d7249957 100644 --- a/plugins/websocket_server/combined.proto +++ b/plugins/websocket_server/combined.proto @@ -1,6 +1,6 @@ syntax = "proto3"; -package ignition.msgs; +package gz.msgs; message Time { int64 sec = 1; diff --git a/plugins/websocket_server/index-old.html b/plugins/websocket_server/index-old.html index cf238618..b1ee5ed3 100644 --- a/plugins/websocket_server/index-old.html +++ b/plugins/websocket_server/index-old.html @@ -9,7 +9,7 @@ var wsUri = "ws://localhost:9002"; var output; var proto = "syntax = \"proto3\";\ - package ignition.msgs;\ + package gz.msgs;\ message Time {\ int64 sec = 1;\ int32 nsec = 2;\ diff --git a/plugins/websocket_server/index.html b/plugins/websocket_server/index.html index 52e5fcf8..108fca73 100644 --- a/plugins/websocket_server/index.html +++ b/plugins/websocket_server/index.html @@ -43,7 +43,7 @@ var clockSub = new Topic({ ign: ign, name: '/clock', - messageType : 'ignition.msgs.Clock', + messageType : 'gz.msgs.Clock', callback: function(msg) { var output = document.getElementById('output'); output.innerHTML = 'Clock: ' + msg.sim.sec + '.' + msg.sim.nsec; @@ -54,7 +54,7 @@ var poseSub = new Topic({ ign: ign, name: '/world/shapes/dynamic_pose/info', - messageType : 'ignition.msgs.Pose_V', + messageType : 'gz.msgs.Pose_V', callback: function(msg) { for (var i = 0; i < msg.pose.length; ++i) { var entity = scene.getByName(msg.pose[i].name); diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index a168daf5..5293f542 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -1,13 +1,13 @@ # add_subdirectory(plugins) set (sources - ign.cc + gz.cc Manager.cc ) set (gtest_sources Manager_TEST.cc - ign_TEST.cc + gz_TEST.cc ) # Create the library target. @@ -35,7 +35,7 @@ ign_build_tests(TYPE UNIT SOURCES ${gtest_sources} ignition-common${IGN_COMMON_MAJOR_VER}::ignition-common${IGN_COMMON_MAJOR_VER} ) -if(TARGET UNIT_ign_TEST) +if(TARGET UNIT_gz_TEST) # Running `ign launch` on macOS has problems when run with /usr/bin/ruby # due to System Integrity Protection (SIP). Try to find ruby from # homebrew as a workaround. @@ -43,10 +43,10 @@ if(TARGET UNIT_ign_TEST) find_program(BREW_RUBY ruby HINTS /usr/local/opt/ruby/bin) endif() - target_compile_definitions(UNIT_ign_TEST PRIVATE + target_compile_definitions(UNIT_gz_TEST PRIVATE "BREW_RUBY=\"${BREW_RUBY} \"") - target_compile_definitions(UNIT_ign_TEST PRIVATE + target_compile_definitions(UNIT_gz_TEST PRIVATE "IGN_PATH=\"${HAVE_IGN_TOOLS}\"") endif() diff --git a/src/Manager.cc b/src/Manager.cc index dc554ff8..e7fdbcc8 100644 --- a/src/Manager.cc +++ b/src/Manager.cc @@ -50,7 +50,7 @@ #include "vendor/backward.hpp" -using namespace ignition::launch; +using namespace gz::launch; using namespace std::chrono_literals; /// \brief A class to encapsulate an executable (program) to run. @@ -95,7 +95,7 @@ class Executable }; /// \brief Private data variables for the Ignition class. -class ignition::launch::ManagerPrivate +class gz::launch::ManagerPrivate { /// \brief Constructor. public: ManagerPrivate(); @@ -233,7 +233,7 @@ Manager::Manager() this->dataPtr->myself = this->dataPtr.get(); std::string homePath; - ignition::common::env(IGN_HOMEDIR, homePath); + gz::common::env(IGN_HOMEDIR, homePath); // Make sure to initialize logging. ignLogInit(homePath + "/.ignition", "launch.log"); @@ -689,7 +689,7 @@ void ManagerPrivate::ParseExecutables(const tinyxml2::XMLElement *_elem) else { std::vector parts = - ignition::common::split(cmdElem->GetText(), " "); + gz::common::split(cmdElem->GetText(), " "); std::move(parts.begin(), parts.end(), std::back_inserter(cmdParts)); } @@ -699,7 +699,7 @@ void ManagerPrivate::ParseExecutables(const tinyxml2::XMLElement *_elem) "auto_restart"); if (restartElem && restartElem->GetText()) { - std::string txt = ignition::common::lowercase(restartElem->GetText()); + std::string txt = gz::common::lowercase(restartElem->GetText()); autoRestart = txt == "true" || txt == "1" || txt == "t"; } @@ -739,7 +739,7 @@ std::list ManagerPrivate::ParseEnvs( // Expand env var contents, such as $LD_LIBRARY_PATH if (!value.empty() && value.at(0) == '$') { - ignition::common::env(value.substr(1), value); + gz::common::env(value.substr(1), value); } result.push_back(name + "=" + value); @@ -775,29 +775,29 @@ void ManagerPrivate::LoadPlugin(const tinyxml2::XMLElement *_elem) return; } - if (name == "ignition::launch::GazeboServer") + if (name == "gz::launch::GazeboServer") { setenv("RMT_PORT", "1500", 1); } - else if (name == "ignition::launch::GazeboGui") + else if (name == "gz::launch::GazeboGui") { setenv("RMT_PORT", "1501", 1); } - ignition::common::SystemPaths systemPaths; + gz::common::SystemPaths systemPaths; systemPaths.SetPluginPathEnv("IGN_LAUNCH_PLUGIN_PATH"); systemPaths.AddPluginPaths(IGNITION_LAUNCH_PLUGIN_INSTALL_PATH); // Add LD_LIBRARY_PATH #ifdef __linux__ std::string libPath; - ignition::common::env("LD_LIBRARY_PATH", libPath); + gz::common::env("LD_LIBRARY_PATH", libPath); systemPaths.AddPluginPaths(libPath); #endif // Add in the gazebo plugin path for convenience std::string homePath; - ignition::common::env(IGN_HOMEDIR, homePath); + gz::common::env(IGN_HOMEDIR, homePath); systemPaths.AddPluginPaths(homePath + "/.ignition/gazebo/plugins"); std::string pathToLib; @@ -823,7 +823,7 @@ void ManagerPrivate::LoadPlugin(const tinyxml2::XMLElement *_elem) } std::unordered_set validPlugins = - loader.PluginsImplementing(); + loader.PluginsImplementing(); if (validPlugins.count(name) == 0) { std::string availablePlugins; diff --git a/src/Manager.hh b/src/Manager.hh index 37c3ee3b..7f2aceaf 100644 --- a/src/Manager.hh +++ b/src/Manager.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_LAUNCH_MANAGER_HH_ -#define IGNITION_LAUNCH_MANAGER_HH_ +#ifndef GZ_LAUNCH_MANAGER_HH_ +#define GZ_LAUNCH_MANAGER_HH_ #include #include #include -namespace ignition +namespace gz { namespace launch { diff --git a/src/Manager_TEST.cc b/src/Manager_TEST.cc index abc9ff05..22b6ac8d 100644 --- a/src/Manager_TEST.cc +++ b/src/Manager_TEST.cc @@ -31,9 +31,9 @@ static constexpr char kTestScriptPath[] = "/tmp/ign-launch.sh"; bool RemoveTestScript() { // Remove the file if it already exists - if (ignition::common::isFile(kTestScriptPath)) + if (gz::common::isFile(kTestScriptPath)) { - if (!ignition::common::removeFile(kTestScriptPath)) + if (!gz::common::removeFile(kTestScriptPath)) { return false; } @@ -60,7 +60,7 @@ touch $TEST_VAR ///////////////////////////////////////////////// TEST(Ignition_TEST, RunEmptyConfig) { - ignition::launch::Manager mgr; + gz::launch::Manager mgr; // Expect false because no config file was set. EXPECT_FALSE(mgr.RunConfig("")); @@ -74,7 +74,7 @@ TEST(Ignition_TEST, MissingIgnition) " ign-gazebo-server" ""; - ignition::launch::Manager mgr; + gz::launch::Manager mgr; // Stop the manager after a short pause. EXPECT_FALSE(mgr.RunConfig(config)); @@ -88,7 +88,7 @@ TEST(Ignition_TEST, RunBadXml) " executable>"; - ignition::launch::Manager mgr; + gz::launch::Manager mgr; // Stop the manager after a short pause. EXPECT_FALSE(mgr.RunConfig(config)); @@ -112,7 +112,7 @@ TEST(Ignition_TEST, RunLs) " " ""; - ignition::launch::Manager mgr; + gz::launch::Manager mgr; // We should be able to run the ls command. This does not check the // output. @@ -126,9 +126,9 @@ TEST(Ignition_TEST, IGN_UTILS_TEST_DISABLED_ON_WIN32(RunEnvPre)) // Test that environment is applied regardless of order std::string testPath = "/tmp/ign-launch-env-test-pre"; - if (ignition::common::isFile(testPath)) + if (gz::common::isFile(testPath)) { - ASSERT_TRUE(ignition::common::removeFile(testPath)); + ASSERT_TRUE(gz::common::removeFile(testPath)); } ASSERT_TRUE(WriteTestScript()); @@ -145,11 +145,11 @@ TEST(Ignition_TEST, IGN_UTILS_TEST_DISABLED_ON_WIN32(RunEnvPre)) )"; - ignition::launch::Manager mgr; + gz::launch::Manager mgr; EXPECT_TRUE(mgr.RunConfig(config)); - EXPECT_TRUE(ignition::common::isFile(testPath)); - EXPECT_TRUE(ignition::common::removeFile(testPath)); + EXPECT_TRUE(gz::common::isFile(testPath)); + EXPECT_TRUE(gz::common::removeFile(testPath)); EXPECT_TRUE(RemoveTestScript()); } @@ -159,9 +159,9 @@ TEST(Ignition_TEST, IGN_UTILS_TEST_DISABLED_ON_WIN32(RunEnvPost)) // Test that environment is applied regardless of order std::string testPath = "/tmp/ign-launch-env-test-post"; - if (ignition::common::isFile(testPath)) + if (gz::common::isFile(testPath)) { - ASSERT_TRUE(ignition::common::removeFile(testPath)); + ASSERT_TRUE(gz::common::removeFile(testPath)); } ASSERT_TRUE(WriteTestScript()); @@ -178,18 +178,18 @@ TEST(Ignition_TEST, IGN_UTILS_TEST_DISABLED_ON_WIN32(RunEnvPost)) )"; - ignition::launch::Manager mgr; + gz::launch::Manager mgr; EXPECT_TRUE(mgr.RunConfig(config)); - EXPECT_TRUE(ignition::common::isFile(testPath)); - EXPECT_TRUE(ignition::common::removeFile(testPath)); + EXPECT_TRUE(gz::common::isFile(testPath)); + EXPECT_TRUE(gz::common::removeFile(testPath)); EXPECT_TRUE(RemoveTestScript()); } ///////////////////////////////////////////////// int main(int argc, char **argv) { - ignition::common::Console::SetVerbosity(4); + gz::common::Console::SetVerbosity(4); ::testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/src/gz.cc b/src/gz.cc index dfa84f80..5fe17c55 100644 --- a/src/gz.cc +++ b/src/gz.cc @@ -37,12 +37,12 @@ extern "C" IGNITION_LAUNCH_VISIBLE const char *configPath() extern "C" IGNITION_LAUNCH_VISIBLE void cmdVerbosity( const char *_verbosity) { - ignition::common::Console::SetVerbosity(std::atoi(_verbosity)); + gz::common::Console::SetVerbosity(std::atoi(_verbosity)); } ////////////////////////////////////////////////// extern "C" IGNITION_LAUNCH_VISIBLE int run(const char *_config) { - ignition::launch::Manager mgr; + gz::launch::Manager mgr; return mgr.RunConfig(_config); } diff --git a/src/gz.hh b/src/gz.hh index e35d923e..63094821 100644 --- a/src/gz.hh +++ b/src/gz.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_LAUNCH_IGN_HH_ -#define IGNITION_LAUNCH_IGN_HH_ +#ifndef GZ_LAUNCH_IGN_HH_ +#define GZ_LAUNCH_IGN_HH_ #include "ignition/launch/Export.hh" diff --git a/src/gz_TEST.cc b/src/gz_TEST.cc index a9af15e9..96653cb9 100644 --- a/src/gz_TEST.cc +++ b/src/gz_TEST.cc @@ -84,7 +84,7 @@ TEST(CmdLine, HelpVsCompletionFlags) std::string helpOutput = customExecStr(kIgnCommand + "--help"); // Call the output function in the bash completion script - std::string scriptPath = ignition::common::joinPaths( + std::string scriptPath = gz::common::joinPaths( std::string(PROJECT_SOURCE_PATH), "src", "launch.bash_completion.sh"); diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 942f5195..0ed93633 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -5,6 +5,7 @@ include_directories ( ${PROJECT_BINARY_DIR}/include/ ) +configure_file (test_config.hh.in ${PROJECT_BINARY_DIR}/include/ignition/launch/test_config.hh) configure_file (test_config.hh.in ${PROJECT_BINARY_DIR}/include/ignition/launch/test_config.hh) # Build gtest diff --git a/test/integration/deprecated_TEST.cc b/test/integration/deprecated_TEST.cc new file mode 100644 index 00000000..0bb00342 --- /dev/null +++ b/test/integration/deprecated_TEST.cc @@ -0,0 +1,26 @@ +/* + * Copyright (C) 2022 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. + * +*/ + +#include +#include + +///////////////////////////////////////////////// +// Make sure the ignition namespace still works +TEST(Deprecated, IgnitionNamespace) +{ + ignition::launch::Plugin plugin; +} diff --git a/test/integration/faulty_plugins.cc b/test/integration/faulty_plugins.cc index 4cdf51e6..5e5d2a0f 100644 --- a/test/integration/faulty_plugins.cc +++ b/test/integration/faulty_plugins.cc @@ -32,7 +32,7 @@ std::string getConfig(const std::string &_pluginName) bool runConfig(const std::string &_config) { - ignition::launch::Manager mgr; + gz::launch::Manager mgr; return mgr.RunConfig(_config); } diff --git a/test/integration/plugins/bad_plugins.cc b/test/integration/plugins/bad_plugins.cc index ce17e847..6c5d57a3 100644 --- a/test/integration/plugins/bad_plugins.cc +++ b/test/integration/plugins/bad_plugins.cc @@ -20,7 +20,7 @@ #include -SegfaultOnLoad::SegfaultOnLoad(): ignition::launch::Plugin() {} +SegfaultOnLoad::SegfaultOnLoad(): gz::launch::Plugin() {} bool SegfaultOnLoad::Load(const tinyxml2::XMLElement * /*_elem*/) { @@ -31,4 +31,4 @@ bool SegfaultOnLoad::Load(const tinyxml2::XMLElement * /*_elem*/) return true; } -IGNITION_ADD_PLUGIN(SegfaultOnLoad, ignition::launch::Plugin) +IGNITION_ADD_PLUGIN(SegfaultOnLoad, gz::launch::Plugin) diff --git a/test/integration/plugins/bad_plugins.hh b/test/integration/plugins/bad_plugins.hh index 214e95b1..4ed74213 100644 --- a/test/integration/plugins/bad_plugins.hh +++ b/test/integration/plugins/bad_plugins.hh @@ -18,7 +18,7 @@ #include #include "ignition/launch/Plugin.hh" -class SegfaultOnLoad : public ignition::launch::Plugin +class SegfaultOnLoad : public gz::launch::Plugin { public: SegfaultOnLoad(); public: virtual bool Load( diff --git a/test/test_config.hh.in b/test/test_config.hh.in index 2a47b41c..9d8e7bbd 100644 --- a/test/test_config.hh.in +++ b/test/test_config.hh.in @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_LAUNCH_TEST_CONFIG_HH_ -#define IGNITION_LAUNCH_TEST_CONFIG_HH_ +#ifndef GZ_LAUNCH_TEST_CONFIG_HH_ +#define GZ_LAUNCH_TEST_CONFIG_HH_ #define PROJECT_SOURCE_PATH "${PROJECT_SOURCE_DIR}" #define PROJECT_BINARY_PATH "${CMAKE_BINARY_DIR}"