diff --git a/MIGRATION.md b/MIGRATION.md index 410860d1..568dcb9a 100644 --- a/MIGRATION.md +++ b/MIGRATION.md @@ -16,13 +16,13 @@ target_link_libraries(my_target PUBLIC ignition-plugin1::core) However, if your code wants to be able to load plugins, it should link to the `loader` component. In most cases, it should probably link privately, unless you -need the `gz::plugin::Loader` class to be part of your library's API: +need the `ignition::plugin::Loader` class to be part of your library's API: ``` target_link_libraries(my_target PRIVATE ignition-plugin1::loader) ``` -If `gz::plugin::PluginPtr` objects are part of your library's API, then +If `ignition::plugin::PluginPtr` objects are part of your library's API, then you may want `loader` to be private while `core` is public: ``` @@ -77,15 +77,15 @@ you choose exactly one. # Loading a library -The `gz::common::SystemPaths` class was not ported into `ign-plugin` +The `ignition::common::SystemPaths` class was not ported into `ign-plugin` because it is more related to filesystem utilities than to plugins. If you are -currently using `gz::common::SystemPaths` to help with loading plugins, +currently using `ignition::common::SystemPaths` to help with loading plugins, then you should continue to use it. It does not have a replacement in `ign-plugin`. Here is a list of things that you *should* replace: * `#include ` should be replaced with `#include ` -* `gz::common::PluginLoader` should be replaced with `gz::plugin::Loader` +* `ignition::common::PluginLoader` should be replaced with `ignition::plugin::Loader` * When calling `Loader::Instantiate("....")` do **NOT** prefix the class name with `::`. E.g. `"::some_namespace::MyClass"` should now be `"some_namespace::MyClass"`. diff --git a/core/include/gz/plugin/EnablePluginFromThis.hh b/core/include/gz/plugin/EnablePluginFromThis.hh index 0f93736a..6deaf4d9 100644 --- a/core/include/gz/plugin/EnablePluginFromThis.hh +++ b/core/include/gz/plugin/EnablePluginFromThis.hh @@ -22,7 +22,7 @@ #include -namespace gz +namespace ignition { namespace plugin { diff --git a/core/include/gz/plugin/Factory.hh b/core/include/gz/plugin/Factory.hh index 5da2378e..0b533c78 100644 --- a/core/include/gz/plugin/Factory.hh +++ b/core/include/gz/plugin/Factory.hh @@ -25,7 +25,7 @@ #include -namespace gz +namespace ignition { namespace plugin { diff --git a/core/include/gz/plugin/Info.hh b/core/include/gz/plugin/Info.hh index 5717c4e6..78c28b50 100644 --- a/core/include/gz/plugin/Info.hh +++ b/core/include/gz/plugin/Info.hh @@ -29,7 +29,7 @@ #include -namespace gz +namespace ignition { namespace plugin { diff --git a/core/include/gz/plugin/Plugin.hh b/core/include/gz/plugin/Plugin.hh index 64aa8928..cae84e90 100644 --- a/core/include/gz/plugin/Plugin.hh +++ b/core/include/gz/plugin/Plugin.hh @@ -28,7 +28,7 @@ #include #include -namespace gz +namespace ignition { namespace plugin { diff --git a/core/include/gz/plugin/PluginPtr.hh b/core/include/gz/plugin/PluginPtr.hh index 605a5819..51d547c6 100644 --- a/core/include/gz/plugin/PluginPtr.hh +++ b/core/include/gz/plugin/PluginPtr.hh @@ -25,7 +25,7 @@ #include -namespace gz +namespace ignition { namespace plugin { @@ -33,7 +33,7 @@ namespace gz namespace detail { template class ComposePlugin; } /// \brief This class manages the lifecycle of a plugin instance. It can - /// receive a plugin instance from the gz::plugin::Loader class + /// receive a plugin instance from the ignition::plugin::Loader class /// or by copy-construction or assignment from another PluginPtr instance. /// /// This class behaves similarly to a std::shared_ptr where multiple diff --git a/core/include/gz/plugin/SpecializedPlugin.hh b/core/include/gz/plugin/SpecializedPlugin.hh index b13669e0..71fbcced 100644 --- a/core/include/gz/plugin/SpecializedPlugin.hh +++ b/core/include/gz/plugin/SpecializedPlugin.hh @@ -22,7 +22,7 @@ #include #include "gz/plugin/Plugin.hh" -namespace gz +namespace ignition { namespace plugin { diff --git a/core/include/gz/plugin/SpecializedPluginPtr.hh b/core/include/gz/plugin/SpecializedPluginPtr.hh index a92a1769..6e9ba354 100644 --- a/core/include/gz/plugin/SpecializedPluginPtr.hh +++ b/core/include/gz/plugin/SpecializedPluginPtr.hh @@ -22,7 +22,7 @@ #include "gz/plugin/PluginPtr.hh" #include "gz/plugin/SpecializedPlugin.hh" -namespace gz +namespace ignition { namespace plugin { diff --git a/core/include/gz/plugin/WeakPluginPtr.hh b/core/include/gz/plugin/WeakPluginPtr.hh index b7151f2b..5968d71b 100644 --- a/core/include/gz/plugin/WeakPluginPtr.hh +++ b/core/include/gz/plugin/WeakPluginPtr.hh @@ -22,7 +22,7 @@ #include -namespace gz +namespace ignition { namespace plugin { diff --git a/core/include/gz/plugin/config.hh.in b/core/include/gz/plugin/config.hh.in index e41175a0..85fc4a9b 100644 --- a/core/include/gz/plugin/config.hh.in +++ b/core/include/gz/plugin/config.hh.in @@ -13,4 +13,13 @@ #define IGNITION_PLUGIN_VERSION_HEADER "Ignition Plugin, version ${PROJECT_VERSION_FULL}\nCopyright (C) 2017 Open Source Robotics Foundation.\nReleased under the Apache 2.0 License.\n\n" +namespace ignition +{ +} + +namespace gz +{ + using namespace ignition; +} + #endif diff --git a/core/include/gz/plugin/detail/Factory.hh b/core/include/gz/plugin/detail/Factory.hh index 66581885..abfb9bc9 100644 --- a/core/include/gz/plugin/detail/Factory.hh +++ b/core/include/gz/plugin/detail/Factory.hh @@ -25,7 +25,7 @@ #include -namespace gz +namespace ignition { namespace plugin { @@ -50,8 +50,8 @@ namespace gz public: virtual ~FactoryCounter(); // friendship declaration - template friend class gz::plugin::Factory; - template friend class gz::plugin::ProductDeleter; + template friend class ignition::plugin::Factory; + template friend class ignition::plugin::ProductDeleter; }; } diff --git a/core/include/gz/plugin/detail/Plugin.hh b/core/include/gz/plugin/detail/Plugin.hh index 668ef072..cc8528ff 100644 --- a/core/include/gz/plugin/detail/Plugin.hh +++ b/core/include/gz/plugin/detail/Plugin.hh @@ -23,7 +23,7 @@ #include #include -namespace gz +namespace ignition { namespace plugin { diff --git a/core/include/gz/plugin/detail/PluginPtr.hh b/core/include/gz/plugin/detail/PluginPtr.hh index edf984da..2372928d 100644 --- a/core/include/gz/plugin/detail/PluginPtr.hh +++ b/core/include/gz/plugin/detail/PluginPtr.hh @@ -24,7 +24,7 @@ #include #include -namespace gz +namespace ignition { namespace plugin { @@ -187,10 +187,10 @@ namespace std /// so that it can easily be used in STL objects like std::unordered_set and /// std::unordered_map template - struct hash> + struct hash> { size_t operator()( - const gz::plugin::TemplatePluginPtr &ptr) const + const ignition::plugin::TemplatePluginPtr &ptr) const { return ptr.Hash(); } diff --git a/core/include/gz/plugin/detail/SpecializedPlugin.hh b/core/include/gz/plugin/detail/SpecializedPlugin.hh index 50f17f8b..78427252 100644 --- a/core/include/gz/plugin/detail/SpecializedPlugin.hh +++ b/core/include/gz/plugin/detail/SpecializedPlugin.hh @@ -30,7 +30,7 @@ bool usedSpecializedInterfaceAccess; #endif -namespace gz +namespace ignition { namespace plugin { @@ -250,7 +250,7 @@ namespace gz bool, HasInterface, () const, const Specializer, ()) // Declare friendship - template friend class gz::plugin::SpecializedPlugin; + template friend class ignition::plugin::SpecializedPlugin; template friend class SelectSpecializers; template friend class ComposePlugin; @@ -271,7 +271,7 @@ namespace gz using Specialization = ComposePlugin; // Declare friendship - template friend class gz::plugin::SpecializedPlugin; + template friend class ignition::plugin::SpecializedPlugin; template friend class SelectSpecializers; template friend class ComposePlugin; diff --git a/core/include/gz/plugin/detail/utility.hh b/core/include/gz/plugin/detail/utility.hh index aff597d8..af24e17d 100644 --- a/core/include/gz/plugin/detail/utility.hh +++ b/core/include/gz/plugin/detail/utility.hh @@ -22,7 +22,7 @@ #include -namespace gz +namespace ignition { namespace plugin { diff --git a/core/include/gz/plugin/utility.hh b/core/include/gz/plugin/utility.hh index 275711d7..867f9e1f 100644 --- a/core/include/gz/plugin/utility.hh +++ b/core/include/gz/plugin/utility.hh @@ -24,7 +24,7 @@ #include #include -namespace gz +namespace ignition { namespace plugin { diff --git a/core/include/ignition/plugin/config.hh b/core/include/ignition/plugin/config.hh index c145d073..232da299 100644 --- a/core/include/ignition/plugin/config.hh +++ b/core/include/ignition/plugin/config.hh @@ -30,14 +30,4 @@ // #define IGNITION_PLUGIN_VERSION_HEADER GZ_PLUGIN_VERSION_HEADER -namespace gz -{ -} - -namespace ignition -{ - using namespace gz; -} - - #endif diff --git a/core/src/EnablePluginFromThis.cc b/core/src/EnablePluginFromThis.cc index 07065eb4..9b5cf22f 100644 --- a/core/src/EnablePluginFromThis.cc +++ b/core/src/EnablePluginFromThis.cc @@ -18,7 +18,7 @@ #include #include -namespace gz +namespace ignition { namespace plugin { diff --git a/core/src/Factory.cc b/core/src/Factory.cc index b06354ad..b31f57cd 100644 --- a/core/src/Factory.cc +++ b/core/src/Factory.cc @@ -51,7 +51,7 @@ namespace static LostProductManager lostProductManager; } // namespace -namespace gz +namespace ignition { namespace plugin { diff --git a/core/src/Factory_TEST.cc b/core/src/Factory_TEST.cc index a6b24b08..6dcc149a 100644 --- a/core/src/Factory_TEST.cc +++ b/core/src/Factory_TEST.cc @@ -51,13 +51,13 @@ struct SomeDerived : public SomeBase } }; -using NoArgFactory = gz::plugin::Factory; +using NoArgFactory = ignition::plugin::Factory; using NoArgProducer = NoArgFactory::Producing; -using DoubleIntFactory = gz::plugin::Factory; +using DoubleIntFactory = ignition::plugin::Factory; using DoubleIntProducer = DoubleIntFactory::Producing; -using VectorFactory = gz::plugin::Factory< +using VectorFactory = ignition::plugin::Factory< SomeBase, const std::vector&>; using VectorProducer = VectorFactory::Producing; diff --git a/core/src/Info.cc b/core/src/Info.cc index 7f7fdca7..3c914bcd 100644 --- a/core/src/Info.cc +++ b/core/src/Info.cc @@ -17,7 +17,7 @@ #include -namespace gz +namespace ignition { namespace plugin { diff --git a/core/src/Info_TEST.cc b/core/src/Info_TEST.cc index 4728b592..27a729cc 100644 --- a/core/src/Info_TEST.cc +++ b/core/src/Info_TEST.cc @@ -29,7 +29,7 @@ struct SomePlugin : public SomeInterface TEST(Info, Clear) { - gz::plugin::Info info; + ignition::plugin::Info info; info.name = typeid(SomePlugin).name(); info.factory = [=]() diff --git a/core/src/Plugin.cc b/core/src/Plugin.cc index 06273b80..d57c9b44 100644 --- a/core/src/Plugin.cc +++ b/core/src/Plugin.cc @@ -22,7 +22,7 @@ #include "gz/plugin/Plugin.hh" #include "gz/plugin/Info.hh" -namespace gz +namespace ignition { namespace plugin { diff --git a/core/src/WeakPluginPtr.cc b/core/src/WeakPluginPtr.cc index ec1ae9b6..9d2e5647 100644 --- a/core/src/WeakPluginPtr.cc +++ b/core/src/WeakPluginPtr.cc @@ -17,7 +17,7 @@ #include -namespace gz +namespace ignition { namespace plugin { diff --git a/core/src/utility.cc b/core/src/utility.cc index 970d2f1a..9cc4c731 100644 --- a/core/src/utility.cc +++ b/core/src/utility.cc @@ -27,7 +27,7 @@ #include -namespace gz +namespace ignition { namespace plugin { diff --git a/core/src/utility_TEST.cc b/core/src/utility_TEST.cc index 29c2fc3e..62849a6b 100644 --- a/core/src/utility_TEST.cc +++ b/core/src/utility_TEST.cc @@ -19,7 +19,7 @@ #include -using namespace gz::plugin; +using namespace ignition::plugin; struct SomeType { }; diff --git a/examples/integrators.cc b/examples/integrators.cc index 556d7225..5be94e65 100644 --- a/examples/integrators.cc +++ b/examples/integrators.cc @@ -32,9 +32,9 @@ namespace bpo = boost::program_options; #endif -using NumericalIntegrator = gz::plugin::examples::NumericalIntegrator; -using ODESystem = gz::plugin::examples::ODESystem; -using ODESystemFactory = gz::plugin::examples::ODESystemFactory; +using NumericalIntegrator = ignition::plugin::examples::NumericalIntegrator; +using ODESystem = ignition::plugin::examples::ODESystem; +using ODESystemFactory = ignition::plugin::examples::ODESystemFactory; // The macro that this uses is provided as a compile definition in the // examples/CMakeLists.txt file. @@ -60,7 +60,7 @@ struct TestResult struct PluginHolder { std::string name; - gz::plugin::PluginPtr plugin; + ignition::plugin::PluginPtr plugin; }; /// \brief Compute the component-wise percent error of the estimate produced by @@ -88,7 +88,7 @@ TestResult TestIntegrator( const double _timeStep, const unsigned int _numSteps) { - const gz::plugin::PluginPtr &plugin = _pluginHolder.plugin; + const ignition::plugin::PluginPtr &plugin = _pluginHolder.plugin; NumericalIntegrator* integrator = plugin->QueryInterface(); @@ -210,7 +210,7 @@ void TestPlugins( /// \brief Load all the plugins that implement _interface. std::vector LoadPlugins( - const gz::plugin::Loader &_loader, + const ignition::plugin::Loader &_loader, const std::string &_interface) { // Fill in the holders object with each plugin. @@ -220,7 +220,7 @@ std::vector LoadPlugins( for (const std::string &name : pluginNames) { - gz::plugin::PluginPtr plugin = _loader.Instantiate(name); + ignition::plugin::PluginPtr plugin = _loader.Instantiate(name); if (!plugin) { std::cout << "Failed to load [" << name << "] as a class" @@ -236,25 +236,25 @@ std::vector LoadPlugins( /// \brief Load all plugins that implement the NumericalIntegrator interface. std::vector LoadIntegratorPlugins( - const gz::plugin::Loader &_loader) + const ignition::plugin::Loader &_loader) { return LoadPlugins( - _loader, "gz::plugin::examples::NumericalIntegrator"); + _loader, "ignition::plugin::examples::NumericalIntegrator"); } /// \brief Load all plugins that implement the ODESystemFactory interface std::vector LoadSystemFactoryPlugins( - const gz::plugin::Loader &_loader) + const ignition::plugin::Loader &_loader) { return LoadPlugins( - _loader, "gz::plugin::examples::ODESystemFactory"); + _loader, "ignition::plugin::examples::ODESystemFactory"); } /// \brief Prime the plugin loader with the paths and library names that it /// should try to get plugins from. void PrimeTheLoader( - gz::common::SystemPaths &_paths, /* TODO: This should be const */ - gz::plugin::Loader &_loader, + ignition::common::SystemPaths &_paths, /* TODO: This should be const */ + ignition::plugin::Loader &_loader, const std::set &_pluginNames) { for (const std::string &name : _pluginNames) @@ -284,10 +284,10 @@ void PrimeTheLoader( int main(int argc, char *argv[]) { // Create an object that can search the system paths for the plugin libraries. - gz::common::SystemPaths paths; + ignition::common::SystemPaths paths; // Create a plugin loader - gz::plugin::Loader loader; + ignition::plugin::Loader loader; // Add the build directory path for the plugin libraries so the SystemPaths // object will know to search through it. diff --git a/examples/plugins/BoxEnvironment.cc b/examples/plugins/BoxEnvironment.cc index a1d2dbba..07fa4051 100644 --- a/examples/plugins/BoxEnvironment.cc +++ b/examples/plugins/BoxEnvironment.cc @@ -20,14 +20,14 @@ namespace BoxEnvironment { /// \brief A plugin that creates a box environment -class Plugin : public virtual gz::plugin::examples::Environment +class Plugin : public virtual ignition::plugin::examples::Environment { - public: gz::plugin::examples::Layout GenerateLayout() const override + public: ignition::plugin::examples::Layout GenerateLayout() const override { - gz::plugin::examples::Layout layout; + ignition::plugin::examples::Layout layout; const double L = 5.0; - using gz::math::Vector2d; + using ignition::math::Vector2d; layout.push_back(std::make_pair(Vector2d(L, L), Vector2d(L, -L))); layout.push_back(std::make_pair(Vector2d(L, L), Vector2d(-L, L))); @@ -42,4 +42,4 @@ class Plugin : public virtual gz::plugin::examples::Environment IGNITION_ADD_PLUGIN( BoxEnvironment::Plugin, - gz::plugin::examples::Environment) + ignition::plugin::examples::Environment) diff --git a/examples/plugins/CautiousBot.cc b/examples/plugins/CautiousBot.cc index a5b80529..ce75bbab 100644 --- a/examples/plugins/CautiousBot.cc +++ b/examples/plugins/CautiousBot.cc @@ -17,7 +17,7 @@ #include "robot.hh" -using namespace gz::plugin::examples; +using namespace ignition::plugin::examples; namespace CautiousBotLibrary { @@ -32,14 +32,14 @@ class CautiousBot } // Documentation inherited - public: gz::math::Vector3d Velocity() const override + public: ignition::math::Vector3d Velocity() const override { const double MaxDist = 10.0; // Try to stay 0.1 meters away from any obstacle const double d = (std::min(distance, MaxDist) - 0.1); - return gz::math::Vector3d(0.1*d, 0.0, 0.0); + return ignition::math::Vector3d(0.1*d, 0.0, 0.0); } // Documentation inherited diff --git a/examples/plugins/CrashBot.cc b/examples/plugins/CrashBot.cc index e0664d4b..172d3f36 100644 --- a/examples/plugins/CrashBot.cc +++ b/examples/plugins/CrashBot.cc @@ -17,7 +17,7 @@ #include "robot.hh" -using namespace gz::plugin::examples; +using namespace ignition::plugin::examples; namespace CrashBotLib { @@ -33,15 +33,15 @@ class CrashBot } // Documentation inherited - public: gz::math::Vector3d Velocity() const override + public: ignition::math::Vector3d Velocity() const override { // If the proximity sensor detects a wall, drive straight forward, // aggressively into the wall if (detectedWall) - return gz::math::Vector3d(1.0, 0.0, 0.0); + return ignition::math::Vector3d(1.0, 0.0, 0.0); // If we have not detected a wall, drive in a spiral, searching for a wall - return gz::math::Vector3d(0.5, 0.0, 20.0*IGN_PI/180.0); + return ignition::math::Vector3d(0.5, 0.0, 20.0*IGN_PI/180.0); } // Documentation inherited diff --git a/examples/plugins/ExponentialODE.cc b/examples/plugins/ExponentialODE.cc index c9eddcab..a6b8e7f0 100644 --- a/examples/plugins/ExponentialODE.cc +++ b/examples/plugins/ExponentialODE.cc @@ -21,7 +21,7 @@ #include "integrators.hh" -namespace gz { +namespace ignition { namespace plugin { namespace examples { namespace ExponentialODE { diff --git a/examples/plugins/ForwardEuler.cc b/examples/plugins/ForwardEuler.cc index dc21ae6e..636d97b6 100644 --- a/examples/plugins/ForwardEuler.cc +++ b/examples/plugins/ForwardEuler.cc @@ -21,7 +21,7 @@ #include "integrators.hh" -namespace gz{ +namespace ignition{ namespace plugin { namespace examples { namespace ForwardEuler { @@ -53,7 +53,7 @@ std::vector times(const double s, } /// \brief Forward Euler implementation of a numerical integrator -class Integrator : public gz::plugin::examples::NumericalIntegrator +class Integrator : public ignition::plugin::examples::NumericalIntegrator { // Documentation inherited public: void SetFunction( diff --git a/examples/plugins/PolynomialODE.cc b/examples/plugins/PolynomialODE.cc index d440d4cb..d91a45de 100644 --- a/examples/plugins/PolynomialODE.cc +++ b/examples/plugins/PolynomialODE.cc @@ -21,7 +21,7 @@ #include "integrators.hh" -namespace gz { +namespace ignition { namespace plugin { namespace examples { namespace PolynomialODE { @@ -204,10 +204,10 @@ class CubicFactory : public ODESystemFactory // Register multiple plugins for this library IGNITION_ADD_PLUGIN( - gz::plugin::examples::PolynomialODE::ParabolicFactory, - gz::plugin::examples::ODESystemFactory) + ignition::plugin::examples::PolynomialODE::ParabolicFactory, + ignition::plugin::examples::ODESystemFactory) IGNITION_ADD_PLUGIN( - gz::plugin::examples::PolynomialODE::CubicFactory, - gz::plugin::examples::ODESystemFactory) + ignition::plugin::examples::PolynomialODE::CubicFactory, + ignition::plugin::examples::ODESystemFactory) diff --git a/examples/plugins/RungeKutta4.cc b/examples/plugins/RungeKutta4.cc index 4db48a98..dbfa9e3f 100644 --- a/examples/plugins/RungeKutta4.cc +++ b/examples/plugins/RungeKutta4.cc @@ -21,7 +21,7 @@ #include "integrators.hh" -namespace gz{ +namespace ignition{ namespace plugin { namespace examples { namespace RungeKutta4 { @@ -53,7 +53,7 @@ std::vector times(const double s, } /// \brief RK4 implementation of a numerical integrator -class Integrator : public gz::plugin::examples::NumericalIntegrator +class Integrator : public ignition::plugin::examples::NumericalIntegrator { // Documentation inherited public: void SetFunction( diff --git a/examples/plugins/integrators.hh b/examples/plugins/integrators.hh index 74113af5..b83c2a59 100644 --- a/examples/plugins/integrators.hh +++ b/examples/plugins/integrators.hh @@ -21,7 +21,7 @@ #include #include -namespace gz +namespace ignition { namespace plugin { diff --git a/examples/plugins/robot.hh b/examples/plugins/robot.hh index deb0f9c6..f50ce215 100644 --- a/examples/plugins/robot.hh +++ b/examples/plugins/robot.hh @@ -25,7 +25,7 @@ #include -namespace gz +namespace ignition { namespace plugin { @@ -45,7 +45,7 @@ namespace gz /// \return The first two components are x/y velocity (m/s). The third /// component is the yaw velocity (rad/s about the z-axis). The x/y /// coordinates are always relative to the robot's frame. - public: virtual gz::math::Vector3d Velocity() const = 0; + public: virtual ignition::math::Vector3d Velocity() const = 0; /// \brief Virtual destructor public: virtual ~Drive() = default; @@ -78,7 +78,7 @@ namespace gz /// \brief Get a GPS reading. /// \param[in] _location The world-frame x/y location of the robot. public: virtual void ReadGPS( - const gz::math::Vector2d &_location) = 0; + const ignition::math::Vector2d &_location) = 0; /// \brief Virtual destructor public: virtual ~GPSSensor() = default; @@ -99,7 +99,7 @@ namespace gz ///////////////////////////////////////////////// /// \brief A pair of Vector2d points defines a wall. using Wall = - std::pair; + std::pair; ///////////////////////////////////////////////// /// \brief The layout of an environment is defined by a set of walls. diff --git a/examples/robot.cc b/examples/robot.cc index 59f7e3fb..7cd30dba 100644 --- a/examples/robot.cc +++ b/examples/robot.cc @@ -37,24 +37,24 @@ namespace bpo = boost::program_options; const std::string PluginLibDir = IGN_PLUGIN_EXAMPLES_LIBDIR; ///////////////////////////////////////////////// -using namespace gz::plugin::examples; +using namespace ignition::plugin::examples; ///////////////////////////////////////////////// -using RobotPluginPtr = gz::plugin::SpecializedPluginPtr< +using RobotPluginPtr = ignition::plugin::SpecializedPluginPtr< Drive, ProximitySensor, GPSSensor, Compass, MapDatabase>; ///////////////////////////////////////////////// using EnvironmentPluginPtr = - gz::plugin::SpecializedPluginPtr; + ignition::plugin::SpecializedPluginPtr; -using PointPair = std::pair; +using PointPair = std::pair; ///////////////////////////////////////////////// -using IntersectionResult = std::pair; +using IntersectionResult = std::pair; ///////////////////////////////////////////////// const IntersectionResult NoIntersection = - std::make_pair(false, gz::math::Vector2d()); + std::make_pair(false, ignition::math::Vector2d()); ///////////////////////////////////////////////// IntersectionResult CheckIntersection( @@ -93,13 +93,13 @@ IntersectionResult CheckIntersection( return NoIntersection; } - return std::make_pair(true, gz::math::Vector2d(x,y)); + return std::make_pair(true, ignition::math::Vector2d(x,y)); } ///////////////////////////////////////////////// IntersectionResult CheckCollisions( - const gz::math::Vector2d &_x1, - const gz::math::Vector2d &_x0, + const ignition::math::Vector2d &_x1, + const ignition::math::Vector2d &_x0, const Layout &_layout) { PointPair points = std::make_pair(_x1, _x0); @@ -135,7 +135,7 @@ void Simulate(const EnvironmentPluginPtr &_environment, uplink->ReadMap(layout); double time = 0.0; - gz::math::Vector2d x; + ignition::math::Vector2d x; double theta = 0.0; while (time < _duration) @@ -144,7 +144,7 @@ void Simulate(const EnvironmentPluginPtr &_environment, if (ProximitySensor *proximity = _robot->QueryInterface()) { const double range = proximity->MaxRange(); - const gz::math::Vector2d x_far = x + gz::math::Vector2d( + const ignition::math::Vector2d x_far = x + ignition::math::Vector2d( range*cos(theta), range*sin(theta)); IntersectionResult result = CheckCollisions(x, x_far, layout); @@ -171,11 +171,11 @@ void Simulate(const EnvironmentPluginPtr &_environment, } // Save the last state - gz::math::Vector2d x_last = x; + ignition::math::Vector2d x_last = x; // Get the driving information const double dt = 1.0/drive->Frequency(); - const gz::math::Vector3d &vel = drive->Velocity(); + const ignition::math::Vector3d &vel = drive->Velocity(); // We integrate the position components with a half-step taken in the angle, // which should smooth out the behavior of sharp turns. @@ -221,10 +221,10 @@ void Simulate(const EnvironmentPluginPtr &_environment, int main(int argc, char *argv[]) { // Create an object that can search the system paths for the plugin libraries. - gz::common::SystemPaths paths; + ignition::common::SystemPaths paths; // Create a plugin loader - gz::plugin::Loader loader; + ignition::plugin::Loader loader; // Add the build directory path for the plugin libraries so the SystemPaths // object will know to search through it. @@ -327,7 +327,7 @@ int main(int argc, char *argv[]) paths.FindSharedLibrary(robotLib)); std::unordered_set drivePlugins = - loader.PluginsImplementing("gz::plugin::examples::Drive"); + loader.PluginsImplementing("ignition::plugin::examples::Drive"); RobotPluginPtr robot; // Get the first plugin from the robotLib library that provides a Drive @@ -353,7 +353,7 @@ int main(int argc, char *argv[]) paths.FindSharedLibrary(envLib)); std::unordered_set envInterfacePlugins = - loader.PluginsImplementing("gz::plugin::examples::Environment"); + loader.PluginsImplementing("ignition::plugin::examples::Environment"); EnvironmentPluginPtr environment; // Get the first plugin from the envLib library that provides an Environment diff --git a/loader/include/gz/plugin/Loader.hh b/loader/include/gz/plugin/Loader.hh index 2a384c4e..c77b0862 100644 --- a/loader/include/gz/plugin/Loader.hh +++ b/loader/include/gz/plugin/Loader.hh @@ -30,7 +30,7 @@ #include #include -namespace gz +namespace ignition { namespace plugin { diff --git a/loader/include/gz/plugin/detail/Loader.hh b/loader/include/gz/plugin/detail/Loader.hh index 8031502c..ce5ce0f6 100644 --- a/loader/include/gz/plugin/detail/Loader.hh +++ b/loader/include/gz/plugin/detail/Loader.hh @@ -25,7 +25,7 @@ #include #include -namespace gz +namespace ignition { namespace plugin { diff --git a/loader/src/Loader.cc b/loader/src/Loader.cc index e5980fb2..a0a40ba6 100644 --- a/loader/src/Loader.cc +++ b/loader/src/Loader.cc @@ -32,7 +32,7 @@ #include -namespace gz +namespace ignition { namespace plugin { @@ -408,7 +408,7 @@ namespace gz if (this->dataPtr->plugins.end() == it) { // LCOV_EXCL_START - std::cerr << "[gz::Loader::PrivateGetInfo] A resolved name [" + std::cerr << "[ignition::Loader::PrivateGetInfo] A resolved name [" << _resolvedName << "] could not be found in the PluginMap. " << "This should not be possible! Please report this bug!\n"; assert(false); @@ -429,7 +429,7 @@ namespace gz if (this->dataPtr->pluginToDlHandlePtrs.end() == it) { // LCOV_EXCL_START - std::cerr << "[gz::Loader::PrivateGetInfo] A resolved name [" + std::cerr << "[ignition::Loader::PrivateGetInfo] A resolved name [" << _resolvedName << "] could not be found in the " << "PluginToDlHandleMap. This should not be possible! Please " << "report this bug!\n"; @@ -595,7 +595,7 @@ namespace gz InfoHook(nullptr, reinterpret_cast(&allInfo), &version, &size, &alignment); - if (gz::plugin::INFO_API_VERSION != version) + if (ignition::plugin::INFO_API_VERSION != version) { // TODO(anyone): When we need to support multiple API versions, // put the logic for it into here. @@ -604,7 +604,7 @@ namespace gz std::cerr << "The library [" << _pathToLibrary << "] is using an " << "incompatible version [" << version << "] of the " - << "gz::plugin Info API. The version in this library " + << "ignition::plugin Info API. The version in this library " << "is [" << INFO_API_VERSION << "].\n"; return loadedPlugins; } @@ -625,7 +625,7 @@ namespace gz if (!allInfo) { std::cerr << "The library [" << _pathToLibrary << "] failed to provide " - << "gz::plugin Info for unknown reasons. Please report " + << "ignition::plugin Info for unknown reasons. Please report " << "this error as a bug!\n"; return loadedPlugins; @@ -659,7 +659,7 @@ namespace gz // buffering. std::stringstream ss; - ss << "[gz::plugin::Loader::LookupPlugin] Failed to resolve the " + ss << "[ignition::plugin::Loader::LookupPlugin] Failed to resolve the " << "alias [" << _nameOrAlias << "] because it refers to multiple " << "plugins:\n"; for (const std::string &plugin : alias->second) @@ -670,7 +670,7 @@ namespace gz return ""; } - std::cerr << "[gz::plugin::Loader::LookupPlugin] Failed to get " + std::cerr << "[ignition::plugin::Loader::LookupPlugin] Failed to get " << "info for [" << _nameOrAlias << "]. Could not find a plugin " << "with that name or alias.\n"; diff --git a/loader/src/Loader_TEST.cc b/loader/src/Loader_TEST.cc index edb6c1fa..8c641305 100644 --- a/loader/src/Loader_TEST.cc +++ b/loader/src/Loader_TEST.cc @@ -27,14 +27,14 @@ ///////////////////////////////////////////////// TEST(Loader, InitialNoInterfacesImplemented) { - gz::plugin::Loader loader; + ignition::plugin::Loader loader; EXPECT_EQ(0u, loader.InterfacesImplemented().size()); } ///////////////////////////////////////////////// TEST(Loader, LoadNonexistantLibrary) { - gz::plugin::Loader loader; + ignition::plugin::Loader loader; EXPECT_TRUE(loader.LoadLib("/path/to/libDoesNotExist.so").empty()); EXPECT_FALSE(loader.ForgetLibrary("/path/to/libDoesNotExist.so")); } @@ -42,7 +42,7 @@ TEST(Loader, LoadNonexistantLibrary) ///////////////////////////////////////////////// TEST(Loader, LoadNonLibrary) { - gz::plugin::Loader loader; + ignition::plugin::Loader loader; EXPECT_TRUE(loader.LoadLib(std::string(IGN_PLUGIN_SOURCE_DIR) + "/core/src/Plugin.cc").empty()); } @@ -50,15 +50,15 @@ TEST(Loader, LoadNonLibrary) ///////////////////////////////////////////////// TEST(Loader, LoadNonPluginLibrary) { - gz::plugin::Loader loader; + ignition::plugin::Loader loader; EXPECT_TRUE(loader.LoadLib(IGN_PLUGIN_LIB).empty()); } ///////////////////////////////////////////////// TEST(Loader, InstantiateUnloadedPlugin) { - gz::plugin::Loader loader; - gz::plugin::PluginPtr plugin = + ignition::plugin::Loader loader; + ignition::plugin::PluginPtr plugin = loader.Instantiate("plugin::that::is::not::loaded"); EXPECT_FALSE(plugin); EXPECT_FALSE(loader.ForgetLibraryOfPlugin("plugin::that::is::not::loaded")); @@ -69,11 +69,11 @@ class SomeInterface { }; ///////////////////////////////////////////////// TEST(Loader, InstantiateSpecializedPlugin) { - gz::plugin::Loader loader; + ignition::plugin::Loader loader; // This makes sure that Loader::Instantiate can compile auto plugin = loader.Instantiate< - gz::plugin::SpecializedPluginPtr >("fake::plugin"); + ignition::plugin::SpecializedPluginPtr >("fake::plugin"); EXPECT_FALSE(plugin); } @@ -82,7 +82,7 @@ TEST(Loader, DoubleLoad) { // We do this test for code coverage, to test the lines of code that get run // when a user asks for a library to be loaded twice. - gz::plugin::Loader loader; + ignition::plugin::Loader loader; loader.LoadLib(IGNDummyPlugins_LIB); const std::size_t interfaceCount = loader.InterfacesImplemented().size(); @@ -100,13 +100,13 @@ TEST(Loader, ForgetUnloadedLibrary) // This first test triggers lines for the case that: // 1. A library is not loaded, and // 2. We tell a loader to forget the library - gz::plugin::Loader loader; + ignition::plugin::Loader loader; EXPECT_FALSE(loader.ForgetLibrary(IGNDummyPlugins_LIB)); // This next test triggers lines for the case that: // 1. A library is loaded by some loader in the application, and // 2. We tell a *different* loader to forget the library - gz::plugin::Loader hasTheLibrary; + ignition::plugin::Loader hasTheLibrary; EXPECT_LT(0u, hasTheLibrary.LoadLib(IGNDummyPlugins_LIB).size()); EXPECT_FALSE(loader.ForgetLibrary(IGNDummyPlugins_LIB)); diff --git a/loader/src/gz.cc b/loader/src/gz.cc index ba82f0d1..a689b452 100644 --- a/loader/src/gz.cc +++ b/loader/src/gz.cc @@ -21,7 +21,7 @@ #include "gz/plugin/Loader.hh" #include "gz/plugin/config.hh" -using namespace gz; +using namespace ignition; using namespace plugin; ////////////////////////////////////////////////// diff --git a/loader/src/gz_TEST.cc b/loader/src/gz_TEST.cc index 196969a0..fd97a37f 100644 --- a/loader/src/gz_TEST.cc +++ b/loader/src/gz_TEST.cc @@ -28,7 +28,7 @@ # define pclose _pclose #endif -using namespace gz; +using namespace ignition; static const std::string g_ignVersion("--force-version " + // NOLINT(*) std::string(IGN_VERSION_FULL)); @@ -145,7 +145,7 @@ TEST(ignTest, PluginInfoDummyPlugins) EXPECT_NE(std::string::npos, output.find("test::util::DummySetterBase")) << output; EXPECT_NE(std::string::npos, - output.find("gz::plugin::EnablePluginFromThis")) + output.find("ignition::plugin::EnablePluginFromThis")) << output; } @@ -175,7 +175,7 @@ TEST(ignTest, PluginInfoVerboseDummyPlugins) EXPECT_NE(std::string::npos, output.find("test::util::DummySetterBase")) << output; EXPECT_NE(std::string::npos, - output.find("gz::plugin::EnablePluginFromThis")) + output.find("ignition::plugin::EnablePluginFromThis")) << output; EXPECT_NE(std::string::npos, output.find("Known Plugins: 3")) diff --git a/register/include/gz/plugin/Register.hh b/register/include/gz/plugin/Register.hh index ac1facd4..2dc7f9a1 100644 --- a/register/include/gz/plugin/Register.hh +++ b/register/include/gz/plugin/Register.hh @@ -85,7 +85,7 @@ /// memory management system the consumer prefers. /// /// The inputs and output of a factory are defined using the -/// gz::plugin::Factory class in the ignition/plugin/Factory.hh header. +/// ignition::plugin::Factory class in the ignition/plugin/Factory.hh header. /// /// The first argument of this macro should be the class that implements the /// factory's output interface. The second argument should be the factory @@ -109,11 +109,11 @@ /// }; /// /// /* BAD! Will not compile: -/// IGNITION_ADD_FACTORY(MyType, gz::plugin::Factory); +/// IGNITION_ADD_FACTORY(MyType, ignition::plugin::Factory); /// */ /// /// // Instead do this: -/// using MyFactory = gz::plugin::Factory; +/// using MyFactory = ignition::plugin::Factory; /// IGNITION_ADD_FACTORY(MyType, MyFactory); /// \endcode #define IGNITION_ADD_FACTORY(ProductType, FactoryType) \ diff --git a/register/include/gz/plugin/detail/Register.hh b/register/include/gz/plugin/detail/Register.hh index 065c2449..3a2432bc 100644 --- a/register/include/gz/plugin/detail/Register.hh +++ b/register/include/gz/plugin/detail/Register.hh @@ -122,7 +122,7 @@ extern "C" // plugin library. // ^^^^^^^^^^^^^^^^^^^^^ READ ABOVE FOR LINKING ERRORS ^^^^^^^^^^^^^^^^^^^^^ { - using InfoMap = gz::plugin::InfoMap; + using InfoMap = ignition::plugin::InfoMap; // We use a static variable here so that we can accumulate multiple // Info objects from multiple plugin registration calls within one // shared library, and then provide it all to the Loader through this @@ -133,8 +133,8 @@ extern "C" { // When _inputSingleInfo is not a nullptr, it means that one of the plugin // registration macros is providing us with some Info. - const gz::plugin::Info *input = - static_cast(_inputSingleInfo); + const ignition::plugin::Info *input = + static_cast(_inputSingleInfo); InfoMap::iterator it; bool inserted; @@ -153,7 +153,7 @@ extern "C" // user to specify different interfaces and aliases for the same plugin // type using different macros in different locations or across multiple // translation units. - gz::plugin::Info &entry = it->second; + ignition::plugin::Info &entry = it->second; for (const auto &interfaceMapEntry : input->interfaces) entry.interfaces.insert(interfaceMapEntry); @@ -182,21 +182,21 @@ extern "C" bool agreement = true; - if (gz::plugin::INFO_API_VERSION != *_inputAndOutputAPIVersion) + if (ignition::plugin::INFO_API_VERSION != *_inputAndOutputAPIVersion) { // LCOV_EXCL_START agreement = false; // LCOV_EXCL_STOP } - if (sizeof(gz::plugin::Info) != *_inputAndOutputInfoSize) + if (sizeof(ignition::plugin::Info) != *_inputAndOutputInfoSize) { // LCOV_EXCL_START agreement = false; // LCOV_EXCL_STOP } - if (alignof(gz::plugin::Info) != *_inputAndOutputInfoAlign) + if (alignof(ignition::plugin::Info) != *_inputAndOutputInfoAlign) { // LCOV_EXCL_START agreement = false; @@ -212,9 +212,9 @@ extern "C" // This implementation might change when new API versions are introduced, // but this current implementation will still be forward compatible with // new API versions. - *_inputAndOutputAPIVersion = gz::plugin::INFO_API_VERSION; - *_inputAndOutputInfoSize = sizeof(gz::plugin::Info); - *_inputAndOutputInfoAlign = alignof(gz::plugin::Info); + *_inputAndOutputAPIVersion = ignition::plugin::INFO_API_VERSION; + *_inputAndOutputInfoSize = sizeof(ignition::plugin::Info); + *_inputAndOutputInfoAlign = alignof(ignition::plugin::Info); // If the size, alignment, or API do not agree, we should return without // outputting any of the plugin info; otherwise, we could get a @@ -236,7 +236,7 @@ extern "C" #endif } -namespace gz +namespace ignition { namespace plugin { @@ -437,13 +437,13 @@ IGN_UTILS_WARN_RESUME__NON_VIRTUAL_DESTRUCTOR ////////////////////////////////////////////////// /// This macro creates a uniquely-named class whose constructor calls the -/// gz::plugin::detail::Registrar::Register function. It then declares a +/// ignition::plugin::detail::Registrar::Register function. It then declares a /// uniquely-named instance of the class with static lifetime. Since the class /// instance has a static lifetime, it will be constructed when the shared /// library is loaded. When it is constructed, the Register function will /// be called. #define DETAIL_IGNITION_ADD_PLUGIN_HELPER(UniqueID, ...) \ - namespace gz \ + namespace ignition \ { \ namespace plugin \ { \ @@ -453,7 +453,7 @@ IGN_UTILS_WARN_RESUME__NON_VIRTUAL_DESTRUCTOR { \ ExecuteWhenLoadingLibrary##UniqueID() \ { \ - ::gz::plugin::detail::Registrar<__VA_ARGS__>::Register(); \ + ::ignition::plugin::detail::Registrar<__VA_ARGS__>::Register(); \ } \ }; \ \ @@ -479,13 +479,13 @@ IGN_UTILS_WARN_RESUME__NON_VIRTUAL_DESTRUCTOR ////////////////////////////////////////////////// /// This macro creates a uniquely-named class whose constructor calls the -/// gz::plugin::detail::Registrar::RegisterAlias function. It then +/// ignition::plugin::detail::Registrar::RegisterAlias function. It then /// declares a uniquely-named instance of the class with static lifetime. Since /// the class instance has a static lifetime, it will be constructed when the /// shared library is loaded. When it is constructed, the Register function will /// be called. #define DETAIL_IGNITION_ADD_PLUGIN_ALIAS_HELPER(UniqueID, PluginClass, ...) \ - namespace gz \ + namespace ignition \ { \ namespace plugin \ { \ @@ -495,7 +495,7 @@ IGN_UTILS_WARN_RESUME__NON_VIRTUAL_DESTRUCTOR { \ ExecuteWhenLoadingLibrary##UniqueID() \ { \ - ::gz::plugin::detail::Registrar::RegisterAlias( \ + ::ignition::plugin::detail::Registrar::RegisterAlias( \ __VA_ARGS__); \ } \ }; \ @@ -527,7 +527,7 @@ IGN_UTILS_WARN_RESUME__NON_VIRTUAL_DESTRUCTOR DETAIL_IGNITION_ADD_PLUGIN(FactoryType::Producing, FactoryType) \ DETAIL_IGNITION_ADD_PLUGIN_ALIAS( \ FactoryType::Producing, \ - ::gz::plugin::DemangleSymbol(typeid(ProductType).name())) + ::ignition::plugin::DemangleSymbol(typeid(ProductType).name())) ////////////////////////////////////////////////// diff --git a/test/integration/EnablePluginFromThis_TEST.cc b/test/integration/EnablePluginFromThis_TEST.cc index f38e8b4f..0f3996fa 100644 --- a/test/integration/EnablePluginFromThis_TEST.cc +++ b/test/integration/EnablePluginFromThis_TEST.cc @@ -28,22 +28,22 @@ ///////////////////////////////////////////////// TEST(EnablePluginFromThis, BasicInstantiate) { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(IGNDummyPlugins_LIB); - gz::plugin::PluginPtr plugin = + ignition::plugin::PluginPtr plugin = pl.Instantiate("test::util::DummyMultiPlugin"); ASSERT_TRUE(plugin); auto *fromThisInterface = - plugin->QueryInterface(); + plugin->QueryInterface(); EXPECT_TRUE(fromThisInterface); - gz::plugin::PluginPtr fromThis = fromThisInterface->PluginFromThis(); + ignition::plugin::PluginPtr fromThis = fromThisInterface->PluginFromThis(); EXPECT_EQ(plugin, fromThis); - gz::plugin::ConstPluginPtr constFromThis = - static_cast( + ignition::plugin::ConstPluginPtr constFromThis = + static_cast( fromThisInterface)->PluginFromThis(); EXPECT_EQ(constFromThis, fromThis); @@ -59,12 +59,12 @@ TEST(EnablePluginFromThis, BasicInstantiate) ASSERT_TRUE(plugin); fromThisInterface = - plugin->QueryInterface(); + plugin->QueryInterface(); EXPECT_EQ(nullptr, fromThisInterface); } ///////////////////////////////////////////////// -using MySpecializedPluginPtr = gz::plugin::SpecializedPluginPtr< +using MySpecializedPluginPtr = ignition::plugin::SpecializedPluginPtr< test::util::DummyNameBase, test::util::DummyDoubleBase, test::util::DummyIntBase @@ -73,7 +73,7 @@ using MySpecializedPluginPtr = gz::plugin::SpecializedPluginPtr< ///////////////////////////////////////////////// TEST(EnablePluginFromThis, TemplatedInstantiate) { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(IGNDummyPlugins_LIB); MySpecializedPluginPtr plugin = @@ -81,10 +81,10 @@ TEST(EnablePluginFromThis, TemplatedInstantiate) ASSERT_TRUE(plugin); auto *fromThisInterface = - plugin->QueryInterface(); + plugin->QueryInterface(); EXPECT_TRUE(fromThisInterface); - gz::plugin::PluginPtr fromThis = fromThisInterface->PluginFromThis(); + ignition::plugin::PluginPtr fromThis = fromThisInterface->PluginFromThis(); EXPECT_EQ(plugin, fromThis); @@ -94,7 +94,7 @@ TEST(EnablePluginFromThis, TemplatedInstantiate) ASSERT_TRUE(plugin); fromThisInterface = - plugin->QueryInterface(); + plugin->QueryInterface(); EXPECT_EQ(nullptr, fromThisInterface); } @@ -103,24 +103,24 @@ TEST(EnablePluginFromThis, LibraryManagement) { const std::string &libraryPath = IGNDummyPlugins_LIB; - gz::plugin::WeakPluginPtr weak; + ignition::plugin::WeakPluginPtr weak; { - gz::plugin::PluginPtr longterm; + ignition::plugin::PluginPtr longterm; CHECK_FOR_LIBRARY(libraryPath, false); { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(libraryPath); CHECK_FOR_LIBRARY(libraryPath, true); - gz::plugin::PluginPtr temporary = + ignition::plugin::PluginPtr temporary = pl.Instantiate("test::util::DummyMultiPlugin"); auto fromThis = - temporary->QueryInterface(); + temporary->QueryInterface(); longterm = fromThis->PluginFromThis(); weak = fromThis->PluginFromThis(); diff --git a/test/integration/WeakPluginPtr.cc b/test/integration/WeakPluginPtr.cc index 2ebe14ff..3a4ad6d4 100644 --- a/test/integration/WeakPluginPtr.cc +++ b/test/integration/WeakPluginPtr.cc @@ -28,23 +28,23 @@ TEST(WeakPluginPtr, Lifecycle) { const std::string &libraryPath = IGNDummyPlugins_LIB; - gz::plugin::WeakPluginPtr weak; + ignition::plugin::WeakPluginPtr weak; CHECK_FOR_LIBRARY(libraryPath, false); { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(libraryPath); CHECK_FOR_LIBRARY(libraryPath, true); - gz::plugin::PluginPtr plugin = + ignition::plugin::PluginPtr plugin = pl.Instantiate("test::util::DummyMultiPlugin"); weak = plugin; EXPECT_FALSE(weak.IsExpired()); - gz::plugin::PluginPtr copy = weak.Lock(); + ignition::plugin::PluginPtr copy = weak.Lock(); test::util::DummyIntBase* base = copy->QueryInterface(); @@ -60,7 +60,7 @@ TEST(WeakPluginPtr, Lifecycle) EXPECT_TRUE(weak.IsExpired()); - gz::plugin::PluginPtr empty = weak.Lock(); + ignition::plugin::PluginPtr empty = weak.Lock(); EXPECT_TRUE(empty.IsEmpty()); EXPECT_FALSE(empty->QueryInterface()); } @@ -68,32 +68,32 @@ TEST(WeakPluginPtr, Lifecycle) ///////////////////////////////////////////////// TEST(WeakPluginPtr, CopyMove) { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(IGNDummyPlugins_LIB); - gz::plugin::PluginPtr plugin = + ignition::plugin::PluginPtr plugin = pl.Instantiate("test::util::DummyMultiPlugin"); - gz::plugin::WeakPluginPtr weakConstructFromPlugin(plugin); + ignition::plugin::WeakPluginPtr weakConstructFromPlugin(plugin); EXPECT_EQ(plugin, weakConstructFromPlugin.Lock()); - gz::plugin::WeakPluginPtr weakCopyFromOther( + ignition::plugin::WeakPluginPtr weakCopyFromOther( weakConstructFromPlugin); EXPECT_EQ(plugin, weakConstructFromPlugin.Lock()); - gz::plugin::WeakPluginPtr weakCopyAssignFromOther; + ignition::plugin::WeakPluginPtr weakCopyAssignFromOther; weakCopyAssignFromOther = weakConstructFromPlugin; EXPECT_EQ(plugin, weakCopyAssignFromOther.Lock()); - gz::plugin::WeakPluginPtr weakMoveFromOther( + ignition::plugin::WeakPluginPtr weakMoveFromOther( std::move(weakCopyFromOther)); EXPECT_EQ(plugin, weakMoveFromOther.Lock()); - gz::plugin::WeakPluginPtr weakMoveAssignFromOther; + ignition::plugin::WeakPluginPtr weakMoveAssignFromOther; weakMoveAssignFromOther = std::move(weakCopyAssignFromOther); EXPECT_EQ(plugin, weakMoveAssignFromOther.Lock()); - gz::plugin::WeakPluginPtr weakAssignFromPlugin; + ignition::plugin::WeakPluginPtr weakAssignFromPlugin; weakAssignFromPlugin = plugin; EXPECT_EQ(plugin, weakAssignFromPlugin.Lock()); } diff --git a/test/integration/aliases.cc b/test/integration/aliases.cc index 26b6dac0..f2fca661 100644 --- a/test/integration/aliases.cc +++ b/test/integration/aliases.cc @@ -24,7 +24,7 @@ ///////////////////////////////////////////////// TEST(Alias, InspectAliases) { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; // Make sure the expected plugins were loaded. std::unordered_set pluginNames = @@ -49,7 +49,7 @@ TEST(Alias, InspectAliases) ///////////////////////////////////////////////// TEST(Alias, ConflictingAlias) { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; // Make sure the expected plugins were loaded. std::unordered_set pluginNames = @@ -59,7 +59,7 @@ TEST(Alias, ConflictingAlias) ASSERT_EQ(1u, pluginNames.count("test::util::DummyNoAliasPlugin")); // This alias conflicts between DummySinglePlugin and DummyMultiPlugin - gz::plugin::PluginPtr attempt = pl.Instantiate("Bar"); + ignition::plugin::PluginPtr attempt = pl.Instantiate("Bar"); EXPECT_TRUE(attempt.IsEmpty()); // This alias conflicts between DummySinglePlugin and DummyMultiPlugin diff --git a/test/integration/factory.cc b/test/integration/factory.cc index 87017662..2361b010 100644 --- a/test/integration/factory.cc +++ b/test/integration/factory.cc @@ -28,7 +28,7 @@ using namespace test::util; ///////////////////////////////////////////////// TEST(Factory, Inspect) { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(IGNFactoryPlugins_LIB); std::cout << pl.PrettyStr() << std::endl; @@ -42,7 +42,7 @@ TEST(Factory, Inspect) ///////////////////////////////////////////////// TEST(Factory, Construct) { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(IGNFactoryPlugins_LIB); auto nameFactory = pl.Factory("test::util::DummyNameForward"); @@ -99,13 +99,13 @@ TEST(Factory, Construct) ///////////////////////////////////////////////// TEST(Factory, Alias) { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(IGNFactoryPlugins_LIB); std::string symbolName; for (const std::string &name : pl.AllPlugins()) { - if (name.find("gz::plugin::Factory") != std::string::npos && + if (name.find("ignition::plugin::Factory") != std::string::npos && name.find("test::util::SomeObjectAddTwo") != std::string::npos) { symbolName = name; @@ -145,7 +145,7 @@ TEST(Factory, LibraryManagement) SomeObjectFactory::ProductPtrType obj; { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(libraryPath); CHECK_FOR_LIBRARY(libraryPath, true); @@ -173,7 +173,7 @@ TEST(Factory, LibraryManagement) SomeObject *obj; { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(libraryPath); CHECK_FOR_LIBRARY(libraryPath, true); @@ -191,7 +191,7 @@ TEST(Factory, LibraryManagement) CHECK_FOR_LIBRARY(libraryPath, true); - gz::plugin::ProductDeleter()(obj); + ignition::plugin::ProductDeleter()(obj); CHECK_FOR_LIBRARY(libraryPath, false); } @@ -205,7 +205,7 @@ TEST(Factory, LibraryManagement) std::unique_ptr obj; { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(libraryPath); CHECK_FOR_LIBRARY(libraryPath, true); @@ -226,7 +226,7 @@ TEST(Factory, LibraryManagement) // Now the reference count for the library has been passed into the // lostProductManager. - EXPECT_EQ(1u, gz::plugin::LostProductCount()); + EXPECT_EQ(1u, ignition::plugin::LostProductCount()); // As long as the reference count is in the lostProductManager, the library // will remain loaded. @@ -234,10 +234,10 @@ TEST(Factory, LibraryManagement) // This function will clean up all the lost products, deleting their reference // counts. - gz::plugin::CleanupLostProducts(); + ignition::plugin::CleanupLostProducts(); // Now there should be no more lost products, so this count is 0. - EXPECT_EQ(0u, gz::plugin::LostProductCount()); + EXPECT_EQ(0u, ignition::plugin::LostProductCount()); // With the reference counts deleted, the library should automatically unload. CHECK_FOR_LIBRARY(libraryPath, false); diff --git a/test/integration/plugin.cc b/test/integration/plugin.cc index f719c292..4acab69c 100644 --- a/test/integration/plugin.cc +++ b/test/integration/plugin.cc @@ -42,7 +42,7 @@ TEST(Loader, LoadBadPlugins) IGNBadPluginSize_LIB}; for (auto const & library : libraries) { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; // Make sure the expected plugins were loaded. std::unordered_set pluginNames = pl.LoadLib(library); @@ -53,7 +53,7 @@ TEST(Loader, LoadBadPlugins) ///////////////////////////////////////////////// TEST(Loader, LoadExistingLibrary) { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; // Make sure the expected plugins were loaded. std::unordered_set pluginNames = @@ -75,7 +75,7 @@ TEST(Loader, LoadExistingLibrary) EXPECT_EQ(1u, pl.InterfacesImplemented().count( "test::util::DummySetterBase")); EXPECT_EQ(1u, pl.InterfacesImplemented().count( - "gz::plugin::EnablePluginFromThis")); + "ignition::plugin::EnablePluginFromThis")); EXPECT_EQ(1u, pl.InterfacesImplemented().count( "test::util::DummyGetPluginInstancePtr")); EXPECT_EQ(1u, pl.InterfacesImplemented().count("test::util::DummyNameBase")); @@ -95,7 +95,7 @@ TEST(Loader, LoadExistingLibrary) EXPECT_EQ(3u, pl.AllPlugins().size()); // Check DummySinglePlugin. - gz::plugin::PluginPtr firstPlugin = + ignition::plugin::PluginPtr firstPlugin = pl.Instantiate("test::util::DummySinglePlugin"); EXPECT_FALSE(firstPlugin.IsEmpty()); EXPECT_TRUE(static_cast(firstPlugin)); @@ -115,7 +115,7 @@ TEST(Loader, LoadExistingLibrary) EXPECT_FALSE(firstPlugin->HasInterface("test::util::DummySetterBase")); // Check DummyMultiPlugin. - gz::plugin::PluginPtr secondPlugin = + ignition::plugin::PluginPtr secondPlugin = pl.Instantiate("test::util::DummyMultiPlugin"); EXPECT_FALSE(secondPlugin.IsEmpty()); @@ -176,7 +176,7 @@ TEST(Loader, LoadExistingLibrary) class SomeInterface { }; using SomeSpecializedPluginPtr = - gz::plugin::SpecializedPluginPtr< + ignition::plugin::SpecializedPluginPtr< SomeInterface, test::util::DummyIntBase, test::util::DummySetterBase>; @@ -184,7 +184,7 @@ using SomeSpecializedPluginPtr = ///////////////////////////////////////////////// TEST(SpecializedPluginPtr, Construction) { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(IGNDummyPlugins_LIB); SomeSpecializedPluginPtr plugin( @@ -240,21 +240,21 @@ TEST(SpecializedPluginPtr, Construction) TEST(PluginPtr, Empty) { - gz::plugin::PluginPtr empty; + ignition::plugin::PluginPtr empty; EXPECT_TRUE(empty.IsEmpty()); EXPECT_EQ(nullptr, empty->Name()); EXPECT_FALSE(empty->HasInterface()); EXPECT_FALSE(static_cast(empty)); EXPECT_EQ(nullptr, empty->QueryInterfaceSharedPtr()); - gz::plugin::ConstPluginPtr constEmpty; + ignition::plugin::ConstPluginPtr constEmpty; EXPECT_EQ(nullptr, constEmpty->QueryInterfaceSharedPtr()); } ///////////////////////////////////////////////// template void TestSetAndMapUsage( - const gz::plugin::Loader &loader, - const gz::plugin::PluginPtr &plugin) + const ignition::plugin::Loader &loader, + const ignition::plugin::PluginPtr &plugin) { PluginPtrType1 plugin1 = plugin; PluginPtrType2 plugin2 = plugin1; @@ -267,22 +267,22 @@ void TestSetAndMapUsage( EXPECT_TRUE(plugin2 == plugin1); EXPECT_FALSE(plugin2 != plugin1); - std::set orderedSet; + std::set orderedSet; EXPECT_TRUE(orderedSet.insert(plugin1).second); EXPECT_FALSE(orderedSet.insert(plugin1).second); EXPECT_FALSE(orderedSet.insert(plugin2).second); - std::unordered_set unorderedSet; + std::unordered_set unorderedSet; EXPECT_TRUE(unorderedSet.insert(plugin1).second); EXPECT_FALSE(unorderedSet.insert(plugin1).second); EXPECT_FALSE(unorderedSet.insert(plugin2).second); - std::map orderedMap; + std::map orderedMap; EXPECT_TRUE(orderedMap.insert(std::make_pair(plugin1, "some string")).second); EXPECT_FALSE(orderedMap.insert(std::make_pair(plugin1, "a string")).second); EXPECT_FALSE(orderedMap.insert(std::make_pair(plugin2, "chars")).second); - std::unordered_map unorderedMap; + std::unordered_map unorderedMap; EXPECT_TRUE(unorderedMap.insert(std::make_pair(plugin1, "strings")).second); EXPECT_FALSE(unorderedMap.insert(std::make_pair(plugin1, "letters")).second); EXPECT_FALSE(unorderedMap.insert(std::make_pair(plugin2, "")).second); @@ -309,33 +309,33 @@ void TestSetAndMapUsage( ///////////////////////////////////////////////// using EmptySpecializedPluginPtr = - gz::plugin::SpecializedPluginPtr<>; + ignition::plugin::SpecializedPluginPtr<>; using SingleSpecializedPluginPtr = - gz::plugin::SpecializedPluginPtr; + ignition::plugin::SpecializedPluginPtr; using AnotherSpecializedPluginPtr = - gz::plugin::SpecializedPluginPtr< + ignition::plugin::SpecializedPluginPtr< SomeInterface, test::util::DummyIntBase>; using DuplicatedInterfaceSpecializedPluginPtr = - gz::plugin::SpecializedPluginPtr< + ignition::plugin::SpecializedPluginPtr< SomeInterface, SomeInterface>; ///////////////////////////////////////////////// TEST(PluginPtr, CopyMoveSemantics) { - gz::plugin::PluginPtr plugin; + ignition::plugin::PluginPtr plugin; EXPECT_TRUE(plugin.IsEmpty()); - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(IGNDummyPlugins_LIB); plugin = pl.Instantiate("test::util::DummySinglePlugin"); EXPECT_FALSE(plugin.IsEmpty()); - gz::plugin::PluginPtr otherPlugin = + ignition::plugin::PluginPtr otherPlugin = pl.Instantiate("test::util::DummySinglePlugin"); EXPECT_FALSE(otherPlugin.IsEmpty()); @@ -347,17 +347,17 @@ TEST(PluginPtr, CopyMoveSemantics) EXPECT_FALSE(plugin != otherPlugin); TestSetAndMapUsage< - gz::plugin::PluginPtr, - gz::plugin::PluginPtr>( + ignition::plugin::PluginPtr, + ignition::plugin::PluginPtr>( pl, plugin); TestSetAndMapUsage< - gz::plugin::PluginPtr, + ignition::plugin::PluginPtr, EmptySpecializedPluginPtr>( pl, plugin); TestSetAndMapUsage< - gz::plugin::PluginPtr, + ignition::plugin::PluginPtr, SomeSpecializedPluginPtr>( pl, plugin); @@ -376,7 +376,7 @@ TEST(PluginPtr, CopyMoveSemantics) DuplicatedInterfaceSpecializedPluginPtr>( pl, plugin); - gz::plugin::ConstPluginPtr c_plugin(plugin); + ignition::plugin::ConstPluginPtr c_plugin(plugin); EXPECT_FALSE(c_plugin.IsEmpty()); EXPECT_TRUE(c_plugin == plugin); @@ -410,12 +410,12 @@ void CheckSomeValues( ///////////////////////////////////////////////// TEST(PluginPtr, QueryInterfaceSharedPtr) { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(IGNDummyPlugins_LIB); // QueryInterfaceSharedPtr without specialization { - gz::plugin::PluginPtr plugin = + ignition::plugin::PluginPtr plugin = pl.Instantiate("test::util::DummyMultiPlugin"); std::shared_ptr int_ptr = @@ -424,7 +424,7 @@ TEST(PluginPtr, QueryInterfaceSharedPtr) EXPECT_EQ(5, int_ptr->MyIntegerValueIs()); std::shared_ptr const_int_ptr = - gz::plugin::ConstPluginPtr(plugin) + ignition::plugin::ConstPluginPtr(plugin) ->QueryInterfaceSharedPtr(); EXPECT_TRUE(const_int_ptr.get()); EXPECT_EQ(5, int_ptr->MyIntegerValueIs()); @@ -435,7 +435,7 @@ TEST(PluginPtr, QueryInterfaceSharedPtr) EXPECT_FALSE(some_ptr.get()); std::shared_ptr const_some_ptr = - gz::plugin::ConstPluginPtr(plugin) + ignition::plugin::ConstPluginPtr(plugin) ->QueryInterfaceSharedPtr(); EXPECT_FALSE(const_some_ptr.get()); } @@ -481,9 +481,9 @@ TEST(PluginPtr, QueryInterfaceSharedPtr) } ///////////////////////////////////////////////// -gz::plugin::PluginPtr GetSomePlugin(const std::string &path) +ignition::plugin::PluginPtr GetSomePlugin(const std::string &path) { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(path); return pl.Instantiate("test::util::DummyMultiPlugin"); @@ -496,7 +496,7 @@ TEST(PluginPtr, LibraryManagement) // Use scoping to destroy somePlugin { - gz::plugin::PluginPtr somePlugin = GetSomePlugin(path); + ignition::plugin::PluginPtr somePlugin = GetSomePlugin(path); EXPECT_TRUE(somePlugin); CHECK_FOR_LIBRARY(path, true); @@ -506,11 +506,11 @@ TEST(PluginPtr, LibraryManagement) // Test that we can transfer between plugins { - gz::plugin::PluginPtr somePlugin; + ignition::plugin::PluginPtr somePlugin; CHECK_FOR_LIBRARY(path, false); { - gz::plugin::PluginPtr temporaryPlugin = GetSomePlugin(path); + ignition::plugin::PluginPtr temporaryPlugin = GetSomePlugin(path); CHECK_FOR_LIBRARY(path, true); somePlugin = temporaryPlugin; } @@ -522,7 +522,7 @@ TEST(PluginPtr, LibraryManagement) // Test that we can forget libraries { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(path); CHECK_FOR_LIBRARY(path, true); @@ -535,9 +535,9 @@ TEST(PluginPtr, LibraryManagement) // Test that we can forget libraries, but the library will remain loaded if // a plugin instance is still using it. { - gz::plugin::PluginPtr plugin; + ignition::plugin::PluginPtr plugin; - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(path); CHECK_FOR_LIBRARY(path, true); @@ -555,7 +555,7 @@ TEST(PluginPtr, LibraryManagement) // Check that we can unload libraries based on plugin name { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(path); CHECK_FOR_LIBRARY(path, true); @@ -588,13 +588,13 @@ TEST(PluginPtr, LibraryManagement) // Check that mulitple Loaders can work side-by-side { - gz::plugin::Loader pl1; + ignition::plugin::Loader pl1; pl1.LoadLib(path); CHECK_FOR_LIBRARY(path, true); { - gz::plugin::Loader pl2; + ignition::plugin::Loader pl2; pl2.LoadLib(path); CHECK_FOR_LIBRARY(path, true); diff --git a/test/integration/templated_plugins.cc b/test/integration/templated_plugins.cc index 72108dd5..c1973549 100644 --- a/test/integration/templated_plugins.cc +++ b/test/integration/templated_plugins.cc @@ -32,7 +32,7 @@ using namespace test::plugins; ///////////////////////////////////////////////// TEST(TemplatedPlugins, InterfaceCount) { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(IGNTemplatedPlugins_LIB); const std::size_t getIntCount = @@ -62,13 +62,13 @@ TEST(TemplatedPlugins, InterfaceCount) ///////////////////////////////////////////////// template -using SetAndGetPluginPtr = gz::plugin::SpecializedPluginPtr< +using SetAndGetPluginPtr = ignition::plugin::SpecializedPluginPtr< TemplatedGetInterface, TemplatedSetInterface >; ///////////////////////////////////////////////// template -void TestSetAndGet(const gz::plugin::Loader &_pl, +void TestSetAndGet(const ignition::plugin::Loader &_pl, const T &_valueToUse) { using GetInterface = TemplatedGetInterface; @@ -106,7 +106,7 @@ void TestSetAndGet(const gz::plugin::Loader &_pl, ///////////////////////////////////////////////// TEST(TemplatedPlugins, SetAndGet) { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(IGNTemplatedPlugins_LIB); TestSetAndGet(pl, 120); diff --git a/test/performance/plugin_specialization.cc b/test/performance/plugin_specialization.cc index dd515097..743f1c5a 100644 --- a/test/performance/plugin_specialization.cc +++ b/test/performance/plugin_specialization.cc @@ -52,26 +52,26 @@ IGN_CREATE_INTERFACE(Interface19) // Specialize for only 1 type using Specialize1Type = - gz::plugin::SpecializedPluginPtr; + ignition::plugin::SpecializedPluginPtr; // Specialize for 3 different types, and put the type we care about first in // the list. using Specialize3Types_Leading = - gz::plugin::SpecializedPluginPtr< + ignition::plugin::SpecializedPluginPtr< test::util::DummySetterBase, Interface1, Interface2>; // Specialize for 3 different types, and put the type we care about last in // the list. using Specialize3Types_Trailing = - gz::plugin::SpecializedPluginPtr< + ignition::plugin::SpecializedPluginPtr< Interface1, Interface2, test::util::DummySetterBase>; // Specialize for 10 different types, and put the type we care about first in // the list. using Specialize10Types_Leading = - gz::plugin::SpecializedPluginPtr< + ignition::plugin::SpecializedPluginPtr< test::util::DummySetterBase, Interface1, Interface2, Interface3, Interface4, Interface5, Interface6, Interface7, Interface8, Interface9>; @@ -79,7 +79,7 @@ using Specialize10Types_Leading = // Specialize for 10 different types, and put the type we care about last in // the list. using Specialize10Types_Trailing = - gz::plugin::SpecializedPluginPtr< + ignition::plugin::SpecializedPluginPtr< Interface1, Interface2, Interface3, Interface4, Interface5, Interface6, Interface7, Interface8, Interface9, test::util::DummySetterBase>; @@ -87,7 +87,7 @@ using Specialize10Types_Trailing = // Specialize for 20 different types, and put the type we care about first in // the list. using Specialize20Types_Leading = - gz::plugin::SpecializedPluginPtr< + ignition::plugin::SpecializedPluginPtr< test::util::DummySetterBase, Interface1, Interface2, Interface3, Interface4, Interface5, Interface6, Interface7, Interface8, Interface9, Interface10, @@ -97,7 +97,7 @@ using Specialize20Types_Leading = // Specialize for 20 different types, and put the type we care about last in // the list. using Specialize20Types_Trailing = - gz::plugin::SpecializedPluginPtr< + ignition::plugin::SpecializedPluginPtr< Interface1, Interface2, Interface3, Interface4, Interface5, Interface6, Interface7, Interface8, Interface9, Interface10, Interface11, Interface12, Interface13, Interface14, Interface15, @@ -127,11 +127,11 @@ double RunPerformanceTest(const PluginType &plugin) ///////////////////////////////////////////////// TEST(PluginSpecialization, AccessTime) { - gz::plugin::Loader pl; + ignition::plugin::Loader pl; pl.LoadLib(IGNDummyPlugin_LIB); // Load up the generic plugin - gz::plugin::PluginPtr plugin = + ignition::plugin::PluginPtr plugin = pl.Instantiate("::test::util::DummyMultiPlugin"); // Create specialized versions diff --git a/test/plugins/BadPluginAlign.cc b/test/plugins/BadPluginAlign.cc index 8cf2501b..6be99f15 100644 --- a/test/plugins/BadPluginAlign.cc +++ b/test/plugins/BadPluginAlign.cc @@ -26,5 +26,5 @@ extern "C" void EXPORT IgnitionPluginHook( std::size_t *, std::size_t *_inputAndOutputInfoAlign) { - *_inputAndOutputInfoAlign = alignof(gz::plugin::Info)+1; + *_inputAndOutputInfoAlign = alignof(ignition::plugin::Info)+1; } diff --git a/test/plugins/BadPluginSize.cc b/test/plugins/BadPluginSize.cc index 3acd5131..0ec47c62 100644 --- a/test/plugins/BadPluginSize.cc +++ b/test/plugins/BadPluginSize.cc @@ -26,5 +26,5 @@ extern "C" void EXPORT IgnitionPluginHook( std::size_t *_inputAndOutputInfoSize, std::size_t *) { - *_inputAndOutputInfoSize = sizeof(gz::plugin::Info)+1; + *_inputAndOutputInfoSize = sizeof(ignition::plugin::Info)+1; } diff --git a/test/plugins/DummyMultiPlugin.hh b/test/plugins/DummyMultiPlugin.hh index 77d088e5..b448c3e6 100644 --- a/test/plugins/DummyMultiPlugin.hh +++ b/test/plugins/DummyMultiPlugin.hh @@ -17,7 +17,7 @@ class DummyMultiPlugin public DummySetterBase, public DummyGetObjectBase, public DummyGetPluginInstancePtr, - public gz::plugin::EnablePluginFromThis + public ignition::plugin::EnablePluginFromThis { public: virtual std::string MyNameIs() const override; public: virtual double MyDoubleValueIs() const override; diff --git a/test/plugins/FactoryPlugins.hh b/test/plugins/FactoryPlugins.hh index d96ef6d1..4c71af43 100644 --- a/test/plugins/FactoryPlugins.hh +++ b/test/plugins/FactoryPlugins.hh @@ -29,15 +29,15 @@ namespace util /// \brief A signature for factories that take a std::string and return a /// DummyNameBase implementation using NameFactory = - gz::plugin::Factory; + ignition::plugin::Factory; /// \brief A signature for factories that take a double and return a /// DummyDoubleBase implementation -using DoubleFactory = gz::plugin::Factory; +using DoubleFactory = ignition::plugin::Factory; /// \brief A signature for factories that take an int and return a DummyIntBase /// implementation -using IntFactory = gz::plugin::Factory; +using IntFactory = ignition::plugin::Factory; /// \brief A class whose constructor takes in arguments class SomeObject @@ -59,7 +59,7 @@ class SomeObject /// \brief A signature for factories that take an int and double and then return /// a SomeObject instance -using SomeObjectFactory = gz::plugin::Factory; +using SomeObjectFactory = ignition::plugin::Factory; } } diff --git a/test/static_assertions/plugin_bad_const_assignment.cc b/test/static_assertions/plugin_bad_const_assignment.cc index 63d75a4e..02e7e0a7 100644 --- a/test/static_assertions/plugin_bad_const_assignment.cc +++ b/test/static_assertions/plugin_bad_const_assignment.cc @@ -19,7 +19,7 @@ int main() { - gz::plugin::ConstPluginPtr const_ptr; - gz::plugin::PluginPtr ptr; + ignition::plugin::ConstPluginPtr const_ptr; + ignition::plugin::PluginPtr ptr; ptr = const_ptr; } diff --git a/test/static_assertions/plugin_bad_const_construct.cc b/test/static_assertions/plugin_bad_const_construct.cc index 6a0f87aa..d211fa07 100644 --- a/test/static_assertions/plugin_bad_const_construct.cc +++ b/test/static_assertions/plugin_bad_const_construct.cc @@ -19,5 +19,5 @@ int main() { - gz::plugin::PluginPtr ptr{gz::plugin::ConstPluginPtr()}; + ignition::plugin::PluginPtr ptr{ignition::plugin::ConstPluginPtr()}; }