From f82e2e54c5f94221335928ea0ee12dd55154cc5f Mon Sep 17 00:00:00 2001 From: methylDragon Date: Fri, 17 Jun 2022 16:12:18 -0700 Subject: [PATCH] ign -> gz Upstream Macro Migration : gz-msgs (#260) Co-authored-by: Louise Poubel --- include/gz/msgs/Factory.hh | 8 ++++---- include/gz/msgs/Filesystem.hh | 4 ++-- include/gz/msgs/Utility.hh | 2 +- include/ignition/msgs/Factory.hh | 3 +++ proto/gz/msgs/fuel_metadata.proto | 2 +- proto/gz/msgs/occupancy_grid.proto | 2 +- proto/gz/msgs/pointcloud_packed.proto | 2 +- src/Generator.cc | 4 ++-- src/Utility.cc | 10 +++++----- src/Utility_TEST.cc | 16 ++++++++-------- src/cmd/cmdmsgs.rb.in | 6 +++--- src/ign.cc | 2 +- src/ign.hh | 2 +- tools/ign_TEST.cc | 2 +- 14 files changed, 34 insertions(+), 31 deletions(-) diff --git a/include/gz/msgs/Factory.hh b/include/gz/msgs/Factory.hh index 3c723a8f..7516dc4c 100644 --- a/include/gz/msgs/Factory.hh +++ b/include/gz/msgs/Factory.hh @@ -114,21 +114,21 @@ namespace gz /// Use this macro to register messages. /// \param[in] _msgtype Message type name. /// \param[in] _classname Class name for message. - #define IGN_REGISTER_STATIC_MSG(_msgtype, _classname) \ + #define GZ_REGISTER_STATIC_MSG(_msgtype, _classname) \ GZ_MSGS_VISIBLE \ std::unique_ptr New##_classname() \ { \ return std::unique_ptr(\ new gz::msgs::_classname); \ } \ - class GZ_MSGS_VISIBLE IgnMsg##_classname \ + class GZ_MSGS_VISIBLE GzMsg##_classname \ { \ - public: IgnMsg##_classname() \ + public: GzMsg##_classname() \ { \ gz::msgs::Factory::Register(_msgtype, New##_classname);\ } \ }; \ - static IgnMsg##_classname IgnitionMessagesInitializer##_classname; + static GzMsg##_classname GzMessagesInitializer##_classname; } } } diff --git a/include/gz/msgs/Filesystem.hh b/include/gz/msgs/Filesystem.hh index 22a12217..9fa6ef05 100644 --- a/include/gz/msgs/Filesystem.hh +++ b/include/gz/msgs/Filesystem.hh @@ -82,10 +82,10 @@ namespace gz /// \brief Close an open directory handle. private: void CloseHandle(); - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Private data. private: std::unique_ptr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/gz/msgs/Utility.hh b/include/gz/msgs/Utility.hh index 4b363d86..379c6581 100644 --- a/include/gz/msgs/Utility.hh +++ b/include/gz/msgs/Utility.hh @@ -35,7 +35,7 @@ /// \file Utility.hh /// \brief Utility functions that support conversion between message type -/// and ignition math types. +/// and Gazebo Math types. namespace gz { diff --git a/include/ignition/msgs/Factory.hh b/include/ignition/msgs/Factory.hh index 5256b4a6..ec2f3b74 100644 --- a/include/ignition/msgs/Factory.hh +++ b/include/ignition/msgs/Factory.hh @@ -17,3 +17,6 @@ #include #include + +#define IGN_REGISTER_STATIC_MSG(_msgtype, _classname) \ + GZ_REGISTER_STATIC_MSG(_msgtype, _classname) diff --git a/proto/gz/msgs/fuel_metadata.proto b/proto/gz/msgs/fuel_metadata.proto index 25ebd521..c2646de1 100644 --- a/proto/gz/msgs/fuel_metadata.proto +++ b/proto/gz/msgs/fuel_metadata.proto @@ -22,7 +22,7 @@ option java_outer_classname = "FuelMetadata"; /// \ingroup gz.msgs /// \interface FuelMetadata -/// \brief Meta data for an ignition Fuel resource, such as a model or world. +/// \brief Meta data for a Gazebo Fuel resource, such as a model or world. import "gz/msgs/version.proto"; import "gz/msgs/version_range.proto"; diff --git a/proto/gz/msgs/occupancy_grid.proto b/proto/gz/msgs/occupancy_grid.proto index 019b4cfd..b27ca68a 100644 --- a/proto/gz/msgs/occupancy_grid.proto +++ b/proto/gz/msgs/occupancy_grid.proto @@ -23,7 +23,7 @@ option java_outer_classname = "OccpuancyGridProtos"; /// \ingroup gz.msgs /// \interface OccupancyGrid /// \brief This message is designed to mimic ROS nav_msgs/OccupancyGrid to -/// facilitate transfer/conversion of data between ignition and ROS. +/// facilitate transfer/conversion of data between Gazebo and ROS. /// /// See: http://docs.ros.org/melodic/api/nav_msgs/html/msg/OccupancyGrid.html diff --git a/proto/gz/msgs/pointcloud_packed.proto b/proto/gz/msgs/pointcloud_packed.proto index 57f06392..92cfb0cf 100644 --- a/proto/gz/msgs/pointcloud_packed.proto +++ b/proto/gz/msgs/pointcloud_packed.proto @@ -23,7 +23,7 @@ option java_outer_classname = "PointCloudPackedProtos"; /// \ingroup gz.msgs /// \interface PointCloudPacked /// \brief This message is designed to mimic ROS sensor_msgs/PointCloud2 to -/// facilitate transfer/conversion of data between ignition and ROS. +/// facilitate transfer/conversion of data between Gazebo and ROS. /// /// See: http://docs.ros.org/melodic/api/sensor_msgs/html/msg/PointCloud2.html diff --git a/src/Generator.cc b/src/Generator.cc index ea0dc5e5..d37ef5fc 100644 --- a/src/Generator.cc +++ b/src/Generator.cc @@ -141,10 +141,10 @@ bool Generator::Generate(const FileDescriptor *_file, printer.Print(" 4127 4068)\n", "name", "includes"); printer.Print("#endif\n", "name", "includes"); - // Call the IGN_REGISTER_STATIC_MSG macro for each message + // Call the GZ_REGISTER_STATIC_MSG macro for each message for (auto i = 0; i < _file->message_type_count(); ++i) { - std::string factory = "IGN_REGISTER_STATIC_MSG(\"gz_msgs."; + std::string factory = "GZ_REGISTER_STATIC_MSG(\"gz_msgs."; factory += _file->message_type(i)->name() + "\", " + _file->message_type(i)->name() +")\n"; printer.Print(factory.c_str(), "name", "includes"); diff --git a/src/Utility.cc b/src/Utility.cc index aad40008..74638811 100644 --- a/src/Utility.cc +++ b/src/Utility.cc @@ -35,7 +35,7 @@ namespace gz { // Inline bracket to help doxygen filtering. inline namespace GZ_MSGS_VERSION_NAMESPACE { - /// \brief Left and right trim a string. This was copied from ignition + /// \brief Left and right trim a string. This was copied from Gazebo /// common, ign-common/Util.hh, to avoid adding another dependency. /// Remove this function if ign-common ever becomes a dependency. /// \param[in] _s String to trim @@ -53,7 +53,7 @@ namespace gz return _s; } - /// \brief Splits a string into tokens. This was copied from ignition + /// \brief Splits a string into tokens. This was copied from Gazebo /// common, ign-common/Util.hh, to avoid adding another dependency. /// Remove this function if ign-common every becomes a dependency. /// \param[in] _str Input string. @@ -135,10 +135,10 @@ namespace gz << _sc.surface_model() << "]. Using default." << std::endl; } - out.SetLatitudeReference(IGN_DTOR(_sc.latitude_deg())); - out.SetLongitudeReference(IGN_DTOR(_sc.longitude_deg())); + out.SetLatitudeReference(GZ_DTOR(_sc.latitude_deg())); + out.SetLongitudeReference(GZ_DTOR(_sc.longitude_deg())); out.SetElevationReference(_sc.elevation()); - out.SetHeadingOffset(IGN_DTOR(_sc.heading_deg())); + out.SetHeadingOffset(GZ_DTOR(_sc.heading_deg())); return out; } diff --git a/src/Utility_TEST.cc b/src/Utility_TEST.cc index 841197e6..0c8e603a 100644 --- a/src/Utility_TEST.cc +++ b/src/Utility_TEST.cc @@ -63,7 +63,7 @@ TEST(UtilityTest, ConvertMsgsVector2dToMath) TEST(UtilityTest, ConvertMathQuaterionToMsgs) { msgs::Quaternion msg = - msgs::Convert(math::Quaterniond(IGN_PI * 0.25, IGN_PI * 0.5, IGN_PI)); + msgs::Convert(math::Quaterniond(GZ_PI * 0.25, GZ_PI * 0.5, GZ_PI)); EXPECT_TRUE(math::equal(msg.x(), -0.65328148243818818)); EXPECT_TRUE(math::equal(msg.y(), 0.27059805007309856)); @@ -75,7 +75,7 @@ TEST(UtilityTest, ConvertMathQuaterionToMsgs) TEST(UtilityTest, ConvertMsgsQuaterionToMath) { msgs::Quaternion msg = - msgs::Convert(math::Quaterniond(IGN_PI * 0.25, IGN_PI * 0.5, IGN_PI)); + msgs::Convert(math::Quaterniond(GZ_PI * 0.25, GZ_PI * 0.5, GZ_PI)); math::Quaterniond v = msgs::Convert(msg); // TODO(anyone): to real unit test move math::equal to EXPECT_DOUBLE_EQ @@ -90,7 +90,7 @@ TEST(UtilityTest, ConvertPoseMathToMsgs) { msgs::Pose msg = msgs::Convert(math::Pose3d( math::Vector3d(1, 2, 3), - math::Quaterniond(IGN_PI * 0.25, IGN_PI * 0.5, IGN_PI))); + math::Quaterniond(GZ_PI * 0.25, GZ_PI * 0.5, GZ_PI))); EXPECT_DOUBLE_EQ(1, msg.position().x()); EXPECT_DOUBLE_EQ(2, msg.position().y()); @@ -107,7 +107,7 @@ TEST(UtilityTest, ConvertMsgPoseToMath) { msgs::Pose msg = msgs::Convert( math::Pose3d(math::Vector3d(1, 2, 3), - math::Quaterniond(IGN_PI * 0.25, IGN_PI * 0.5, IGN_PI))); + math::Quaterniond(GZ_PI * 0.25, GZ_PI * 0.5, GZ_PI))); math::Pose3d v = msgs::Convert(msg); EXPECT_DOUBLE_EQ(1, v.Pos().X()); @@ -242,7 +242,7 @@ TEST(MsgsTest, ConvertMathSphericalCoordinatesToMsgs) auto msg = msgs::Convert( math::SphericalCoordinates( math::SphericalCoordinates::SurfaceType::EARTH_WGS84, - IGN_DTOR(1.1), IGN_DTOR(2.2), 3.3, IGN_DTOR(0.4))); + GZ_DTOR(1.1), GZ_DTOR(2.2), 3.3, GZ_DTOR(0.4))); EXPECT_EQ(msgs::SphericalCoordinates::EARTH_WGS84, msg.surface_model()); EXPECT_DOUBLE_EQ(1.1, msg.latitude_deg()); @@ -380,7 +380,7 @@ TEST(UtilityTest, SetVector2d) TEST(UtilityTest, SetQuaternion) { msgs::Quaternion msg; - msgs::Set(&msg, math::Quaterniond(IGN_PI * 0.25, IGN_PI * 0.5, IGN_PI)); + msgs::Set(&msg, math::Quaterniond(GZ_PI * 0.25, GZ_PI * 0.5, GZ_PI)); EXPECT_TRUE(math::equal(msg.x(), -0.65328148243818818)); EXPECT_TRUE(math::equal(msg.y(), 0.27059805007309856)); EXPECT_TRUE(math::equal(msg.z(), 0.65328148243818829)); @@ -392,7 +392,7 @@ TEST(UtilityTest, SetPose) { msgs::Pose msg; msgs::Set(&msg, math::Pose3d(math::Vector3d(1, 2, 3), - math::Quaterniond(IGN_PI * 0.25, IGN_PI * 0.5, IGN_PI))); + math::Quaterniond(GZ_PI * 0.25, GZ_PI * 0.5, GZ_PI))); EXPECT_DOUBLE_EQ(1, msg.position().x()); EXPECT_DOUBLE_EQ(2, msg.position().y()); @@ -480,7 +480,7 @@ TEST(MsgsTest, SetSphericalCoordinates) msgs::SphericalCoordinates msg; msgs::Set(&msg, math::SphericalCoordinates( math::SphericalCoordinates::SurfaceType::EARTH_WGS84, - IGN_DTOR(1.1), IGN_DTOR(2.2), 3.3, IGN_DTOR(0.4))); + GZ_DTOR(1.1), GZ_DTOR(2.2), 3.3, GZ_DTOR(0.4))); EXPECT_EQ(msgs::SphericalCoordinates::EARTH_WGS84, msg.surface_model()); EXPECT_DOUBLE_EQ(1.1, msg.latitude_deg()); diff --git a/src/cmd/cmdmsgs.rb.in b/src/cmd/cmdmsgs.rb.in index 5bd150a9..4ffa8710 100644 --- a/src/cmd/cmdmsgs.rb.in +++ b/src/cmd/cmdmsgs.rb.in @@ -120,11 +120,11 @@ class Cmd end # Read the library version. - Importer.extern 'const char* ignitionMsgsVersion()' + Importer.extern 'const char* gzMsgsVersion()' begin - plugin_version = Importer.ignitionMsgsVersion.to_s + plugin_version = Importer.gzMsgsVersion.to_s rescue DLError - puts "Library error: Problem running 'ignitionMsgsVersion()' from #{plugin}." + puts "Library error: Problem running 'gzMsgsVersion()' from #{plugin}." exit(-1) end diff --git a/src/ign.cc b/src/ign.cc index fac6eeb9..6aaf9e5e 100644 --- a/src/ign.cc +++ b/src/ign.cc @@ -79,7 +79,7 @@ void cmdMsgList() ////////////////////////////////////////////////// extern "C" GZ_MSGS_VISIBLE -const char *ignitionMsgsVersion() +const char *gzMsgsVersion() { return GZ_MSGS_VERSION_FULL; } diff --git a/src/ign.hh b/src/ign.hh index 3df68de2..236ecd37 100644 --- a/src/ign.hh +++ b/src/ign.hh @@ -30,6 +30,6 @@ extern "C" GZ_MSGS_VISIBLE void cmdMsgList(); /// \brief External hook to read the library version. /// \return C-string representing the version. Ex.: 0.1.2 -extern "C" GZ_MSGS_VISIBLE const char *ignitionMsgsVersion(); +extern "C" GZ_MSGS_VISIBLE const char *gzMsgsVersion(); #endif diff --git a/tools/ign_TEST.cc b/tools/ign_TEST.cc index a704a870..50418607 100644 --- a/tools/ign_TEST.cc +++ b/tools/ign_TEST.cc @@ -99,7 +99,7 @@ int main(int argc, char **argv) // Make sure that we load the library recently built and not the one installed // in your system. - // Add the directory where ignition msgs has been built. + // Add the directory where Gazebo msgs has been built. std::string value = std::string(GZ_TEST_LIBRARY_PATH); // Save the current value of LD_LIBRARY_PATH. auto cvalue = std::getenv("LD_LIBRARY_PATH");