From 964ee1b382d667c774e0d8e1403754dbde7867ca Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 25 Jul 2022 16:17:47 -0700 Subject: [PATCH] Support ros_ign migration Clean up shared libraries, and tick-tock RosGzPointCloud Tick-tock launch args Hard-tock ign_ in sources Migrate ign, ign_, IGN_ for sources, launch, and test files Migrate IGN_XXX_VER, IGN_T, header guards Migrate launchfile, launchfile args, and test source references Migrate ros_ign_XXX and gz_gazebo -> gz_sim Migrate ros_ign_XXX project names Migrate Ign, ign-, IGN_DEPS, ign-gazebo Migrate ignitionrobotics, ignitionrobotics/ros_ign, osrf/ros_ign Migrate ignition-version, IGNITION_VERSION, Ignition , ros_ign_ci Signed-off-by: methylDragon --- ros_gz/CMakeLists.txt | 2 +- ros_gz/package.xml | 2 +- ros_gz_bridge/CMakeLists.txt | 38 +-- .../include/ros_gz_bridge/convert.hpp | 16 +- .../convert/builtin_interfaces.hpp | 2 +- .../ros_gz_bridge/convert/geometry_msgs.hpp | 2 +- .../ros_gz_bridge/convert/nav_msgs.hpp | 2 +- .../convert/ros_gz_interfaces.hpp | 158 +++++------ .../ros_gz_bridge/convert/rosgraph_msgs.hpp | 2 +- .../ros_gz_bridge/convert/sensor_msgs.hpp | 2 +- .../ros_gz_bridge/convert/std_msgs.hpp | 2 +- .../ros_gz_bridge/convert/tf2_msgs.hpp | 2 +- .../ros_gz_bridge/convert/trajectory_msgs.hpp | 2 +- ros_gz_bridge/package.xml | 4 +- .../src/convert/builtin_interfaces.cpp | 2 +- ros_gz_bridge/src/convert/geometry_msgs.cpp | 2 +- ros_gz_bridge/src/convert/nav_msgs.cpp | 2 +- .../src/convert/ros_gz_interfaces.cpp | 216 +++++++-------- ros_gz_bridge/src/convert/rosgraph_msgs.cpp | 2 +- ros_gz_bridge/src/convert/sensor_msgs.cpp | 2 +- ros_gz_bridge/src/convert/std_msgs.cpp | 4 +- ros_gz_bridge/src/convert/tf2_msgs.cpp | 2 +- ros_gz_bridge/src/convert/trajectory_msgs.cpp | 2 +- ros_gz_bridge/src/factories.cpp | 10 +- .../src/factories/builtin_interfaces.cpp | 2 +- ros_gz_bridge/src/factories/geometry_msgs.cpp | 2 +- ros_gz_bridge/src/factories/nav_msgs.cpp | 2 +- .../src/factories/ros_gz_interfaces.cpp | 250 +++++++++--------- .../src/factories/ros_gz_interfaces.hpp | 2 +- ros_gz_bridge/src/factories/rosgraph_msgs.cpp | 2 +- ros_gz_bridge/src/factories/sensor_msgs.cpp | 2 +- ros_gz_bridge/src/factories/std_msgs.cpp | 2 +- ros_gz_bridge/src/factories/tf2_msgs.cpp | 2 +- .../src/factories/trajectory_msgs.cpp | 2 +- ros_gz_bridge/src/parameter_bridge.cpp | 4 +- .../service_factories/ros_gz_interfaces.cpp | 46 ++-- .../service_factories/ros_gz_interfaces.hpp | 2 +- ros_gz_bridge/src/service_factory.hpp | 2 +- .../test/launch/test_gz_server.launch.py | 10 +- .../test/launch/test_gz_subscriber.launch.py | 26 +- .../test/launch/test_ros_subscriber.launch.py | 26 +- .../test/publishers/gz_publisher.cpp | 2 +- .../test/publishers/ros_publisher.cpp | 72 ++--- ros_gz_bridge/test/serverclient/gz_server.cpp | 2 +- .../test/serverclient/ros_client.cpp | 10 +- .../test/subscribers/gz_subscriber.cpp | 86 +++--- .../ros_gz_interfaces_subscriber.cpp | 18 +- ros_gz_bridge/test/utils/gz_test_msg.cpp | 2 +- ros_gz_bridge/test/utils/ros_test_msg.cpp | 70 ++--- ros_gz_bridge/test/utils/ros_test_msg.hpp | 56 ++-- ros_gz_image/CMakeLists.txt | 8 +- ros_gz_image/package.xml | 4 +- ros_gz_image/src/image_bridge.cpp | 4 +- .../test/launch/test_ros_subscriber.launch | 6 +- ros_gz_image/test/ros_subscriber.test | 4 +- ros_gz_interfaces/CMakeLists.txt | 2 +- ros_gz_interfaces/msg/Contact.msg | 6 +- ros_gz_interfaces/msg/Contacts.msg | 2 +- ros_gz_interfaces/msg/WorldControl.msg | 2 +- ros_gz_interfaces/package.xml | 2 +- ros_gz_interfaces/srv/ControlWorld.srv | 2 +- ros_gz_interfaces/srv/DeleteEntity.srv | 2 +- ros_gz_interfaces/srv/SetEntityPose.srv | 2 +- ros_gz_interfaces/srv/SpawnEntity.srv | 2 +- ros_gz_point_cloud/CMakeLists.txt | 29 +- ros_gz_point_cloud/examples/depth_camera.sdf | 18 +- ros_gz_point_cloud/examples/gpu_lidar.sdf | 18 +- ros_gz_point_cloud/examples/rgbd_camera.sdf | 22 +- ros_gz_point_cloud/package.xml | 2 +- ros_gz_sim/CMakeLists.txt | 12 +- ros_gz_sim/launch/gz_sim.launch.py.in | 37 ++- ros_gz_sim/package.xml | 2 +- ros_gz_sim/src/create.cpp | 2 +- ros_gz_sim_demos/CMakeLists.txt | 2 +- .../launch/air_pressure.launch.py | 14 +- ros_gz_sim_demos/launch/battery.launch.py | 12 +- ros_gz_sim_demos/launch/camera.launch.py | 16 +- .../launch/depth_camera.launch.py | 16 +- ros_gz_sim_demos/launch/diff_drive.launch.py | 16 +- ros_gz_sim_demos/launch/gpu_lidar.launch.py | 16 +- .../launch/gpu_lidar_bridge.launch.py | 16 +- .../launch/image_bridge.launch.py | 12 +- ros_gz_sim_demos/launch/imu.launch.py | 16 +- .../launch/joint_states.launch.py | 20 +- .../launch/magnetometer.launch.py | 12 +- ros_gz_sim_demos/launch/rgbd_camera.launch.py | 16 +- .../launch/rgbd_camera_bridge.launch.py | 16 +- .../robot_description_publisher.launch.py | 14 +- ros_gz_sim_demos/launch/tf_bridge.launch.py | 8 +- .../launch/triggered_camera.launch.py | 16 +- ros_gz_sim_demos/models/rrbot.xacro | 2 +- ros_gz_sim_demos/package.xml | 12 +- 92 files changed, 833 insertions(+), 791 deletions(-) diff --git a/ros_gz/CMakeLists.txt b/ros_gz/CMakeLists.txt index 80524e92e..db4e01a77 100644 --- a/ros_gz/CMakeLists.txt +++ b/ros_gz/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(ros_ign) +project(ros_gz) find_package(ament_cmake REQUIRED) if(BUILD_TESTING) diff --git a/ros_gz/package.xml b/ros_gz/package.xml index 53963119e..83bc74699 100644 --- a/ros_gz/package.xml +++ b/ros_gz/package.xml @@ -3,7 +3,7 @@ - ros_ign + ros_gz 0.244.3 Meta-package containing interfaces for using ROS 2 with Ignition simulation. Louise Poubel diff --git a/ros_gz_bridge/CMakeLists.txt b/ros_gz_bridge/CMakeLists.txt index 8c2a5f06e..f1eb5d8e6 100644 --- a/ros_gz_bridge/CMakeLists.txt +++ b/ros_gz_bridge/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) -project(ros_ign_bridge) +project(ros_gz_bridge) # Default to C++14 if(NOT CMAKE_CXX_STANDARD) @@ -15,7 +15,7 @@ find_package(builtin_interfaces REQUIRED) find_package(geometry_msgs REQUIRED) find_package(nav_msgs REQUIRED) find_package(rclcpp REQUIRED) -find_package(ros_ign_interfaces REQUIRED) +find_package(ros_gz_interfaces REQUIRED) find_package(rosgraph_msgs REQUIRED) find_package(sensor_msgs REQUIRED) find_package(std_msgs REQUIRED) @@ -61,7 +61,7 @@ set(PACKAGES builtin_interfaces geometry_msgs nav_msgs - ros_ign_interfaces + ros_gz_interfaces rosgraph_msgs sensor_msgs std_msgs @@ -108,14 +108,14 @@ set(bridge_executables ) set(bridge_lib - ros_ign_bridge_lib + ros_gz_bridge_lib ) add_library(${bridge_lib} SHARED src/factories.cpp src/factory_interface.cpp - src/service_factories/ros_ign_interfaces.cpp + src/service_factories/ros_gz_interfaces.cpp ) target_include_directories(${bridge_lib} @@ -167,7 +167,7 @@ if(BUILD_TESTING) ament_find_gtest() add_library(test_utils - test/utils/ign_test_msg.cpp + test/utils/gz_test_msg.cpp test/utils/ros_test_msg.cpp ) @@ -184,7 +184,7 @@ if(BUILD_TESTING) geometry_msgs nav_msgs rclcpp - ros_ign_interfaces + ros_gz_interfaces rosgraph_msgs sensor_msgs std_msgs @@ -200,7 +200,7 @@ if(BUILD_TESTING) test/subscribers/ros_subscriber/builtin_interfaces_subscriber.cpp test/subscribers/ros_subscriber/geometry_msgs_subscriber.cpp test/subscribers/ros_subscriber/nav_msgs_subscriber.cpp - test/subscribers/ros_subscriber/ros_ign_interfaces_subscriber.cpp + test/subscribers/ros_subscriber/ros_gz_interfaces_subscriber.cpp test/subscribers/ros_subscriber/rosgraph_msgs_subscriber.cpp test/subscribers/ros_subscriber/sensor_msgs_subscriber.cpp test/subscribers/ros_subscriber/std_msgs_subscriber.cpp @@ -208,14 +208,14 @@ if(BUILD_TESTING) target_link_libraries(test_ros_subscriber test_utils) - add_executable(test_ign_publisher test/publishers/ign_publisher.cpp) - target_link_libraries(test_ign_publisher test_utils) + add_executable(test_gz_publisher test/publishers/gz_publisher.cpp) + target_link_libraries(test_gz_publisher test_utils) - add_executable(test_ign_subscriber test/subscribers/ign_subscriber.cpp) - target_link_libraries(test_ign_subscriber test_utils) + add_executable(test_gz_subscriber test/subscribers/gz_subscriber.cpp) + target_link_libraries(test_gz_subscriber test_utils) - add_executable(test_ign_server test/serverclient/ign_server.cpp) - target_link_libraries(test_ign_server test_utils) + add_executable(test_gz_server test/serverclient/gz_server.cpp) + target_link_libraries(test_gz_server test_utils) add_executable(test_ros_client test/serverclient/ros_client.cpp) target_link_libraries(test_ros_client test_utils) @@ -224,9 +224,9 @@ if(BUILD_TESTING) test_ros_client test_ros_publisher test_ros_subscriber - test_ign_publisher - test_ign_server - test_ign_subscriber + test_gz_publisher + test_gz_server + test_gz_subscriber DESTINATION lib/${PROJECT_NAME} ) @@ -234,11 +234,11 @@ if(BUILD_TESTING) TIMEOUT 200 ) - add_launch_test(test/launch/test_ign_subscriber.launch.py + add_launch_test(test/launch/test_gz_subscriber.launch.py TIMEOUT 200 ) - add_launch_test(test/launch/test_ign_server.launch.py + add_launch_test(test/launch/test_gz_server.launch.py TIMEOUT 200 ) endif() diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert.hpp index 7d0d0e3fb..f7a1eb450 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert.hpp @@ -15,13 +15,13 @@ #ifndef ROS_IGN_BRIDGE__CONVERT_HPP_ #define ROS_IGN_BRIDGE__CONVERT_HPP_ -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include #endif // ROS_IGN_BRIDGE__CONVERT_HPP_ diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/builtin_interfaces.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/builtin_interfaces.hpp index 52892a74a..2720a31c9 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert/builtin_interfaces.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert/builtin_interfaces.hpp @@ -19,7 +19,7 @@ #include -#include "ros_ign_bridge/convert_decl.hpp" +#include "ros_gz_bridge/convert_decl.hpp" namespace ros_ign_bridge { diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/geometry_msgs.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/geometry_msgs.hpp index 8df05b148..e71a36338 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert/geometry_msgs.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert/geometry_msgs.hpp @@ -36,7 +36,7 @@ #include #include -#include +#include namespace ros_ign_bridge { diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/nav_msgs.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/nav_msgs.hpp index 882bc4ce3..28ff233f5 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert/nav_msgs.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert/nav_msgs.hpp @@ -22,7 +22,7 @@ // ROS 2 messages #include -#include +#include namespace ros_ign_bridge { diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/ros_gz_interfaces.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/ros_gz_interfaces.hpp index c0d0340f4..a48a453dc 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert/ros_gz_interfaces.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert/ros_gz_interfaces.hpp @@ -28,153 +28,153 @@ #include // ROS 2 messages -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include namespace ros_ign_bridge { template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::JointWrench & ros_msg, - ignition::msgs::JointWrench & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::JointWrench & ros_msg, + ignition::msgs::JointWrench & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::JointWrench & ign_msg, - ros_ign_interfaces::msg::JointWrench & ros_msg); +convert_gz_to_ros( + const ignition::msgs::JointWrench & gz_msg, + ros_gz_interfaces::msg::JointWrench & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::Entity & ros_msg, - ignition::msgs::Entity & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::Entity & ros_msg, + ignition::msgs::Entity & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Entity & ign_msg, - ros_ign_interfaces::msg::Entity & ros_msg); +convert_gz_to_ros( + const ignition::msgs::Entity & gz_msg, + ros_gz_interfaces::msg::Entity & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::Contact & ros_msg, - ignition::msgs::Contact & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::Contact & ros_msg, + ignition::msgs::Contact & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Contact & ign_msg, - ros_ign_interfaces::msg::Contact & ros_msg); +convert_gz_to_ros( + const ignition::msgs::Contact & gz_msg, + ros_gz_interfaces::msg::Contact & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::Contacts & ros_msg, - ignition::msgs::Contacts & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::Contacts & ros_msg, + ignition::msgs::Contacts & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Contacts & ign_msg, - ros_ign_interfaces::msg::Contacts & ros_msg); +convert_gz_to_ros( + const ignition::msgs::Contacts & gz_msg, + ros_gz_interfaces::msg::Contacts & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::GuiCamera & ros_msg, - ignition::msgs::GUICamera & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::GuiCamera & ros_msg, + ignition::msgs::GUICamera & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::GUICamera & ign_msg, - ros_ign_interfaces::msg::GuiCamera & ros_msg); +convert_gz_to_ros( + const ignition::msgs::GUICamera & gz_msg, + ros_gz_interfaces::msg::GuiCamera & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::Light & ros_msg, - ignition::msgs::Light & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::Light & ros_msg, + ignition::msgs::Light & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Light & ign_msg, - ros_ign_interfaces::msg::Light & ros_msg); +convert_gz_to_ros( + const ignition::msgs::Light & gz_msg, + ros_gz_interfaces::msg::Light & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::StringVec & ros_msg, - ignition::msgs::StringMsg_V & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::StringVec & ros_msg, + ignition::msgs::StringMsg_V & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::StringMsg_V & ign_msg, - ros_ign_interfaces::msg::StringVec & ros_msg); +convert_gz_to_ros( + const ignition::msgs::StringMsg_V & gz_msg, + ros_gz_interfaces::msg::StringVec & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::TrackVisual & ros_msg, - ignition::msgs::TrackVisual & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::TrackVisual & ros_msg, + ignition::msgs::TrackVisual & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::TrackVisual & ign_msg, - ros_ign_interfaces::msg::TrackVisual & ros_msg); +convert_gz_to_ros( + const ignition::msgs::TrackVisual & gz_msg, + ros_gz_interfaces::msg::TrackVisual & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::VideoRecord & ros_msg, - ignition::msgs::VideoRecord & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::VideoRecord & ros_msg, + ignition::msgs::VideoRecord & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::VideoRecord & ign_msg, - ros_ign_interfaces::msg::VideoRecord & ros_msg); +convert_gz_to_ros( + const ignition::msgs::VideoRecord & gz_msg, + ros_gz_interfaces::msg::VideoRecord & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::WorldControl & ros_msg, - ignition::msgs::WorldControl & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::WorldControl & ros_msg, + ignition::msgs::WorldControl & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::WorldControl & ign_msg, - ros_ign_interfaces::msg::WorldControl & ros_msg); +convert_gz_to_ros( + const ignition::msgs::WorldControl & gz_msg, + ros_gz_interfaces::msg::WorldControl & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::WorldReset & ros_msg, - ignition::msgs::WorldReset & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::WorldReset & ros_msg, + ignition::msgs::WorldReset & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::WorldReset & ign_msg, - ros_ign_interfaces::msg::WorldReset & ros_msg); -} // namespace ros_ign_bridge +convert_gz_to_ros( + const ignition::msgs::WorldReset & gz_msg, + ros_gz_interfaces::msg::WorldReset & ros_msg); +} // namespace ros_gz_bridge #endif // ROS_IGN_BRIDGE__CONVERT__ROS_IGN_INTERFACES_HPP_ diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/rosgraph_msgs.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/rosgraph_msgs.hpp index 1356a2644..0d6a99460 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert/rosgraph_msgs.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert/rosgraph_msgs.hpp @@ -21,7 +21,7 @@ // ROS 2 messages #include -#include +#include namespace ros_ign_bridge { diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/sensor_msgs.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/sensor_msgs.hpp index c24050048..4ab25330c 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert/sensor_msgs.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert/sensor_msgs.hpp @@ -37,7 +37,7 @@ #include #include -#include +#include namespace ros_ign_bridge { diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/std_msgs.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/std_msgs.hpp index 10ebeeb18..713fa76be 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert/std_msgs.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert/std_msgs.hpp @@ -37,7 +37,7 @@ #include #include -#include +#include namespace ros_ign_bridge { diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/tf2_msgs.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/tf2_msgs.hpp index b7052a9f5..5297485f2 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert/tf2_msgs.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert/tf2_msgs.hpp @@ -21,7 +21,7 @@ // ROS 2 messages #include -#include +#include namespace ros_ign_bridge { diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/trajectory_msgs.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/trajectory_msgs.hpp index 90a2edec8..791047910 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert/trajectory_msgs.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert/trajectory_msgs.hpp @@ -21,7 +21,7 @@ // ROS 2 messages #include -#include +#include namespace ros_ign_bridge { diff --git a/ros_gz_bridge/package.xml b/ros_gz_bridge/package.xml index 17cbe5ecb..246e694a4 100644 --- a/ros_gz_bridge/package.xml +++ b/ros_gz_bridge/package.xml @@ -1,7 +1,7 @@ - ros_ign_bridge + ros_gz_bridge 0.244.3 Bridge communication between ROS and Ignition Transport Louise Poubel @@ -16,7 +16,7 @@ geometry_msgs nav_msgs rclcpp - ros_ign_interfaces + ros_gz_interfaces rosgraph_msgs sensor_msgs std_msgs diff --git a/ros_gz_bridge/src/convert/builtin_interfaces.cpp b/ros_gz_bridge/src/convert/builtin_interfaces.cpp index 728c18475..2c0447493 100644 --- a/ros_gz_bridge/src/convert/builtin_interfaces.cpp +++ b/ros_gz_bridge/src/convert/builtin_interfaces.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ros_ign_bridge/convert/builtin_interfaces.hpp" +#include "ros_gz_bridge/convert/builtin_interfaces.hpp" namespace ros_ign_bridge { diff --git a/ros_gz_bridge/src/convert/geometry_msgs.cpp b/ros_gz_bridge/src/convert/geometry_msgs.cpp index 15bd0261e..0aec5aee6 100644 --- a/ros_gz_bridge/src/convert/geometry_msgs.cpp +++ b/ros_gz_bridge/src/convert/geometry_msgs.cpp @@ -13,7 +13,7 @@ // limitations under the License. #include "convert/utils.hpp" -#include "ros_ign_bridge/convert/geometry_msgs.hpp" +#include "ros_gz_bridge/convert/geometry_msgs.hpp" namespace ros_ign_bridge { diff --git a/ros_gz_bridge/src/convert/nav_msgs.cpp b/ros_gz_bridge/src/convert/nav_msgs.cpp index 297debe70..e50f0ee95 100644 --- a/ros_gz_bridge/src/convert/nav_msgs.cpp +++ b/ros_gz_bridge/src/convert/nav_msgs.cpp @@ -13,7 +13,7 @@ // limitations under the License. #include "convert/utils.hpp" -#include "ros_ign_bridge/convert/nav_msgs.hpp" +#include "ros_gz_bridge/convert/nav_msgs.hpp" namespace ros_ign_bridge { diff --git a/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp b/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp index 9b51ff029..26d31dd2f 100644 --- a/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp +++ b/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp @@ -12,16 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ros_ign_bridge/convert/ros_ign_interfaces.hpp" +#include "ros_gz_bridge/convert/ros_gz_interfaces.hpp" namespace ros_ign_bridge { template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::JointWrench & ros_msg, - ignition::msgs::JointWrench & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::JointWrench & ros_msg, + ignition::msgs::JointWrench & gz_msg) { convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); ign_msg.set_body_1_name(ros_msg.body_1_name.data); @@ -34,9 +34,9 @@ convert_ros_to_ign( template<> void -convert_ign_to_ros( - const ignition::msgs::JointWrench & ign_msg, - ros_ign_interfaces::msg::JointWrench & ros_msg) +convert_gz_to_ros( + const ignition::msgs::JointWrench & gz_msg, + ros_gz_interfaces::msg::JointWrench & ros_msg) { convert_ign_to_ros(ign_msg.header(), ros_msg.header); ros_msg.body_1_name.data = ign_msg.body_1_name(); @@ -49,36 +49,36 @@ convert_ign_to_ros( template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::Entity & ros_msg, - ignition::msgs::Entity & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::Entity & ros_msg, + ignition::msgs::Entity & gz_msg) { ign_msg.set_id(ros_msg.id); ign_msg.set_name(ros_msg.name); switch (ros_msg.type) { - case ros_ign_interfaces::msg::Entity::NONE: - ign_msg.set_type(ignition::msgs::Entity::NONE); + case ros_gz_interfaces::msg::Entity::NONE: + gz_msg.set_type(ignition::msgs::Entity::NONE); break; - case ros_ign_interfaces::msg::Entity::LIGHT: - ign_msg.set_type(ignition::msgs::Entity::LIGHT); + case ros_gz_interfaces::msg::Entity::LIGHT: + gz_msg.set_type(ignition::msgs::Entity::LIGHT); break; - case ros_ign_interfaces::msg::Entity::MODEL: - ign_msg.set_type(ignition::msgs::Entity::MODEL); + case ros_gz_interfaces::msg::Entity::MODEL: + gz_msg.set_type(ignition::msgs::Entity::MODEL); break; - case ros_ign_interfaces::msg::Entity::LINK: - ign_msg.set_type(ignition::msgs::Entity::LINK); + case ros_gz_interfaces::msg::Entity::LINK: + gz_msg.set_type(ignition::msgs::Entity::LINK); break; - case ros_ign_interfaces::msg::Entity::VISUAL: - ign_msg.set_type(ignition::msgs::Entity::VISUAL); + case ros_gz_interfaces::msg::Entity::VISUAL: + gz_msg.set_type(ignition::msgs::Entity::VISUAL); break; - case ros_ign_interfaces::msg::Entity::COLLISION: - ign_msg.set_type(ignition::msgs::Entity::COLLISION); + case ros_gz_interfaces::msg::Entity::COLLISION: + gz_msg.set_type(ignition::msgs::Entity::COLLISION); break; - case ros_ign_interfaces::msg::Entity::SENSOR: - ign_msg.set_type(ignition::msgs::Entity::SENSOR); + case ros_gz_interfaces::msg::Entity::SENSOR: + gz_msg.set_type(ignition::msgs::Entity::SENSOR); break; - case ros_ign_interfaces::msg::Entity::JOINT: - ign_msg.set_type(ignition::msgs::Entity::JOINT); + case ros_gz_interfaces::msg::Entity::JOINT: + gz_msg.set_type(ignition::msgs::Entity::JOINT); break; default: std::cerr << "Unsupported entity type [" << ros_msg.type << "]\n"; @@ -87,28 +87,28 @@ convert_ros_to_ign( template<> void -convert_ign_to_ros( - const ignition::msgs::Entity & ign_msg, - ros_ign_interfaces::msg::Entity & ros_msg) +convert_gz_to_ros( + const ignition::msgs::Entity & gz_msg, + ros_gz_interfaces::msg::Entity & ros_msg) { - ros_msg.id = ign_msg.id(); - ros_msg.name = ign_msg.name(); - if (ign_msg.type() == ignition::msgs::Entity::Type::Entity_Type_NONE) { - ros_msg.type = ros_ign_interfaces::msg::Entity::NONE; - } else if (ign_msg.type() == ignition::msgs::Entity::LIGHT) { - ros_msg.type = ros_ign_interfaces::msg::Entity::LIGHT; - } else if (ign_msg.type() == ignition::msgs::Entity::MODEL) { - ros_msg.type = ros_ign_interfaces::msg::Entity::MODEL; - } else if (ign_msg.type() == ignition::msgs::Entity::LINK) { - ros_msg.type = ros_ign_interfaces::msg::Entity::LINK; - } else if (ign_msg.type() == ignition::msgs::Entity::VISUAL) { - ros_msg.type = ros_ign_interfaces::msg::Entity::VISUAL; - } else if (ign_msg.type() == ignition::msgs::Entity::COLLISION) { - ros_msg.type = ros_ign_interfaces::msg::Entity::COLLISION; - } else if (ign_msg.type() == ignition::msgs::Entity::SENSOR) { - ros_msg.type = ros_ign_interfaces::msg::Entity::SENSOR; - } else if (ign_msg.type() == ignition::msgs::Entity::JOINT) { - ros_msg.type = ros_ign_interfaces::msg::Entity::JOINT; + ros_msg.id = gz_msg.id(); + ros_msg.name = gz_msg.name(); + if (gz_msg.type() == ignition::msgs::Entity::Type::Entity_Type_NONE) { + ros_msg.type = ros_gz_interfaces::msg::Entity::NONE; + } else if (gz_msg.type() == ignition::msgs::Entity::LIGHT) { + ros_msg.type = ros_gz_interfaces::msg::Entity::LIGHT; + } else if (gz_msg.type() == ignition::msgs::Entity::MODEL) { + ros_msg.type = ros_gz_interfaces::msg::Entity::MODEL; + } else if (gz_msg.type() == ignition::msgs::Entity::LINK) { + ros_msg.type = ros_gz_interfaces::msg::Entity::LINK; + } else if (gz_msg.type() == ignition::msgs::Entity::VISUAL) { + ros_msg.type = ros_gz_interfaces::msg::Entity::VISUAL; + } else if (gz_msg.type() == ignition::msgs::Entity::COLLISION) { + ros_msg.type = ros_gz_interfaces::msg::Entity::COLLISION; + } else if (gz_msg.type() == ignition::msgs::Entity::SENSOR) { + ros_msg.type = ros_gz_interfaces::msg::Entity::SENSOR; + } else if (gz_msg.type() == ignition::msgs::Entity::JOINT) { + ros_msg.type = ros_gz_interfaces::msg::Entity::JOINT; } else { std::cerr << "Unsupported Entity [" << ign_msg.type() << "]" << std::endl; @@ -117,9 +117,9 @@ convert_ign_to_ros( template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::Contact & ros_msg, - ignition::msgs::Contact & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::Contact & ros_msg, + ignition::msgs::Contact & gz_msg) { convert_ros_to_ign(ros_msg.collision1, (*ign_msg.mutable_collision1())); convert_ros_to_ign(ros_msg.collision1, (*ign_msg.mutable_collision2())); @@ -145,9 +145,9 @@ convert_ros_to_ign( template<> void -convert_ign_to_ros( - const ignition::msgs::Contact & ign_msg, - ros_ign_interfaces::msg::Contact & ros_msg) +convert_gz_to_ros( + const ignition::msgs::Contact & gz_msg, + ros_gz_interfaces::msg::Contact & ros_msg) { convert_ign_to_ros(ign_msg.collision1(), ros_msg.collision1); convert_ign_to_ros(ign_msg.collision2(), ros_msg.collision2); @@ -164,18 +164,18 @@ convert_ign_to_ros( for (auto i = 0; i < ign_msg.depth_size(); ++i) { ros_msg.depths.push_back(ign_msg.depth(i)); } - for (auto i = 0; i < ign_msg.wrench_size(); ++i) { - ros_ign_interfaces::msg::JointWrench ros_joint_wrench; - convert_ign_to_ros(ign_msg.wrench(i), ros_joint_wrench); + for (auto i = 0; i < gz_msg.wrench_size(); ++i) { + ros_gz_interfaces::msg::JointWrench ros_joint_wrench; + convert_gz_to_ros(gz_msg.wrench(i), ros_joint_wrench); ros_msg.wrenches.push_back(ros_joint_wrench); } } template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::Contacts & ros_msg, - ignition::msgs::Contacts & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::Contacts & ros_msg, + ignition::msgs::Contacts & gz_msg) { convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); ign_msg.clear_contact(); @@ -187,23 +187,23 @@ convert_ros_to_ign( template<> void -convert_ign_to_ros( - const ignition::msgs::Contacts & ign_msg, - ros_ign_interfaces::msg::Contacts & ros_msg) +convert_gz_to_ros( + const ignition::msgs::Contacts & gz_msg, + ros_gz_interfaces::msg::Contacts & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); - for (auto i = 0; i < ign_msg.contact_size(); ++i) { - ros_ign_interfaces::msg::Contact ros_contact; - convert_ign_to_ros(ign_msg.contact(i), ros_contact); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); + for (auto i = 0; i < gz_msg.contact_size(); ++i) { + ros_gz_interfaces::msg::Contact ros_contact; + convert_gz_to_ros(gz_msg.contact(i), ros_contact); ros_msg.contacts.push_back(ros_contact); } } template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::GuiCamera & ros_msg, - ignition::msgs::GUICamera & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::GuiCamera & ros_msg, + ignition::msgs::GUICamera & gz_msg) { convert_ros_to_ign(ros_msg.header, *ign_msg.mutable_header()); ign_msg.set_name(ros_msg.name); @@ -215,9 +215,9 @@ convert_ros_to_ign( template<> void -convert_ign_to_ros( - const ignition::msgs::GUICamera & ign_msg, - ros_ign_interfaces::msg::GuiCamera & ros_msg) +convert_gz_to_ros( + const ignition::msgs::GUICamera & gz_msg, + ros_gz_interfaces::msg::GuiCamera & ros_msg) { convert_ign_to_ros(ign_msg.header(), ros_msg.header); ros_msg.name = ign_msg.name(); @@ -229,9 +229,9 @@ convert_ign_to_ros( template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::Light & ros_msg, - ignition::msgs::Light & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::Light & ros_msg, + ignition::msgs::Light & gz_msg) { convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); @@ -267,9 +267,9 @@ convert_ros_to_ign( template<> void -convert_ign_to_ros( - const ignition::msgs::Light & ign_msg, - ros_ign_interfaces::msg::Light & ros_msg) +convert_gz_to_ros( + const ignition::msgs::Light & gz_msg, + ros_gz_interfaces::msg::Light & ros_msg) { convert_ign_to_ros(ign_msg.header(), ros_msg.header); @@ -306,9 +306,9 @@ convert_ign_to_ros( template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::StringVec & ros_msg, - ignition::msgs::StringMsg_V & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::StringVec & ros_msg, + ignition::msgs::StringMsg_V & gz_msg) { convert_ros_to_ign(ros_msg.header, *ign_msg.mutable_header()); for (const auto & elem : ros_msg.data) { @@ -319,9 +319,9 @@ convert_ros_to_ign( template<> void -convert_ign_to_ros( - const ignition::msgs::StringMsg_V & ign_msg, - ros_ign_interfaces::msg::StringVec & ros_msg) +convert_gz_to_ros( + const ignition::msgs::StringMsg_V & gz_msg, + ros_gz_interfaces::msg::StringVec & ros_msg) { convert_ign_to_ros(ign_msg.header(), ros_msg.header); for (const auto & elem : ign_msg.data()) { @@ -331,9 +331,9 @@ convert_ign_to_ros( template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::TrackVisual & ros_msg, - ignition::msgs::TrackVisual & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::TrackVisual & ros_msg, + ignition::msgs::TrackVisual & gz_msg) { convert_ros_to_ign(ros_msg.header, *ign_msg.mutable_header()); ign_msg.set_name(ros_msg.name); @@ -349,9 +349,9 @@ convert_ros_to_ign( template<> void -convert_ign_to_ros( - const ignition::msgs::TrackVisual & ign_msg, - ros_ign_interfaces::msg::TrackVisual & ros_msg) +convert_gz_to_ros( + const ignition::msgs::TrackVisual & gz_msg, + ros_gz_interfaces::msg::TrackVisual & ros_msg) { convert_ign_to_ros(ign_msg.header(), ros_msg.header); ros_msg.name = ign_msg.name(); @@ -367,9 +367,9 @@ convert_ign_to_ros( template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::VideoRecord & ros_msg, - ignition::msgs::VideoRecord & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::VideoRecord & ros_msg, + ignition::msgs::VideoRecord & gz_msg) { convert_ros_to_ign(ros_msg.header, *ign_msg.mutable_header()); ign_msg.set_start(ros_msg.start); @@ -380,9 +380,9 @@ convert_ros_to_ign( template<> void -convert_ign_to_ros( - const ignition::msgs::VideoRecord & ign_msg, - ros_ign_interfaces::msg::VideoRecord & ros_msg) +convert_gz_to_ros( + const ignition::msgs::VideoRecord & gz_msg, + ros_gz_interfaces::msg::VideoRecord & ros_msg) { convert_ign_to_ros(ign_msg.header(), ros_msg.header); ros_msg.start = ign_msg.start(); @@ -393,9 +393,9 @@ convert_ign_to_ros( template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::WorldControl & ros_msg, - ignition::msgs::WorldControl & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::WorldControl & ros_msg, + ignition::msgs::WorldControl & gz_msg) { ign_msg.set_pause(ros_msg.pause); ign_msg.set_step(ros_msg.step); @@ -407,9 +407,9 @@ convert_ros_to_ign( template<> void -convert_ign_to_ros( - const ignition::msgs::WorldControl & ign_msg, - ros_ign_interfaces::msg::WorldControl & ros_msg) +convert_gz_to_ros( + const ignition::msgs::WorldControl & gz_msg, + ros_gz_interfaces::msg::WorldControl & ros_msg) { ros_msg.pause = ign_msg.pause(); ros_msg.step = ign_msg.step(); @@ -421,9 +421,9 @@ convert_ign_to_ros( template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::WorldReset & ros_msg, - ignition::msgs::WorldReset & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::WorldReset & ros_msg, + ignition::msgs::WorldReset & gz_msg) { ign_msg.set_all(ros_msg.all); ign_msg.set_time_only(ros_msg.time_only); @@ -432,9 +432,9 @@ convert_ros_to_ign( template<> void -convert_ign_to_ros( - const ignition::msgs::WorldReset & ign_msg, - ros_ign_interfaces::msg::WorldReset & ros_msg) +convert_gz_to_ros( + const ignition::msgs::WorldReset & gz_msg, + ros_gz_interfaces::msg::WorldReset & ros_msg) { ros_msg.all = ign_msg.all(); ros_msg.time_only = ign_msg.time_only(); diff --git a/ros_gz_bridge/src/convert/rosgraph_msgs.cpp b/ros_gz_bridge/src/convert/rosgraph_msgs.cpp index f73aa3427..740989ff4 100644 --- a/ros_gz_bridge/src/convert/rosgraph_msgs.cpp +++ b/ros_gz_bridge/src/convert/rosgraph_msgs.cpp @@ -15,7 +15,7 @@ #include #include "convert/utils.hpp" -#include "ros_ign_bridge/convert/rosgraph_msgs.hpp" +#include "ros_gz_bridge/convert/rosgraph_msgs.hpp" namespace ros_ign_bridge { diff --git a/ros_gz_bridge/src/convert/sensor_msgs.cpp b/ros_gz_bridge/src/convert/sensor_msgs.cpp index 3da2265d3..daaa365e7 100644 --- a/ros_gz_bridge/src/convert/sensor_msgs.cpp +++ b/ros_gz_bridge/src/convert/sensor_msgs.cpp @@ -15,7 +15,7 @@ #include #include "convert/utils.hpp" -#include "ros_ign_bridge/convert/sensor_msgs.hpp" +#include "ros_gz_bridge/convert/sensor_msgs.hpp" namespace ros_ign_bridge { diff --git a/ros_gz_bridge/src/convert/std_msgs.cpp b/ros_gz_bridge/src/convert/std_msgs.cpp index 08923ea66..17a33692b 100644 --- a/ros_gz_bridge/src/convert/std_msgs.cpp +++ b/ros_gz_bridge/src/convert/std_msgs.cpp @@ -13,8 +13,8 @@ // limitations under the License. #include "convert/utils.hpp" -#include "ros_ign_bridge/convert/builtin_interfaces.hpp" -#include "ros_ign_bridge/convert/std_msgs.hpp" +#include "ros_gz_bridge/convert/builtin_interfaces.hpp" +#include "ros_gz_bridge/convert/std_msgs.hpp" namespace ros_ign_bridge { diff --git a/ros_gz_bridge/src/convert/tf2_msgs.cpp b/ros_gz_bridge/src/convert/tf2_msgs.cpp index 27992fd92..585748f28 100644 --- a/ros_gz_bridge/src/convert/tf2_msgs.cpp +++ b/ros_gz_bridge/src/convert/tf2_msgs.cpp @@ -13,7 +13,7 @@ // limitations under the License. #include "convert/utils.hpp" -#include "ros_ign_bridge/convert/tf2_msgs.hpp" +#include "ros_gz_bridge/convert/tf2_msgs.hpp" namespace ros_ign_bridge { diff --git a/ros_gz_bridge/src/convert/trajectory_msgs.cpp b/ros_gz_bridge/src/convert/trajectory_msgs.cpp index 9c24cf3fd..7b040d49b 100644 --- a/ros_gz_bridge/src/convert/trajectory_msgs.cpp +++ b/ros_gz_bridge/src/convert/trajectory_msgs.cpp @@ -15,7 +15,7 @@ #include #include "convert/utils.hpp" -#include "ros_ign_bridge/convert/trajectory_msgs.hpp" +#include "ros_gz_bridge/convert/trajectory_msgs.hpp" namespace ros_ign_bridge { diff --git a/ros_gz_bridge/src/factories.cpp b/ros_gz_bridge/src/factories.cpp index 210c58241..813aa7f34 100644 --- a/ros_gz_bridge/src/factories.cpp +++ b/ros_gz_bridge/src/factories.cpp @@ -20,14 +20,14 @@ #include "factories/builtin_interfaces.hpp" #include "factories/geometry_msgs.hpp" #include "factories/nav_msgs.hpp" -#include "factories/ros_ign_interfaces.hpp" +#include "factories/ros_gz_interfaces.hpp" #include "factories/rosgraph_msgs.hpp" #include "factories/sensor_msgs.hpp" #include "factories/std_msgs.hpp" #include "factories/tf2_msgs.hpp" #include "factories/trajectory_msgs.hpp" -#include "service_factories/ros_ign_interfaces.hpp" +#include "service_factories/ros_gz_interfaces.hpp" namespace ros_ign_bridge { @@ -50,7 +50,7 @@ get_factory_impl( impl = get_factory__nav_msgs(ros_type_name, ign_type_name); if (impl) {return impl;} - impl = get_factory__ros_ign_interfaces(ros_type_name, ign_type_name); + impl = get_factory__ros_gz_interfaces(ros_type_name, gz_type_name); if (impl) {return impl;} impl = get_factory__rosgraph_msgs(ros_type_name, ign_type_name); @@ -90,8 +90,8 @@ get_service_factory( { std::shared_ptr impl; - impl = get_service_factory__ros_ign_interfaces( - ros_type_name, ign_req_type_name, ign_rep_type_name); + impl = get_service_factory__ros_gz_interfaces( + ros_type_name, gz_req_type_name, gz_rep_type_name); if (impl) {return impl;} std::ostringstream oss{"No template specialization for the specified service type {"}; diff --git a/ros_gz_bridge/src/factories/builtin_interfaces.cpp b/ros_gz_bridge/src/factories/builtin_interfaces.cpp index 20336cfa7..a5198b2b6 100644 --- a/ros_gz_bridge/src/factories/builtin_interfaces.cpp +++ b/ros_gz_bridge/src/factories/builtin_interfaces.cpp @@ -18,7 +18,7 @@ #include #include "factory.hpp" -#include "ros_ign_bridge/convert/builtin_interfaces.hpp" +#include "ros_gz_bridge/convert/builtin_interfaces.hpp" namespace ros_ign_bridge { diff --git a/ros_gz_bridge/src/factories/geometry_msgs.cpp b/ros_gz_bridge/src/factories/geometry_msgs.cpp index 48d7887aa..4076404b9 100644 --- a/ros_gz_bridge/src/factories/geometry_msgs.cpp +++ b/ros_gz_bridge/src/factories/geometry_msgs.cpp @@ -18,7 +18,7 @@ #include #include "factory.hpp" -#include "ros_ign_bridge/convert/geometry_msgs.hpp" +#include "ros_gz_bridge/convert/geometry_msgs.hpp" namespace ros_ign_bridge { diff --git a/ros_gz_bridge/src/factories/nav_msgs.cpp b/ros_gz_bridge/src/factories/nav_msgs.cpp index f6845c8df..eb01c2e53 100644 --- a/ros_gz_bridge/src/factories/nav_msgs.cpp +++ b/ros_gz_bridge/src/factories/nav_msgs.cpp @@ -18,7 +18,7 @@ #include #include "factory.hpp" -#include "ros_ign_bridge/convert/nav_msgs.hpp" +#include "ros_gz_bridge/convert/nav_msgs.hpp" namespace ros_ign_bridge { diff --git a/ros_gz_bridge/src/factories/ros_gz_interfaces.cpp b/ros_gz_bridge/src/factories/ros_gz_interfaces.cpp index 628938927..fca7c67b7 100644 --- a/ros_gz_bridge/src/factories/ros_gz_interfaces.cpp +++ b/ros_gz_bridge/src/factories/ros_gz_interfaces.cpp @@ -12,125 +12,121 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "factories/ros_ign_interfaces.hpp" +#include "factories/ros_gz_interfaces.hpp" #include #include #include "factory.hpp" -#include "ros_ign_bridge/convert/ros_ign_interfaces.hpp" +#include "ros_gz_bridge/convert/ros_gz_interfaces.hpp" namespace ros_ign_bridge { std::shared_ptr -get_factory__ros_ign_interfaces( +get_factory__ros_gz_interfaces( const std::string & ros_type_name, const std::string & ign_type_name) { - if ( - (ros_type_name == "ros_ign_interfaces/msg/JointWrench" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.JointWrench") + if ((ros_type_name == "ros_gz_interfaces/msg/JointWrench" || ros_type_name.empty()) + && (gz_type_name == "gz.msgs.JointWrench" || gz_type_name == "ignition.msgs.JointWrench")) { return std::make_shared< Factory< - ros_ign_interfaces::msg::JointWrench, + ros_gz_interfaces::msg::JointWrench, ignition::msgs::JointWrench > - >("ros_ign_interfaces/msg/JointWrench", ign_type_name); + >("ros_gz_interfaces/msg/JointWrench", gz_type_name); } - if ( - (ros_type_name == "ros_ign_interfaces/msg/Entity" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Entity") + if ((ros_type_name == "ros_gz_interfaces/msg/Entity" || ros_type_name.empty()) + && (gz_type_name == "gz.msgs.Entity" || gz_type_name == "ignition.msgs.Entity")) { return std::make_shared< Factory< - ros_ign_interfaces::msg::Entity, + ros_gz_interfaces::msg::Entity, ignition::msgs::Entity > - >("ros_ign_interfaces/msg/Entity", ign_type_name); + >("ros_gz_interfaces/msg/Entity", gz_type_name); } - if ( - (ros_type_name == "ros_ign_interfaces/msg/Contact" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Contact") + if ((ros_type_name == "ros_gz_interfaces/msg/Contact" || ros_type_name.empty()) + && (gz_type_name == "gz.msgs.Contact" || gz_type_name == "ignition.msgs.Contact")) { return std::make_shared< Factory< - ros_ign_interfaces::msg::Contact, + ros_gz_interfaces::msg::Contact, ignition::msgs::Contact > - >("ros_ign_interfaces/msg/Contact", ign_type_name); + >("ros_gz_interfaces/msg/Contact", gz_type_name); } - if ( - (ros_type_name == "ros_ign_interfaces/msg/Contacts" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Contacts") + if ((ros_type_name == "ros_gz_interfaces/msg/Contacts" || ros_type_name.empty()) + && (gz_type_name == "gz.msgs.Contacts" || gz_type_name == "ignition.msgs.Contacts")) { return std::make_shared< Factory< - ros_ign_interfaces::msg::Contacts, + ros_gz_interfaces::msg::Contacts, ignition::msgs::Contacts > - >("ros_ign_interfaces/msg/Contacts", ign_type_name); + >("ros_gz_interfaces/msg/Contacts", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/GuiCamera" || - ros_type_name.empty()) && ign_type_name == "ignition.msgs.GUICamera") + if ((ros_type_name == "ros_gz_interfaces/msg/GuiCamera" || ros_type_name.empty()) + && (gz_type_name == "gz.msgs.GUICamera" || gz_type_name == "ignition.msgs.GUICamera")) { return std::make_shared< Factory< - ros_ign_interfaces::msg::GuiCamera, + ros_gz_interfaces::msg::GuiCamera, ignition::msgs::GUICamera > - >("ros_ign_interfaces/msg/GuiCamera", ign_type_name); + >("ros_gz_interfaces/msg/GuiCamera", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/Light" || - ros_type_name.empty()) && ign_type_name == "ignition.msgs.Light") + if ((ros_type_name == "ros_gz_interfaces/msg/Light" || ros_type_name.empty()) + && (gz_type_name == "gz.msgs.Light" || gz_type_name == "ignition.msgs.Light")) { return std::make_shared< Factory< - ros_ign_interfaces::msg::Light, + ros_gz_interfaces::msg::Light, ignition::msgs::Light > - >("ros_ign_interfaces/msg/Light", ign_type_name); + >("ros_gz_interfaces/msg/Light", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/StringVec" || - ros_type_name.empty()) && ign_type_name == "ignition.msgs.StringMsg_V") + if ((ros_type_name == "ros_gz_interfaces/msg/StringVec" || ros_type_name.empty()) + && (gz_type_name == "gz.msgs.StringMsg_V" || gz_type_name == "ignition.msgs.StringMsg_V")) { return std::make_shared< Factory< - ros_ign_interfaces::msg::StringVec, + ros_gz_interfaces::msg::StringVec, ignition::msgs::StringMsg_V > - >("ros_ign_interfaces/msg/StringVec", ign_type_name); + >("ros_gz_interfaces/msg/StringVec", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/TrackVisual" || - ros_type_name.empty()) && ign_type_name == "ignition.msgs.TrackVisual") + if ((ros_type_name == "ros_gz_interfaces/msg/TrackVisual" || ros_type_name.empty()) + && (gz_type_name == "gz.msgs.TrackVisual" || gz_type_name == "ignition.msgs.TrackVisual")) { return std::make_shared< Factory< - ros_ign_interfaces::msg::TrackVisual, + ros_gz_interfaces::msg::TrackVisual, ignition::msgs::TrackVisual > - >("ros_ign_interfaces/msg/TrackVisual", ign_type_name); + >("ros_gz_interfaces/msg/TrackVisual", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/VideoRecord" || - ros_type_name.empty()) && ign_type_name == "ignition.msgs.VideoRecord") + if ((ros_type_name == "ros_gz_interfaces/msg/VideoRecord" || ros_type_name.empty()) + && (gz_type_name == "gz.msgs.VideoRecord" || gz_type_name == "ignition.msgs.VideoRecord")) { return std::make_shared< Factory< - ros_ign_interfaces::msg::VideoRecord, + ros_gz_interfaces::msg::VideoRecord, ignition::msgs::VideoRecord > - >("ros_ign_interfaces/msg/VideoRecord", ign_type_name); + >("ros_gz_interfaces/msg/VideoRecord", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/WorldControl" || - ros_type_name.empty()) && ign_type_name == "ignition.msgs.WorldControl") + if ((ros_type_name == "ros_gz_interfaces/msg/WorldControl" || ros_type_name.empty()) + && (gz_type_name == "gz.msgs.WorldControl" || gz_type_name == "ignition.msgs.WorldControl")) { return std::make_shared< Factory< - ros_ign_interfaces::msg::WorldControl, + ros_gz_interfaces::msg::WorldControl, ignition::msgs::WorldControl > - >("ros_ign_interfaces/msg/WorldControl", ign_type_name); + >("ros_gz_interfaces/msg/WorldControl", gz_type_name); } return nullptr; } @@ -138,11 +134,11 @@ get_factory__ros_ign_interfaces( template<> void Factory< - ros_ign_interfaces::msg::JointWrench, + ros_gz_interfaces::msg::JointWrench, ignition::msgs::JointWrench ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::JointWrench & ros_msg, - ignition::msgs::JointWrench & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::JointWrench & ros_msg, + ignition::msgs::JointWrench & gz_msg) { ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); } @@ -150,11 +146,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::JointWrench, + ros_gz_interfaces::msg::JointWrench, ignition::msgs::JointWrench ->::convert_ign_to_ros( - const ignition::msgs::JointWrench & ign_msg, - ros_ign_interfaces::msg::JointWrench & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::JointWrench & gz_msg, + ros_gz_interfaces::msg::JointWrench & ros_msg) { ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); } @@ -162,11 +158,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::Entity, + ros_gz_interfaces::msg::Entity, ignition::msgs::Entity ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::Entity & ros_msg, - ignition::msgs::Entity & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::Entity & ros_msg, + ignition::msgs::Entity & gz_msg) { ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); } @@ -174,11 +170,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::Entity, + ros_gz_interfaces::msg::Entity, ignition::msgs::Entity ->::convert_ign_to_ros( - const ignition::msgs::Entity & ign_msg, - ros_ign_interfaces::msg::Entity & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::Entity & gz_msg, + ros_gz_interfaces::msg::Entity & ros_msg) { ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); } @@ -186,11 +182,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::Contact, + ros_gz_interfaces::msg::Contact, ignition::msgs::Contact ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::Contact & ros_msg, - ignition::msgs::Contact & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::Contact & ros_msg, + ignition::msgs::Contact & gz_msg) { ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); } @@ -198,11 +194,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::Contact, + ros_gz_interfaces::msg::Contact, ignition::msgs::Contact ->::convert_ign_to_ros( - const ignition::msgs::Contact & ign_msg, - ros_ign_interfaces::msg::Contact & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::Contact & gz_msg, + ros_gz_interfaces::msg::Contact & ros_msg) { ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); } @@ -210,11 +206,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::Contacts, + ros_gz_interfaces::msg::Contacts, ignition::msgs::Contacts ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::Contacts & ros_msg, - ignition::msgs::Contacts & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::Contacts & ros_msg, + ignition::msgs::Contacts & gz_msg) { ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); } @@ -222,11 +218,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::Contacts, + ros_gz_interfaces::msg::Contacts, ignition::msgs::Contacts ->::convert_ign_to_ros( - const ignition::msgs::Contacts & ign_msg, - ros_ign_interfaces::msg::Contacts & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::Contacts & gz_msg, + ros_gz_interfaces::msg::Contacts & ros_msg) { ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); } @@ -234,11 +230,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::GuiCamera, + ros_gz_interfaces::msg::GuiCamera, ignition::msgs::GUICamera ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::GuiCamera & ros_msg, - ignition::msgs::GUICamera & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::GuiCamera & ros_msg, + ignition::msgs::GUICamera & gz_msg) { ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); } @@ -246,11 +242,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::GuiCamera, + ros_gz_interfaces::msg::GuiCamera, ignition::msgs::GUICamera ->::convert_ign_to_ros( - const ignition::msgs::GUICamera & ign_msg, - ros_ign_interfaces::msg::GuiCamera & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::GUICamera & gz_msg, + ros_gz_interfaces::msg::GuiCamera & ros_msg) { ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); } @@ -258,11 +254,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::Light, + ros_gz_interfaces::msg::Light, ignition::msgs::Light ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::Light & ros_msg, - ignition::msgs::Light & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::Light & ros_msg, + ignition::msgs::Light & gz_msg) { ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); } @@ -270,11 +266,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::Light, + ros_gz_interfaces::msg::Light, ignition::msgs::Light ->::convert_ign_to_ros( - const ignition::msgs::Light & ign_msg, - ros_ign_interfaces::msg::Light & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::Light & gz_msg, + ros_gz_interfaces::msg::Light & ros_msg) { ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); } @@ -282,11 +278,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::StringVec, + ros_gz_interfaces::msg::StringVec, ignition::msgs::StringMsg_V ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::StringVec & ros_msg, - ignition::msgs::StringMsg_V & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::StringVec & ros_msg, + ignition::msgs::StringMsg_V & gz_msg) { ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); } @@ -294,11 +290,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::StringVec, + ros_gz_interfaces::msg::StringVec, ignition::msgs::StringMsg_V ->::convert_ign_to_ros( - const ignition::msgs::StringMsg_V & ign_msg, - ros_ign_interfaces::msg::StringVec & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::StringMsg_V & gz_msg, + ros_gz_interfaces::msg::StringVec & ros_msg) { ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); } @@ -306,11 +302,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::TrackVisual, + ros_gz_interfaces::msg::TrackVisual, ignition::msgs::TrackVisual ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::TrackVisual & ros_msg, - ignition::msgs::TrackVisual & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::TrackVisual & ros_msg, + ignition::msgs::TrackVisual & gz_msg) { ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); } @@ -318,11 +314,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::TrackVisual, + ros_gz_interfaces::msg::TrackVisual, ignition::msgs::TrackVisual ->::convert_ign_to_ros( - const ignition::msgs::TrackVisual & ign_msg, - ros_ign_interfaces::msg::TrackVisual & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::TrackVisual & gz_msg, + ros_gz_interfaces::msg::TrackVisual & ros_msg) { ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); } @@ -330,11 +326,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::VideoRecord, + ros_gz_interfaces::msg::VideoRecord, ignition::msgs::VideoRecord ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::VideoRecord & ros_msg, - ignition::msgs::VideoRecord & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::VideoRecord & ros_msg, + ignition::msgs::VideoRecord & gz_msg) { ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); } @@ -342,11 +338,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::VideoRecord, + ros_gz_interfaces::msg::VideoRecord, ignition::msgs::VideoRecord ->::convert_ign_to_ros( - const ignition::msgs::VideoRecord & ign_msg, - ros_ign_interfaces::msg::VideoRecord & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::VideoRecord & gz_msg, + ros_gz_interfaces::msg::VideoRecord & ros_msg) { ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); } @@ -354,11 +350,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::WorldControl, + ros_gz_interfaces::msg::WorldControl, ignition::msgs::WorldControl ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::WorldControl & ros_msg, - ignition::msgs::WorldControl & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::WorldControl & ros_msg, + ignition::msgs::WorldControl & gz_msg) { ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); } @@ -366,11 +362,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::WorldControl, + ros_gz_interfaces::msg::WorldControl, ignition::msgs::WorldControl ->::convert_ign_to_ros( - const ignition::msgs::WorldControl & ign_msg, - ros_ign_interfaces::msg::WorldControl & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::WorldControl & gz_msg, + ros_gz_interfaces::msg::WorldControl & ros_msg) { ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); } diff --git a/ros_gz_bridge/src/factories/ros_gz_interfaces.hpp b/ros_gz_bridge/src/factories/ros_gz_interfaces.hpp index 865936196..b5e0e5bef 100644 --- a/ros_gz_bridge/src/factories/ros_gz_interfaces.hpp +++ b/ros_gz_bridge/src/factories/ros_gz_interfaces.hpp @@ -24,7 +24,7 @@ namespace ros_ign_bridge { std::shared_ptr -get_factory__ros_ign_interfaces( +get_factory__ros_gz_interfaces( const std::string & ros_type_name, const std::string & ign_type_name); diff --git a/ros_gz_bridge/src/factories/rosgraph_msgs.cpp b/ros_gz_bridge/src/factories/rosgraph_msgs.cpp index 2cb6d2606..51110db8f 100644 --- a/ros_gz_bridge/src/factories/rosgraph_msgs.cpp +++ b/ros_gz_bridge/src/factories/rosgraph_msgs.cpp @@ -18,7 +18,7 @@ #include #include "factory.hpp" -#include "ros_ign_bridge/convert/rosgraph_msgs.hpp" +#include "ros_gz_bridge/convert/rosgraph_msgs.hpp" namespace ros_ign_bridge { diff --git a/ros_gz_bridge/src/factories/sensor_msgs.cpp b/ros_gz_bridge/src/factories/sensor_msgs.cpp index 36c236d45..57ad067d9 100644 --- a/ros_gz_bridge/src/factories/sensor_msgs.cpp +++ b/ros_gz_bridge/src/factories/sensor_msgs.cpp @@ -18,7 +18,7 @@ #include #include "factory.hpp" -#include "ros_ign_bridge/convert/sensor_msgs.hpp" +#include "ros_gz_bridge/convert/sensor_msgs.hpp" namespace ros_ign_bridge { diff --git a/ros_gz_bridge/src/factories/std_msgs.cpp b/ros_gz_bridge/src/factories/std_msgs.cpp index 0ce63c6ba..5d070fb9c 100644 --- a/ros_gz_bridge/src/factories/std_msgs.cpp +++ b/ros_gz_bridge/src/factories/std_msgs.cpp @@ -18,7 +18,7 @@ #include #include "factory.hpp" -#include "ros_ign_bridge/convert/std_msgs.hpp" +#include "ros_gz_bridge/convert/std_msgs.hpp" namespace ros_ign_bridge { diff --git a/ros_gz_bridge/src/factories/tf2_msgs.cpp b/ros_gz_bridge/src/factories/tf2_msgs.cpp index bdd70f9c3..a4a109300 100644 --- a/ros_gz_bridge/src/factories/tf2_msgs.cpp +++ b/ros_gz_bridge/src/factories/tf2_msgs.cpp @@ -18,7 +18,7 @@ #include #include "factory.hpp" -#include "ros_ign_bridge/convert/tf2_msgs.hpp" +#include "ros_gz_bridge/convert/tf2_msgs.hpp" namespace ros_ign_bridge { diff --git a/ros_gz_bridge/src/factories/trajectory_msgs.cpp b/ros_gz_bridge/src/factories/trajectory_msgs.cpp index f502cc4a3..7c239f87a 100644 --- a/ros_gz_bridge/src/factories/trajectory_msgs.cpp +++ b/ros_gz_bridge/src/factories/trajectory_msgs.cpp @@ -18,7 +18,7 @@ #include #include "factory.hpp" -#include "ros_ign_bridge/convert/trajectory_msgs.hpp" +#include "ros_gz_bridge/convert/trajectory_msgs.hpp" namespace ros_ign_bridge { diff --git a/ros_gz_bridge/src/parameter_bridge.cpp b/ros_gz_bridge/src/parameter_bridge.cpp index 3ceb19f6a..cfa04e4a1 100644 --- a/ros_gz_bridge/src/parameter_bridge.cpp +++ b/ros_gz_bridge/src/parameter_bridge.cpp @@ -70,9 +70,9 @@ void usage() " parameter_bridge /chatter@std_msgs/String]ignition.msgs" << ".StringMsg\n" << "A service bridge:\n" << - " parameter_bridge /world/default/control@ros_ign_interfaces/srv/ControlWorld\n" << + " parameter_bridge /world/default/control@ros_gz_interfaces/srv/ControlWorld\n" << "Or equivalently:\n" << - " parameter_bridge /world/default/control@ros_ign_interfaces/srv/ControlWorld@" + " parameter_bridge /world/default/control@ros_gz_interfaces/srv/ControlWorld@" "ignition.msgs.WorldControl@ignition.msgs.Boolean\n" << std::endl; } diff --git a/ros_gz_bridge/src/service_factories/ros_gz_interfaces.cpp b/ros_gz_bridge/src/service_factories/ros_gz_interfaces.cpp index 70f9e7888..90cc98a99 100644 --- a/ros_gz_bridge/src/service_factories/ros_gz_interfaces.cpp +++ b/ros_gz_bridge/src/service_factories/ros_gz_interfaces.cpp @@ -12,62 +12,78 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "factories/ros_ign_interfaces.hpp" +#include "factories/ros_gz_interfaces.hpp" #include #include -#include "ros_ign_interfaces/srv/control_world.hpp" +#include "ros_gz_interfaces/srv/control_world.hpp" #include "service_factory.hpp" -#include "ros_ign_bridge/convert/ros_ign_interfaces.hpp" +#include "ros_gz_bridge/convert/ros_gz_interfaces.hpp" namespace ros_ign_bridge { std::shared_ptr -get_service_factory__ros_ign_interfaces( +get_service_factory__ros_gz_interfaces( const std::string & ros_type_name, const std::string & ign_req_type_name, const std::string & ign_rep_type_name) { if ( - ros_type_name == "ros_ign_interfaces/srv/ControlWorld" && - (ign_req_type_name.empty() || ign_req_type_name == "ignition.msgs.WorldControl") && - (ign_rep_type_name.empty() || ign_rep_type_name == "ignition.msgs.Boolean")) + ros_type_name == "ros_gz_interfaces/srv/ControlWorld" && + (gz_req_type_name.empty() || gz_req_type_name == "ignition.msgs.WorldControl") && + (gz_rep_type_name.empty() || gz_rep_type_name == "ignition.msgs.Boolean")) { return std::make_shared< ServiceFactory< - ros_ign_interfaces::srv::ControlWorld, + ros_gz_interfaces::srv::ControlWorld, ignition::msgs::WorldControl, ignition::msgs::Boolean> >(ros_type_name, "ignition.msgs.WorldControl", "ignition.msgs.Boolean"); } + + // NOTE(CH3): Prioritising ignition since versions prior to Garden cannot support gz + + if ( + ros_type_name == "ros_gz_interfaces/srv/ControlWorld" && + (gz_req_type_name.empty() || gz_req_type_name == "gz.msgs.WorldControl") && + (gz_rep_type_name.empty() || gz_rep_type_name == "gz.msgs.Boolean")) + { + return std::make_shared< + ServiceFactory< + ros_gz_interfaces::srv::ControlWorld, + ignition::msgs::WorldControl, + ignition::msgs::Boolean> + >(ros_type_name, "gz.msgs.WorldControl", "gz.msgs.Boolean"); + } + return nullptr; } template<> void -convert_ros_to_ign( - const ros_ign_interfaces::srv::ControlWorld::Request & ros_req, - ignition::msgs::WorldControl & ign_req) +convert_ros_to_gz( + const ros_gz_interfaces::srv::ControlWorld::Request & ros_req, + ignition::msgs::WorldControl & gz_req) { convert_ros_to_ign(ros_req.world_control, ign_req); } template<> void -convert_ign_to_ros( - const ignition::msgs::Boolean & ign_rep, - ros_ign_interfaces::srv::ControlWorld::Response & ros_res) +convert_gz_to_ros( + const ignition::msgs::Boolean & gz_rep, + ros_gz_interfaces::srv::ControlWorld::Response & ros_res) { ros_res.success = ign_rep.data(); } template<> bool -send_response_on_error(ros_ign_interfaces::srv::ControlWorld::Response & ros_res) +send_response_on_error(ros_gz_interfaces::srv::ControlWorld::Response & ros_res) { // TODO(now): Is it worth it to have a different field to encode ignition request errors? // Currently we're reusing the success field, which seems fine for this case. diff --git a/ros_gz_bridge/src/service_factories/ros_gz_interfaces.hpp b/ros_gz_bridge/src/service_factories/ros_gz_interfaces.hpp index b28a9e272..4a43adbf5 100644 --- a/ros_gz_bridge/src/service_factories/ros_gz_interfaces.hpp +++ b/ros_gz_bridge/src/service_factories/ros_gz_interfaces.hpp @@ -24,7 +24,7 @@ namespace ros_ign_bridge { std::shared_ptr -get_service_factory__ros_ign_interfaces( +get_service_factory__ros_gz_interfaces( const std::string & ros_type_name, const std::string & ign_req_type_name, const std::string & ign_rep_type_name); diff --git a/ros_gz_bridge/src/service_factory.hpp b/ros_gz_bridge/src/service_factory.hpp index a01637d6d..9bb8d836f 100644 --- a/ros_gz_bridge/src/service_factory.hpp +++ b/ros_gz_bridge/src/service_factory.hpp @@ -24,7 +24,7 @@ #include -#include "ros_ign_bridge/convert_decl.hpp" +#include "ros_gz_bridge/convert_decl.hpp" #include "service_factory_interface.hpp" diff --git a/ros_gz_bridge/test/launch/test_gz_server.launch.py b/ros_gz_bridge/test/launch/test_gz_server.launch.py index f9fd4d530..13770de5f 100644 --- a/ros_gz_bridge/test/launch/test_gz_server.launch.py +++ b/ros_gz_bridge/test/launch/test_gz_server.launch.py @@ -24,22 +24,22 @@ def generate_test_description(): server = Node( - package='ros_ign_bridge', - executable='test_ign_server', + package='ros_gz_bridge', + executable='test_gz_server', output='screen' ) process_under_test = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='test_ros_client', output='screen' ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=[ - '/ign_ros/test/serviceclient/world_control@ros_ign_interfaces/srv/ControlWorld', + '/gz_ros/test/serviceclient/world_control@ros_gz_interfaces/srv/ControlWorld', ], output='screen' ) diff --git a/ros_gz_bridge/test/launch/test_gz_subscriber.launch.py b/ros_gz_bridge/test/launch/test_gz_subscriber.launch.py index 2df7cb00f..7430e662d 100644 --- a/ros_gz_bridge/test/launch/test_gz_subscriber.launch.py +++ b/ros_gz_bridge/test/launch/test_gz_subscriber.launch.py @@ -24,19 +24,19 @@ def generate_test_description(): publisher = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='test_ros_publisher', output='screen' ) process_under_test = Node( - package='ros_ign_bridge', - executable='test_ign_subscriber', + package='ros_gz_bridge', + executable='test_gz_subscriber', output='screen' ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=[ '/time@builtin_interfaces/msg/Time@ignition.msgs.Time', @@ -63,15 +63,15 @@ def generate_test_description(): '/twist_with_covariance@geometry_msgs/msg/TwistWithCovariance@' 'ignition.msgs.TwistWithCovariance', '/wrench@geometry_msgs/msg/Wrench@ignition.msgs.Wrench', - '/joint_wrench@ros_ign_interfaces/msg/JointWrench@ignition.msgs.JointWrench', - '/entity@ros_ign_interfaces/msg/Entity@ignition.msgs.Entity', - '/contact@ros_ign_interfaces/msg/Contact@ignition.msgs.Contact', - '/contacts@ros_ign_interfaces/msg/Contacts@ignition.msgs.Contacts', - '/light@ros_ign_interfaces/msg/Light@ignition.msgs.Light', - '/gui_camera@ros_ign_interfaces/msg/GuiCamera@ignition.msgs.GUICamera', - '/stringmsg_v@ros_ign_interfaces/msg/StringVec@ignition.msgs.StringMsg_V', - '/track_visual@ros_ign_interfaces/msg/TrackVisual@ignition.msgs.TrackVisual', - '/video_record@ros_ign_interfaces/msg/VideoRecord@ignition.msgs.VideoRecord', + '/joint_wrench@ros_gz_interfaces/msg/JointWrench@ignition.msgs.JointWrench', + '/entity@ros_gz_interfaces/msg/Entity@ignition.msgs.Entity', + '/contact@ros_gz_interfaces/msg/Contact@ignition.msgs.Contact', + '/contacts@ros_gz_interfaces/msg/Contacts@ignition.msgs.Contacts', + '/light@ros_gz_interfaces/msg/Light@ignition.msgs.Light', + '/gui_camera@ros_gz_interfaces/msg/GuiCamera@ignition.msgs.GUICamera', + '/stringmsg_v@ros_gz_interfaces/msg/StringVec@ignition.msgs.StringMsg_V', + '/track_visual@ros_gz_interfaces/msg/TrackVisual@ignition.msgs.TrackVisual', + '/video_record@ros_gz_interfaces/msg/VideoRecord@ignition.msgs.VideoRecord', '/image@sensor_msgs/msg/Image@ignition.msgs.Image', '/camera_info@sensor_msgs/msg/CameraInfo@ignition.msgs.CameraInfo', '/fluid_pressure@sensor_msgs/msg/FluidPressure@ignition.msgs.FluidPressure', diff --git a/ros_gz_bridge/test/launch/test_ros_subscriber.launch.py b/ros_gz_bridge/test/launch/test_ros_subscriber.launch.py index 93415b7a6..f411ea30d 100644 --- a/ros_gz_bridge/test/launch/test_ros_subscriber.launch.py +++ b/ros_gz_bridge/test/launch/test_ros_subscriber.launch.py @@ -24,19 +24,19 @@ def generate_test_description(): publisher = Node( - package='ros_ign_bridge', - executable='test_ign_publisher', + package='ros_gz_bridge', + executable='test_gz_publisher', output='screen' ) process_under_test = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='test_ros_subscriber', output='screen' ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=[ '/time@builtin_interfaces/msg/Time@ignition.msgs.Time', @@ -63,15 +63,15 @@ def generate_test_description(): '/twist_with_covariance@geometry_msgs/msg/TwistWithCovariance@' 'ignition.msgs.TwistWithCovariance', '/wrench@geometry_msgs/msg/Wrench@ignition.msgs.Wrench', - '/joint_wrench@ros_ign_interfaces/msg/JointWrench@ignition.msgs.JointWrench', - '/entity@ros_ign_interfaces/msg/Entity@ignition.msgs.Entity', - '/contact@ros_ign_interfaces/msg/Contact@ignition.msgs.Contact', - '/contacts@ros_ign_interfaces/msg/Contacts@ignition.msgs.Contacts', - '/light@ros_ign_interfaces/msg/Light@ignition.msgs.Light', - '/gui_camera@ros_ign_interfaces/msg/GuiCamera@ignition.msgs.GUICamera', - '/stringmsg_v@ros_ign_interfaces/msg/StringVec@ignition.msgs.StringMsg_V', - '/track_visual@ros_ign_interfaces/msg/TrackVisual@ignition.msgs.TrackVisual', - '/video_record@ros_ign_interfaces/msg/VideoRecord@ignition.msgs.VideoRecord', + '/joint_wrench@ros_gz_interfaces/msg/JointWrench@ignition.msgs.JointWrench', + '/entity@ros_gz_interfaces/msg/Entity@ignition.msgs.Entity', + '/contact@ros_gz_interfaces/msg/Contact@ignition.msgs.Contact', + '/contacts@ros_gz_interfaces/msg/Contacts@ignition.msgs.Contacts', + '/light@ros_gz_interfaces/msg/Light@ignition.msgs.Light', + '/gui_camera@ros_gz_interfaces/msg/GuiCamera@ignition.msgs.GUICamera', + '/stringmsg_v@ros_gz_interfaces/msg/StringVec@ignition.msgs.StringMsg_V', + '/track_visual@ros_gz_interfaces/msg/TrackVisual@ignition.msgs.TrackVisual', + '/video_record@ros_gz_interfaces/msg/VideoRecord@ignition.msgs.VideoRecord', '/image@sensor_msgs/msg/Image@ignition.msgs.Image', '/camera_info@sensor_msgs/msg/CameraInfo@ignition.msgs.CameraInfo', '/fluid_pressure@sensor_msgs/msg/FluidPressure@ignition.msgs.FluidPressure', diff --git a/ros_gz_bridge/test/publishers/gz_publisher.cpp b/ros_gz_bridge/test/publishers/gz_publisher.cpp index 28aa36d66..4e106b8e1 100644 --- a/ros_gz_bridge/test/publishers/gz_publisher.cpp +++ b/ros_gz_bridge/test/publishers/gz_publisher.cpp @@ -23,7 +23,7 @@ #include #include "utils/test_utils.hpp" -#include "utils/ign_test_msg.hpp" +#include "utils/gz_test_msg.hpp" /// \brief Flag used to break the publisher loop and terminate the program. static std::atomic g_terminatePub(false); diff --git a/ros_gz_bridge/test/publishers/ros_publisher.cpp b/ros_gz_bridge/test/publishers/ros_publisher.cpp index 52f72a76c..31e4c8756 100644 --- a/ros_gz_bridge/test/publishers/ros_publisher.cpp +++ b/ros_gz_bridge/test/publishers/ros_publisher.cpp @@ -146,59 +146,59 @@ int main(int argc, char ** argv) geometry_msgs::msg::Wrench wrench_msg; ros_ign_bridge::testing::createTestMsg(wrench_msg); - // ros_ign_interfaces::msg::Light. + // ros_gz_interfaces::msg::Light. auto light_pub = - node->create_publisher("light", 1); - ros_ign_interfaces::msg::Light light_msg; - ros_ign_bridge::testing::createTestMsg(light_msg); + node->create_publisher("light", 1); + ros_gz_interfaces::msg::Light light_msg; + ros_gz_bridge::testing::createTestMsg(light_msg); - // ros_ign_interfaces::msg::JointWrench. + // ros_gz_interfaces::msg::JointWrench. auto joint_wrench_pub = - node->create_publisher("joint_wrench", 1); - ros_ign_interfaces::msg::JointWrench joint_wrench_msg; - ros_ign_bridge::testing::createTestMsg(joint_wrench_msg); + node->create_publisher("joint_wrench", 1); + ros_gz_interfaces::msg::JointWrench joint_wrench_msg; + ros_gz_bridge::testing::createTestMsg(joint_wrench_msg); - // ros_ign_interfaces::msg::Entity. + // ros_gz_interfaces::msg::Entity. auto entity_pub = - node->create_publisher("entity", 1); - ros_ign_interfaces::msg::Entity entity_msg; - ros_ign_bridge::testing::createTestMsg(entity_msg); + node->create_publisher("entity", 1); + ros_gz_interfaces::msg::Entity entity_msg; + ros_gz_bridge::testing::createTestMsg(entity_msg); - // ros_ign_interfaces::msg::Contact. + // ros_gz_interfaces::msg::Contact. auto contact_pub = - node->create_publisher("contact", 1); - ros_ign_interfaces::msg::Contact contact_msg; - ros_ign_bridge::testing::createTestMsg(contact_msg); + node->create_publisher("contact", 1); + ros_gz_interfaces::msg::Contact contact_msg; + ros_gz_bridge::testing::createTestMsg(contact_msg); - // ros_ign_interfaces::msg::Contacts. + // ros_gz_interfaces::msg::Contacts. auto contacts_pub = - node->create_publisher("contacts", 1); - ros_ign_interfaces::msg::Contacts contacts_msg; - ros_ign_bridge::testing::createTestMsg(contacts_msg); + node->create_publisher("contacts", 1); + ros_gz_interfaces::msg::Contacts contacts_msg; + ros_gz_bridge::testing::createTestMsg(contacts_msg); - // ros_ign_interfaces::msg::GuiCamera. + // ros_gz_interfaces::msg::GuiCamera. auto gui_camera_pub = - node->create_publisher("gui_camera", 1); - ros_ign_interfaces::msg::GuiCamera gui_camera_msg; - ros_ign_bridge::testing::createTestMsg(gui_camera_msg); + node->create_publisher("gui_camera", 1); + ros_gz_interfaces::msg::GuiCamera gui_camera_msg; + ros_gz_bridge::testing::createTestMsg(gui_camera_msg); - // ros_ign_interfaces::msg::StringVec. + // ros_gz_interfaces::msg::StringVec. auto stringmsg_v_pub = - node->create_publisher("stringmsg_v", 1); - ros_ign_interfaces::msg::StringVec stringmsg_v_msg; - ros_ign_bridge::testing::createTestMsg(stringmsg_v_msg); + node->create_publisher("stringmsg_v", 1); + ros_gz_interfaces::msg::StringVec stringmsg_v_msg; + ros_gz_bridge::testing::createTestMsg(stringmsg_v_msg); - // ros_ign_interfaces::msg::TrackVisual. + // ros_gz_interfaces::msg::TrackVisual. auto track_visual_pub = - node->create_publisher("track_visual", 1); - ros_ign_interfaces::msg::TrackVisual track_visual_msg; - ros_ign_bridge::testing::createTestMsg(track_visual_msg); + node->create_publisher("track_visual", 1); + ros_gz_interfaces::msg::TrackVisual track_visual_msg; + ros_gz_bridge::testing::createTestMsg(track_visual_msg); - // ros_ign_interfaces::msg::VideoRecord. + // ros_gz_interfaces::msg::VideoRecord. auto video_record_pub = - node->create_publisher("video_record", 1); - ros_ign_interfaces::msg::VideoRecord video_record_msg; - ros_ign_bridge::testing::createTestMsg(video_record_msg); + node->create_publisher("video_record", 1); + ros_gz_interfaces::msg::VideoRecord video_record_msg; + ros_gz_bridge::testing::createTestMsg(video_record_msg); // // mav_msgs::msg::Actuators. // auto actuators_pub = diff --git a/ros_gz_bridge/test/serverclient/gz_server.cpp b/ros_gz_bridge/test/serverclient/gz_server.cpp index 3068a3bab..ee549ab1d 100644 --- a/ros_gz_bridge/test/serverclient/gz_server.cpp +++ b/ros_gz_bridge/test/serverclient/gz_server.cpp @@ -24,7 +24,7 @@ #include #include "utils/test_utils.hpp" -#include "utils/ign_test_msg.hpp" +#include "utils/gz_test_msg.hpp" /// \brief Flag used to break the waiting loop and terminate the program. static std::atomic_flag g_terminateSrv(false); diff --git a/ros_gz_bridge/test/serverclient/ros_client.cpp b/ros_gz_bridge/test/serverclient/ros_client.cpp index 1785ced9f..ff21e464d 100644 --- a/ros_gz_bridge/test/serverclient/ros_client.cpp +++ b/ros_gz_bridge/test/serverclient/ros_client.cpp @@ -19,7 +19,7 @@ #include "rclcpp/rclcpp.hpp" -#include "ros_ign_interfaces/srv/control_world.hpp" +#include "ros_gz_interfaces/srv/control_world.hpp" using namespace std::chrono_literals; @@ -27,12 +27,12 @@ using namespace std::chrono_literals; TEST(ROSClientTest, WorldControl) { rclcpp::init(0, NULL); - auto node = std::make_shared("test_ros_client_to_ign_service"); - auto client = node->create_client( - "/ign_ros/test/serviceclient/world_control"); + auto node = std::make_shared("test_ros_client_to_gz_service"); + auto client = node->create_client( + "/gz_ros/test/serviceclient/world_control"); std::this_thread::sleep_for(1s); ASSERT_TRUE(client->wait_for_service(5s)); - auto msg = std::make_shared(); + auto msg = std::make_shared(); auto future = client->async_send_request(msg); rclcpp::executors::SingleThreadedExecutor ex; ex.add_node(node); diff --git a/ros_gz_bridge/test/subscribers/gz_subscriber.cpp b/ros_gz_bridge/test/subscribers/gz_subscriber.cpp index 937459f10..8d7726b48 100644 --- a/ros_gz_bridge/test/subscribers/gz_subscriber.cpp +++ b/ros_gz_bridge/test/subscribers/gz_subscriber.cpp @@ -22,7 +22,7 @@ #include #include "utils/test_utils.hpp" -#include "utils/ign_test_msg.hpp" +#include "utils/gz_test_msg.hpp" ////////////////////////////////////////////////// /// \brief A class for testing Ignition Transport topic subscription. @@ -59,7 +59,7 @@ class MyTestClass }; ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Boolean) +TEST(GzSubscriberTest, Boolean) { MyTestClass client("bool"); @@ -71,7 +71,7 @@ TEST(IgnSubscriberTest, Boolean) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Empty) +TEST(GzSubscriberTest, Empty) { MyTestClass client("empty"); @@ -83,7 +83,7 @@ TEST(IgnSubscriberTest, Empty) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Float) +TEST(GzSubscriberTest, Float) { MyTestClass client("float"); @@ -95,7 +95,7 @@ TEST(IgnSubscriberTest, Float) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Double) +TEST(GzSubscriberTest, Double) { MyTestClass client("double"); @@ -107,7 +107,7 @@ TEST(IgnSubscriberTest, Double) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, UInt32) +TEST(GzSubscriberTest, UInt32) { MyTestClass client("uint32"); @@ -119,7 +119,7 @@ TEST(IgnSubscriberTest, UInt32) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Header) +TEST(GzSubscriberTest, Header) { MyTestClass client("header"); @@ -131,7 +131,7 @@ TEST(IgnSubscriberTest, Header) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, String) +TEST(GzSubscriberTest, String) { MyTestClass client("string"); @@ -143,7 +143,7 @@ TEST(IgnSubscriberTest, String) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Quaternion) +TEST(GzSubscriberTest, Quaternion) { MyTestClass client("quaternion"); @@ -155,7 +155,7 @@ TEST(IgnSubscriberTest, Quaternion) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Vector3) +TEST(GzSubscriberTest, Vector3) { MyTestClass client("vector3"); @@ -167,7 +167,7 @@ TEST(IgnSubscriberTest, Vector3) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Clock) +TEST(GzSubscriberTest, Clock) { MyTestClass client("clock"); @@ -179,7 +179,7 @@ TEST(IgnSubscriberTest, Clock) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Point) +TEST(GzSubscriberTest, Point) { MyTestClass client("point"); @@ -191,7 +191,7 @@ TEST(IgnSubscriberTest, Point) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Pose) +TEST(GzSubscriberTest, Pose) { MyTestClass client("pose"); @@ -203,7 +203,7 @@ TEST(IgnSubscriberTest, Pose) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, PoseWithCovariance) +TEST(GzSubscriberTest, PoseWithCovariance) { MyTestClass client("pose_with_covariance"); @@ -215,7 +215,7 @@ TEST(IgnSubscriberTest, PoseWithCovariance) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, PoseStamped) +TEST(GzSubscriberTest, PoseStamped) { MyTestClass client("pose_stamped"); @@ -227,7 +227,7 @@ TEST(IgnSubscriberTest, PoseStamped) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Transform) +TEST(GzSubscriberTest, Transform) { MyTestClass client("transform"); @@ -239,7 +239,7 @@ TEST(IgnSubscriberTest, Transform) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, TransformStamped) +TEST(GzSubscriberTest, TransformStamped) { MyTestClass client("transform_stamped"); @@ -251,7 +251,7 @@ TEST(IgnSubscriberTest, TransformStamped) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, TF2Message) +TEST(GzSubscriberTest, TF2Message) { MyTestClass client("tf2_message"); @@ -263,7 +263,7 @@ TEST(IgnSubscriberTest, TF2Message) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Twist) +TEST(GzSubscriberTest, Twist) { MyTestClass client("twist"); @@ -275,7 +275,7 @@ TEST(IgnSubscriberTest, Twist) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, TwistWithCovariance) +TEST(GzSubscriberTest, TwistWithCovariance) { MyTestClass client("twist_with_covariance"); @@ -287,7 +287,7 @@ TEST(IgnSubscriberTest, TwistWithCovariance) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Wrench) +TEST(GzSubscriberTest, Wrench) { MyTestClass client("wrench"); @@ -299,7 +299,7 @@ TEST(IgnSubscriberTest, Wrench) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, JointWrench) +TEST(GzSubscriberTest, JointWrench) { MyTestClass client("joint_wrench"); @@ -311,7 +311,7 @@ TEST(IgnSubscriberTest, JointWrench) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Entity) +TEST(GzSubscriberTest, Entity) { MyTestClass client("entity"); @@ -323,7 +323,7 @@ TEST(IgnSubscriberTest, Entity) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Contact) +TEST(GzSubscriberTest, Contact) { MyTestClass client("contact"); @@ -335,7 +335,7 @@ TEST(IgnSubscriberTest, Contact) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Contacts) +TEST(GzSubscriberTest, Contacts) { MyTestClass client("contacts"); @@ -347,7 +347,7 @@ TEST(IgnSubscriberTest, Contacts) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Image) +TEST(GzSubscriberTest, Image) { MyTestClass client("image"); @@ -359,7 +359,7 @@ TEST(IgnSubscriberTest, Image) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, CameraInfo) +TEST(GzSubscriberTest, CameraInfo) { MyTestClass client("camera_info"); @@ -371,7 +371,7 @@ TEST(IgnSubscriberTest, CameraInfo) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, FluidPressure) +TEST(GzSubscriberTest, FluidPressure) { MyTestClass client("fluid_pressure"); @@ -383,7 +383,7 @@ TEST(IgnSubscriberTest, FluidPressure) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Imu) +TEST(GzSubscriberTest, Imu) { MyTestClass client("imu"); @@ -395,7 +395,7 @@ TEST(IgnSubscriberTest, Imu) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, LaserScan) +TEST(GzSubscriberTest, LaserScan) { MyTestClass client("laserscan"); @@ -407,7 +407,7 @@ TEST(IgnSubscriberTest, LaserScan) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Magnetometer) +TEST(GzSubscriberTest, Magnetometer) { MyTestClass client("magnetic"); @@ -419,7 +419,7 @@ TEST(IgnSubscriberTest, Magnetometer) } // ///////////////////////////////////////////////// -// TEST(IgnSubscriberTest, Actuators) +// TEST(GzSubscriberTest, Actuators) // { // MyTestClass client("actuators"); // @@ -431,7 +431,7 @@ TEST(IgnSubscriberTest, Magnetometer) // } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Odometry) +TEST(GzSubscriberTest, Odometry) { MyTestClass client("odometry"); @@ -443,7 +443,7 @@ TEST(IgnSubscriberTest, Odometry) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, OdometryWithCovariance) +TEST(GzSubscriberTest, OdometryWithCovariance) { MyTestClass client("odometry_with_covariance"); @@ -455,7 +455,7 @@ TEST(IgnSubscriberTest, OdometryWithCovariance) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, JointStates) +TEST(GzSubscriberTest, JointStates) { MyTestClass client("joint_states"); @@ -467,7 +467,7 @@ TEST(IgnSubscriberTest, JointStates) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, PointCloudPacked) +TEST(GzSubscriberTest, PointCloudPacked) { MyTestClass client("pointcloud2"); @@ -479,7 +479,7 @@ TEST(IgnSubscriberTest, PointCloudPacked) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, BatteryState) +TEST(GzSubscriberTest, BatteryState) { MyTestClass client("battery_state"); @@ -491,7 +491,7 @@ TEST(IgnSubscriberTest, BatteryState) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, GuiCamera) +TEST(GzSubscriberTest, GuiCamera) { MyTestClass client("gui_camera"); @@ -503,7 +503,7 @@ TEST(IgnSubscriberTest, GuiCamera) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, JointTrajectory) +TEST(GzSubscriberTest, JointTrajectory) { MyTestClass client("joint_trajectory"); @@ -515,7 +515,7 @@ TEST(IgnSubscriberTest, JointTrajectory) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, StringMsg_V) +TEST(GzSubscriberTest, StringMsg_V) { MyTestClass client("stringmsg_v"); @@ -527,7 +527,7 @@ TEST(IgnSubscriberTest, StringMsg_V) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, Time) +TEST(GzSubscriberTest, Time) { MyTestClass client("time"); @@ -539,7 +539,7 @@ TEST(IgnSubscriberTest, Time) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, TrackVisual) +TEST(GzSubscriberTest, TrackVisual) { MyTestClass client("track_visual"); @@ -551,7 +551,7 @@ TEST(IgnSubscriberTest, TrackVisual) } ///////////////////////////////////////////////// -TEST(IgnSubscriberTest, VideoRecord) +TEST(GzSubscriberTest, VideoRecord) { MyTestClass client("video_record"); diff --git a/ros_gz_bridge/test/subscribers/ros_subscriber/ros_gz_interfaces_subscriber.cpp b/ros_gz_bridge/test/subscribers/ros_subscriber/ros_gz_interfaces_subscriber.cpp index 6c81391ec..b272c61d6 100644 --- a/ros_gz_bridge/test/subscribers/ros_subscriber/ros_gz_interfaces_subscriber.cpp +++ b/ros_gz_bridge/test/subscribers/ros_subscriber/ros_gz_interfaces_subscriber.cpp @@ -24,7 +24,7 @@ using ros_subscriber::MyTestClass; ///////////////////////////////////////////////// TEST(ROSSubscriberTest, Light) { - MyTestClass client("light"); + MyTestClass client("light"); using namespace std::chrono_literals; ros_ign_bridge::testing::waitUntilBoolVarAndSpin( @@ -36,7 +36,7 @@ TEST(ROSSubscriberTest, Light) ///////////////////////////////////////////////// TEST(ROSSubscriberTest, JointWrench) { - MyTestClass client("joint_wrench"); + MyTestClass client("joint_wrench"); using namespace std::chrono_literals; ros_ign_bridge::testing::waitUntilBoolVarAndSpin( @@ -48,7 +48,7 @@ TEST(ROSSubscriberTest, JointWrench) ///////////////////////////////////////////////// TEST(ROSSubscriberTest, Entity) { - MyTestClass client("entity"); + MyTestClass client("entity"); using namespace std::chrono_literals; ros_ign_bridge::testing::waitUntilBoolVarAndSpin( @@ -60,7 +60,7 @@ TEST(ROSSubscriberTest, Entity) ///////////////////////////////////////////////// TEST(ROSSubscriberTest, Contact) { - MyTestClass client("contact"); + MyTestClass client("contact"); using namespace std::chrono_literals; ros_ign_bridge::testing::waitUntilBoolVarAndSpin( @@ -72,7 +72,7 @@ TEST(ROSSubscriberTest, Contact) ///////////////////////////////////////////////// TEST(ROSSubscriberTest, Contacts) { - MyTestClass client("contacts"); + MyTestClass client("contacts"); using namespace std::chrono_literals; ros_ign_bridge::testing::waitUntilBoolVarAndSpin( @@ -84,7 +84,7 @@ TEST(ROSSubscriberTest, Contacts) ///////////////////////////////////////////////// TEST(ROSSubscriberTest, GuiCamera) { - MyTestClass client("gui_camera"); + MyTestClass client("gui_camera"); using namespace std::chrono_literals; ros_ign_bridge::testing::waitUntilBoolVarAndSpin( @@ -96,7 +96,7 @@ TEST(ROSSubscriberTest, GuiCamera) ///////////////////////////////////////////////// TEST(ROSSubscriberTest, StringVec) { - MyTestClass client("stringmsg_v"); + MyTestClass client("stringmsg_v"); using namespace std::chrono_literals; ros_ign_bridge::testing::waitUntilBoolVarAndSpin( @@ -108,7 +108,7 @@ TEST(ROSSubscriberTest, StringVec) ///////////////////////////////////////////////// TEST(ROSSubscriberTest, TrackVisual) { - MyTestClass client("track_visual"); + MyTestClass client("track_visual"); using namespace std::chrono_literals; ros_ign_bridge::testing::waitUntilBoolVarAndSpin( @@ -120,7 +120,7 @@ TEST(ROSSubscriberTest, TrackVisual) ///////////////////////////////////////////////// TEST(ROSSubscriberTest, VideoRecord) { - MyTestClass client("video_record"); + MyTestClass client("video_record"); using namespace std::chrono_literals; ros_ign_bridge::testing::waitUntilBoolVarAndSpin( diff --git a/ros_gz_bridge/test/utils/gz_test_msg.cpp b/ros_gz_bridge/test/utils/gz_test_msg.cpp index 42c3409ae..0a1fa79f3 100644 --- a/ros_gz_bridge/test/utils/gz_test_msg.cpp +++ b/ros_gz_bridge/test/utils/gz_test_msg.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ign_test_msg.hpp" +#include "gz_test_msg.hpp" #include diff --git a/ros_gz_bridge/test/utils/ros_test_msg.cpp b/ros_gz_bridge/test/utils/ros_test_msg.cpp index 79da0adde..c6fa23bb0 100644 --- a/ros_gz_bridge/test/utils/ros_test_msg.cpp +++ b/ros_gz_bridge/test/utils/ros_test_msg.cpp @@ -394,7 +394,7 @@ void compareTestMsg(const std::shared_ptr & _msg) compareTestMsg(std::make_shared(_msg->torque)); } -void createTestMsg(ros_ign_interfaces::msg::Light & _msg) +void createTestMsg(ros_gz_interfaces::msg::Light & _msg) { createTestMsg(_msg.header); @@ -421,9 +421,9 @@ void createTestMsg(ros_ign_interfaces::msg::Light & _msg) _msg.intensity = 125.0; } -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::Light expected_msg; + ros_gz_interfaces::msg::Light expected_msg; createTestMsg(expected_msg); compareTestMsg(_msg->header); @@ -451,7 +451,7 @@ void compareTestMsg(const std::shared_ptr & _msg EXPECT_FLOAT_EQ(expected_msg.intensity, _msg->intensity); } -void createTestMsg(ros_ign_interfaces::msg::GuiCamera & _msg) +void createTestMsg(ros_gz_interfaces::msg::GuiCamera & _msg) { createTestMsg(_msg.header); createTestMsg(_msg.track); @@ -462,13 +462,13 @@ void createTestMsg(ros_ign_interfaces::msg::GuiCamera & _msg) _msg.projection_type = "test_gui_camera_projection_type"; } -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::GuiCamera expected_msg; + ros_gz_interfaces::msg::GuiCamera expected_msg; createTestMsg(expected_msg); compareTestMsg(_msg->header); - compareTestMsg(std::make_shared(_msg->track)); + compareTestMsg(std::make_shared(_msg->track)); compareTestMsg(std::make_shared(_msg->pose)); EXPECT_EQ(expected_msg.name, _msg->name); @@ -476,16 +476,16 @@ void compareTestMsg(const std::shared_ptr & EXPECT_EQ(expected_msg.projection_type, _msg->projection_type); } -void createTestMsg(ros_ign_interfaces::msg::StringVec & _msg) +void createTestMsg(ros_gz_interfaces::msg::StringVec & _msg) { createTestMsg(_msg.header); _msg.data.emplace_back("test_string_msg_v_data"); } -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::StringVec expected_msg; + ros_gz_interfaces::msg::StringVec expected_msg; createTestMsg(expected_msg); compareTestMsg(_msg->header); @@ -493,7 +493,7 @@ void compareTestMsg(const std::shared_ptr & EXPECT_EQ(expected_msg.data, _msg->data); } -void createTestMsg(ros_ign_interfaces::msg::TrackVisual & _msg) +void createTestMsg(ros_gz_interfaces::msg::TrackVisual & _msg) { createTestMsg(_msg.header); createTestMsg(_msg.xyz); @@ -508,9 +508,9 @@ void createTestMsg(ros_ign_interfaces::msg::TrackVisual & _msg) _msg.inherit_yaw = true; } -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::TrackVisual expected_msg; + ros_gz_interfaces::msg::TrackVisual expected_msg; createTestMsg(expected_msg); compareTestMsg(_msg->header); @@ -526,7 +526,7 @@ void compareTestMsg(const std::shared_ptr EXPECT_EQ(expected_msg.inherit_yaw, _msg->inherit_yaw); } -void createTestMsg(ros_ign_interfaces::msg::VideoRecord & _msg) +void createTestMsg(ros_gz_interfaces::msg::VideoRecord & _msg) { createTestMsg(_msg.header); @@ -536,9 +536,9 @@ void createTestMsg(ros_ign_interfaces::msg::VideoRecord & _msg) _msg.save_filename = "test_video_record_save_filename"; } -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::VideoRecord expected_msg; + ros_gz_interfaces::msg::VideoRecord expected_msg; createTestMsg(expected_msg); compareTestMsg(_msg->header); @@ -549,7 +549,7 @@ void compareTestMsg(const std::shared_ptr EXPECT_EQ(expected_msg.save_filename, _msg->save_filename); } -void createTestMsg(ros_ign_interfaces::msg::JointWrench & _msg) +void createTestMsg(ros_gz_interfaces::msg::JointWrench & _msg) { createTestMsg(_msg.header); _msg.body_1_name.data = "body1"; @@ -560,9 +560,9 @@ void createTestMsg(ros_ign_interfaces::msg::JointWrench & _msg) createTestMsg(_msg.body_2_wrench); } -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::JointWrench expected_msg; + ros_gz_interfaces::msg::JointWrench expected_msg; createTestMsg(expected_msg); EXPECT_EQ(expected_msg.body_1_name, _msg->body_1_name); @@ -575,16 +575,16 @@ void compareTestMsg(const std::shared_ptr compareTestMsg(std::make_shared(_msg->body_2_wrench)); } -void createTestMsg(ros_ign_interfaces::msg::Entity & _msg) +void createTestMsg(ros_gz_interfaces::msg::Entity & _msg) { _msg.id = 1; _msg.name = "entity"; - _msg.type = ros_ign_interfaces::msg::Entity::VISUAL; + _msg.type = ros_gz_interfaces::msg::Entity::VISUAL; } -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::Entity expected_msg; + ros_gz_interfaces::msg::Entity expected_msg; createTestMsg(expected_msg); EXPECT_EQ(expected_msg.id, _msg->id); @@ -592,7 +592,7 @@ void compareTestMsg(const std::shared_ptr & _ms EXPECT_EQ(expected_msg.type, _msg->type); } -void createTestMsg(ros_ign_interfaces::msg::Contact & _msg) +void createTestMsg(ros_gz_interfaces::msg::Contact & _msg) { createTestMsg(_msg.collision1); createTestMsg(_msg.collision2); @@ -600,7 +600,7 @@ void createTestMsg(ros_ign_interfaces::msg::Contact & _msg) geometry_msgs::msg::Vector3 vector_msg; createTestMsg(vector_msg); - ros_ign_interfaces::msg::JointWrench joint_wrench_msg; + ros_gz_interfaces::msg::JointWrench joint_wrench_msg; createTestMsg(joint_wrench_msg); for (int i = 0; i < 10; i++) { @@ -611,12 +611,12 @@ void createTestMsg(ros_ign_interfaces::msg::Contact & _msg) } } -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::Contact expected_msg; + ros_gz_interfaces::msg::Contact expected_msg; createTestMsg(expected_msg); - compareTestMsg(std::make_shared(_msg->collision1)); - compareTestMsg(std::make_shared(_msg->collision2)); + compareTestMsg(std::make_shared(_msg->collision1)); + compareTestMsg(std::make_shared(_msg->collision2)); EXPECT_EQ(expected_msg.depths.size(), _msg->depths.size()); EXPECT_EQ(expected_msg.positions.size(), _msg->positions.size()); EXPECT_EQ(expected_msg.normals.size(), _msg->normals.size()); @@ -625,15 +625,15 @@ void compareTestMsg(const std::shared_ptr & _m EXPECT_EQ(expected_msg.depths.at(i), _msg->depths.at(i)); compareTestMsg(std::make_shared(_msg->positions.at(i))); compareTestMsg(std::make_shared(_msg->normals.at(i))); - compareTestMsg(std::make_shared(_msg->wrenches.at(i))); + compareTestMsg(std::make_shared(_msg->wrenches.at(i))); } } -void createTestMsg(ros_ign_interfaces::msg::Contacts & _msg) +void createTestMsg(ros_gz_interfaces::msg::Contacts & _msg) { createTestMsg(_msg.header); - ros_ign_interfaces::msg::Contact contact_msg; + ros_gz_interfaces::msg::Contact contact_msg; createTestMsg(contact_msg); for (int i = 0; i < 10; i++) { @@ -641,15 +641,15 @@ void createTestMsg(ros_ign_interfaces::msg::Contacts & _msg) } } -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::Contacts expected_msg; + ros_gz_interfaces::msg::Contacts expected_msg; createTestMsg(expected_msg); compareTestMsg(_msg->header); EXPECT_EQ(expected_msg.contacts.size(), _msg->contacts.size()); for (size_t i = 0; i < _msg->contacts.size(); i++) { - compareTestMsg(std::make_shared(_msg->contacts.at(i))); + compareTestMsg(std::make_shared(_msg->contacts.at(i))); } } diff --git a/ros_gz_bridge/test/utils/ros_test_msg.hpp b/ros_gz_bridge/test/utils/ros_test_msg.hpp index 84e7316cc..29f1809ff 100644 --- a/ros_gz_bridge/test/utils/ros_test_msg.hpp +++ b/ros_gz_bridge/test/utils/ros_test_msg.hpp @@ -38,15 +38,15 @@ #include #include #include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include #include #include @@ -286,79 +286,79 @@ void createTestMsg(nav_msgs::msg::Odometry & _msg); /// \param[in] _msg The message to compare. void compareTestMsg(const std::shared_ptr & _msg); -/// ros_ign_interfaces +/// ros_gz_interfaces /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::JointWrench & _msg); +void createTestMsg(ros_gz_interfaces::msg::JointWrench & _msg); /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg); +void compareTestMsg(const std::shared_ptr & _msg); /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::Light & _msg); +void createTestMsg(ros_gz_interfaces::msg::Light & _msg); /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg); +void compareTestMsg(const std::shared_ptr & _msg); /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::Entity & _msg); +void createTestMsg(ros_gz_interfaces::msg::Entity & _msg); /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg); +void compareTestMsg(const std::shared_ptr & _msg); /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::Contact & _msg); +void createTestMsg(ros_gz_interfaces::msg::Contact & _msg); /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg); +void compareTestMsg(const std::shared_ptr & _msg); /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::Contacts & _msg); +void createTestMsg(ros_gz_interfaces::msg::Contacts & _msg); /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg); +void compareTestMsg(const std::shared_ptr & _msg); /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::GuiCamera & _msg); +void createTestMsg(ros_gz_interfaces::msg::GuiCamera & _msg); /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg); +void compareTestMsg(const std::shared_ptr & _msg); /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::StringVec & _msg); +void createTestMsg(ros_gz_interfaces::msg::StringVec & _msg); /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg); +void compareTestMsg(const std::shared_ptr & _msg); /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::TrackVisual & _msg); +void createTestMsg(ros_gz_interfaces::msg::TrackVisual & _msg); /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg); +void compareTestMsg(const std::shared_ptr & _msg); /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::VideoRecord & _msg); +void createTestMsg(ros_gz_interfaces::msg::VideoRecord & _msg); /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg); +void compareTestMsg(const std::shared_ptr & _msg); /// sensor_msgs diff --git a/ros_gz_image/CMakeLists.txt b/ros_gz_image/CMakeLists.txt index 4d9c9c2e3..aff66fd16 100644 --- a/ros_gz_image/CMakeLists.txt +++ b/ros_gz_image/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) -project(ros_ign_image) +project(ros_gz_image) # Default to C++17 if(NOT CMAKE_CXX_STANDARD) @@ -12,7 +12,7 @@ endif() find_package(ament_cmake REQUIRED) find_package(image_transport REQUIRED) -find_package(ros_ign_bridge REQUIRED) +find_package(ros_gz_bridge REQUIRED) find_package(rclcpp REQUIRED) find_package(sensor_msgs REQUIRED) @@ -68,7 +68,7 @@ target_link_libraries(${executable} ament_target_dependencies(${executable} "image_transport" - "ros_ign_bridge" + "ros_gz_bridge" "rclcpp" "sensor_msgs" ) @@ -84,7 +84,7 @@ if(BUILD_TESTING) # find_package(rostest REQUIRED) # # set(test_publishers - # ign_publisher + # gz_publisher # ) # # set(test_subscribers diff --git a/ros_gz_image/package.xml b/ros_gz_image/package.xml index 95e13e5ce..e87b1b403 100644 --- a/ros_gz_image/package.xml +++ b/ros_gz_image/package.xml @@ -1,5 +1,5 @@ - ros_ign_image + ros_gz_image 0.244.3 Image utilities for Ignition simulation with ROS. Apache 2.0 @@ -9,7 +9,7 @@ pkg-config image_transport - ros_ign_bridge + ros_gz_bridge rclcpp sensor_msgs diff --git a/ros_gz_image/src/image_bridge.cpp b/ros_gz_image/src/image_bridge.cpp index ef4b86782..e5dc54a5a 100644 --- a/ros_gz_image/src/image_bridge.cpp +++ b/ros_gz_image/src/image_bridge.cpp @@ -21,7 +21,7 @@ #include #include #include -#include +#include ////////////////////////////////////////////////// /// \brief Bridges one topic @@ -91,7 +91,7 @@ int main(int argc, char * argv[]) handlers.push_back(std::make_shared(topic, it_node, ign_node)); } - // Spin ROS and Ign until shutdown + // Spin ROS and Gz until shutdown rclcpp::spin(node_); ignition::transport::waitForShutdown(); diff --git a/ros_gz_image/test/launch/test_ros_subscriber.launch b/ros_gz_image/test/launch/test_ros_subscriber.launch index cbe8634b6..e4e451a5d 100644 --- a/ros_gz_image/test/launch/test_ros_subscriber.launch +++ b/ros_gz_image/test/launch/test_ros_subscriber.launch @@ -1,12 +1,12 @@ - - - + + diff --git a/ros_gz_image/test/ros_subscriber.test b/ros_gz_image/test/ros_subscriber.test index a5fb11f3a..192a2b395 100644 --- a/ros_gz_image/test/ros_subscriber.test +++ b/ros_gz_image/test/ros_subscriber.test @@ -1,9 +1,9 @@ - + - + diff --git a/ros_gz_interfaces/CMakeLists.txt b/ros_gz_interfaces/CMakeLists.txt index df8776464..0353319c2 100644 --- a/ros_gz_interfaces/CMakeLists.txt +++ b/ros_gz_interfaces/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(ros_ign_interfaces) +project(ros_gz_interfaces) if(NOT CMAKE_CXX_STANDARD) set(CMAKE_CXX_STANDARD 14) diff --git a/ros_gz_interfaces/msg/Contact.msg b/ros_gz_interfaces/msg/Contact.msg index 902353567..98d2cef8e 100644 --- a/ros_gz_interfaces/msg/Contact.msg +++ b/ros_gz_interfaces/msg/Contact.msg @@ -1,6 +1,6 @@ -ros_ign_interfaces/Entity collision1 # Contact collision1 -ros_ign_interfaces/Entity collision2 # Contact collision2 +ros_gz_interfaces/Entity collision1 # Contact collision1 +ros_gz_interfaces/Entity collision2 # Contact collision2 geometry_msgs/Vector3[] positions # List of contact position geometry_msgs/Vector3[] normals # List of contact normals float64[] depths # List of penetration depths -ros_ign_interfaces/JointWrench[] wrenches # List of joint wrenches including forces/torques +ros_gz_interfaces/JointWrench[] wrenches # List of joint wrenches including forces/torques diff --git a/ros_gz_interfaces/msg/Contacts.msg b/ros_gz_interfaces/msg/Contacts.msg index e709e178d..40232e516 100644 --- a/ros_gz_interfaces/msg/Contacts.msg +++ b/ros_gz_interfaces/msg/Contacts.msg @@ -1,2 +1,2 @@ std_msgs/Header header # Time stamp -ros_ign_interfaces/Contact[] contacts # List of contacts +ros_gz_interfaces/Contact[] contacts # List of contacts diff --git a/ros_gz_interfaces/msg/WorldControl.msg b/ros_gz_interfaces/msg/WorldControl.msg index f08cb6f5b..efa22fb9c 100644 --- a/ros_gz_interfaces/msg/WorldControl.msg +++ b/ros_gz_interfaces/msg/WorldControl.msg @@ -1,7 +1,7 @@ bool pause # Paused state. bool step # uint32 multi_step 0 # Paused after stepping multi_step. -ros_ign_interfaces/WorldReset reset # +ros_gz_interfaces/WorldReset reset # uint32 seed # builtin_interfaces/Time run_to_sim_time # A simulation time in the future to run to and # then pause. diff --git a/ros_gz_interfaces/package.xml b/ros_gz_interfaces/package.xml index 9584c8b41..73d9d0333 100644 --- a/ros_gz_interfaces/package.xml +++ b/ros_gz_interfaces/package.xml @@ -1,5 +1,5 @@ - ros_ign_interfaces + ros_gz_interfaces 0.244.3 Message and service data structures for interacting with Ignition from ROS2. Apache 2.0 diff --git a/ros_gz_interfaces/srv/ControlWorld.srv b/ros_gz_interfaces/srv/ControlWorld.srv index 92f7a712c..d8e41f245 100644 --- a/ros_gz_interfaces/srv/ControlWorld.srv +++ b/ros_gz_interfaces/srv/ControlWorld.srv @@ -1,3 +1,3 @@ -ros_ign_interfaces/WorldControl world_control # Message to Control world in Ignition Gazebo +ros_gz_interfaces/WorldControl world_control # Message to Control world in Gazebo Sim --- bool success # Return true if control is successful. diff --git a/ros_gz_interfaces/srv/DeleteEntity.srv b/ros_gz_interfaces/srv/DeleteEntity.srv index d922e7f9d..13b3e1fd8 100644 --- a/ros_gz_interfaces/srv/DeleteEntity.srv +++ b/ros_gz_interfaces/srv/DeleteEntity.srv @@ -1,3 +1,3 @@ -ros_ign_interfaces/Entity entity # Ignition Gazebo entity to be deleted. +ros_gz_interfaces/Entity entity # Gazebo Sim entity to be deleted. --- bool success # Return true if deletion is successful. diff --git a/ros_gz_interfaces/srv/SetEntityPose.srv b/ros_gz_interfaces/srv/SetEntityPose.srv index f1fbec7eb..b749488cc 100644 --- a/ros_gz_interfaces/srv/SetEntityPose.srv +++ b/ros_gz_interfaces/srv/SetEntityPose.srv @@ -1,4 +1,4 @@ -ros_ign_interfaces/Entity entity # Ignition Gazebo entity. +ros_gz_interfaces/Entity entity # Gazebo Sim entity. geometry_msgs/Pose pose # Pose of entity. --- bool success # Return true if set successfully. diff --git a/ros_gz_interfaces/srv/SpawnEntity.srv b/ros_gz_interfaces/srv/SpawnEntity.srv index cb85e438f..35d5df59e 100644 --- a/ros_gz_interfaces/srv/SpawnEntity.srv +++ b/ros_gz_interfaces/srv/SpawnEntity.srv @@ -1,3 +1,3 @@ -ros_ign_interfaces/EntityFactory entity_factory # Message to create a new entity +ros_gz_interfaces/EntityFactory entity_factory # Message to create a new entity --- bool success # Return true if spawned successfully. diff --git a/ros_gz_point_cloud/CMakeLists.txt b/ros_gz_point_cloud/CMakeLists.txt index e8bcf251d..afcce4241 100644 --- a/ros_gz_point_cloud/CMakeLists.txt +++ b/ros_gz_point_cloud/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) -project(ros_ign_point_cloud) +project(ros_gz_point_cloud) # Default to C++17 if(NOT CMAKE_CXX_STANDARD) @@ -15,13 +15,13 @@ find_package(catkin REQUIRED COMPONENTS sensor_msgs) find_package(ignition-gazebo2 2.1 QUIET REQUIRED) -set(IGN_GAZEBO_VER ${ignition-gazebo2_VERSION_MAJOR}) +set(GZ_SIM_VER ${ignition-gazebo2_VERSION_MAJOR}) find_package(ignition-rendering2 QUIET REQUIRED) -set(IGN_RENDERING_VER ${ignition-rendering2_VERSION_MAJOR}) +set(GZ_RENDERING_VER ${ignition-rendering2_VERSION_MAJOR}) find_package(ignition-sensors2 QUIET REQUIRED) -set(IGN_SENSORS_VER ${ignition-sensors2_VERSION_MAJOR}) +set(GZ_SENSORS_VER ${ignition-sensors2_VERSION_MAJOR}) catkin_package() @@ -30,14 +30,14 @@ include_directories( ${catkin_INCLUDE_DIRS} ) -set(plugin_name RosIgnPointCloud) +set(plugin_name RosGzPointCloud) add_library(${plugin_name} SHARED src/point_cloud.cc ) target_link_libraries(${plugin_name} - ignition-gazebo${IGN_GAZEBO_VER}::core - ignition-rendering${IGN_RENDERING_VER}::core - ignition-sensors${IGN_SENSORS_VER}::core + ignition-gazebo${GZ_SIM_VER}::core + ignition-rendering${GZ_RENDERING_VER}::core + ignition-sensors${GZ_SENSORS_VER}::core ${catkin_LIBRARIES} ) install(TARGETS ${plugin_name} @@ -52,3 +52,16 @@ install( ${CATKIN_PACKAGE_SHARE_DESTINATION}/examples ) +# TODO(CH3): Install symlink to deprecated library name. Remove on tock. +string(REPLACE "RosGz" "RosIgn" plugin_name_ign ${plugin_name}) +if(WIN32) + # symlinks on Windows require admin priviledges, fallback to copy + ADD_CUSTOM_COMMAND(TARGET ${plugin_name} POST_BUILD + COMMAND "${CMAKE_COMMAND}" -E copy + "$" + "$/${plugin_name_ign}") +else() + file(MAKE_DIRECTORY "${PROJECT_BINARY_DIR}/lib") + EXECUTE_PROCESS(COMMAND ${CMAKE_COMMAND} -E create_symlink ${plugin_name} ${plugin_name_ign} WORKING_DIRECTORY "${PROJECT_BINARY_DIR}/lib") + INSTALL(FILES ${PROJECT_BINARY_DIR}/lib/${plugin_name_ign} DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) +endif() diff --git a/ros_gz_point_cloud/examples/depth_camera.sdf b/ros_gz_point_cloud/examples/depth_camera.sdf index 5c47528f1..54e9b26ee 100644 --- a/ros_gz_point_cloud/examples/depth_camera.sdf +++ b/ros_gz_point_cloud/examples/depth_camera.sdf @@ -26,22 +26,22 @@ --> - + 0.001 1.0 ogre2 @@ -82,8 +82,8 @@ true true true - /world/ros_ign/control - /world/ros_ign/stats + /world/ros_gz/control + /world/ros_gz/stats @@ -108,7 +108,7 @@ true true true - /world/ros_ign/stats + /world/ros_gz/stats @@ -275,8 +275,8 @@ true depth_camera + filename="RosGzPointCloud" + name="ros_gz_point_cloud::PointCloud"> points map diff --git a/ros_gz_point_cloud/examples/gpu_lidar.sdf b/ros_gz_point_cloud/examples/gpu_lidar.sdf index f6a531d22..f25e3df11 100644 --- a/ros_gz_point_cloud/examples/gpu_lidar.sdf +++ b/ros_gz_point_cloud/examples/gpu_lidar.sdf @@ -26,22 +26,22 @@ --> - + 0.001 1.0 ogre2 @@ -82,8 +82,8 @@ true true true - /world/ros_ign/control - /world/ros_ign/stats + /world/ros_gz/control + /world/ros_gz/stats @@ -108,7 +108,7 @@ true true true - /world/ros_ign/stats + /world/ros_gz/stats @@ -278,8 +278,8 @@ 1 true + filename="RosGzPointCloud" + name="ros_gz_point_cloud::PointCloud"> custom_params pc2 custom_params/link diff --git a/ros_gz_point_cloud/examples/rgbd_camera.sdf b/ros_gz_point_cloud/examples/rgbd_camera.sdf index dd1282ee5..623a209f1 100644 --- a/ros_gz_point_cloud/examples/rgbd_camera.sdf +++ b/ros_gz_point_cloud/examples/rgbd_camera.sdf @@ -30,22 +30,22 @@ --> - + 0.001 1.0 ogre2 @@ -86,8 +86,8 @@ true true true - /world/ros_ign/control - /world/ros_ign/stats + /world/ros_gz/control + /world/ros_gz/stats @@ -112,7 +112,7 @@ true true true - /world/ros_ign/stats + /world/ros_gz/stats @@ -330,8 +330,8 @@ true custom_params + filename="RosGzPointCloud" + name="ros_gz_point_cloud::PointCloud"> custom_params pc2 map @@ -375,8 +375,8 @@ true rgbd_camera + filename="RosGzPointCloud" + name="ros_gz_point_cloud::PointCloud"> diff --git a/ros_gz_point_cloud/package.xml b/ros_gz_point_cloud/package.xml index 7a7b5add8..164baadd3 100644 --- a/ros_gz_point_cloud/package.xml +++ b/ros_gz_point_cloud/package.xml @@ -1,5 +1,5 @@ - ros_ign_point_cloud + ros_gz_point_cloud 0.7.0 Point cloud utilities for Ignition simulation with ROS. Apache 2.0 diff --git a/ros_gz_sim/CMakeLists.txt b/ros_gz_sim/CMakeLists.txt index a98a5b59b..4cc14adb4 100644 --- a/ros_gz_sim/CMakeLists.txt +++ b/ros_gz_sim/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) -project(ros_ign_gazebo) +project(ros_gz_sim) # Default to C++14 if(NOT CMAKE_CXX_STANDARD) @@ -86,17 +86,17 @@ target_link_libraries(create ament_target_dependencies(create std_msgs) configure_file( - launch/ign_gazebo.launch.py.in - launch/ign_gazebo.launch.py.configured + launch/gz_sim.launch.py.in + launch/gz_sim.launch.py.configured @ONLY ) file(GENERATE - OUTPUT "${CMAKE_CURRENT_BINARY_DIR}/launch/ign_gazebo.launch.py" - INPUT "${CMAKE_CURRENT_BINARY_DIR}/launch/ign_gazebo.launch.py.configured" + OUTPUT "${CMAKE_CURRENT_BINARY_DIR}/launch/gz_sim.launch.py" + INPUT "${CMAKE_CURRENT_BINARY_DIR}/launch/gz_sim.launch.py.configured" ) install(FILES - "${CMAKE_CURRENT_BINARY_DIR}/launch/ign_gazebo.launch.py" + "${CMAKE_CURRENT_BINARY_DIR}/launch/gz_sim.launch.py" DESTINATION share/${PROJECT_NAME}/launch ) diff --git a/ros_gz_sim/launch/gz_sim.launch.py.in b/ros_gz_sim/launch/gz_sim.launch.py.in index 7adb02ce5..e8ff4909b 100644 --- a/ros_gz_sim/launch/gz_sim.launch.py.in +++ b/ros_gz_sim/launch/gz_sim.launch.py.in @@ -12,7 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -"""Launch Ignition Gazebo with command line arguments.""" +"""Launch Gazebo Sim with command line arguments.""" from os import environ @@ -23,20 +23,37 @@ from launch.substitutions import LaunchConfiguration def generate_launch_description(): - env = {'IGN_GAZEBO_SYSTEM_PLUGIN_PATH': - ':'.join([environ.get('IGN_GAZEBO_SYSTEM_PLUGIN_PATH', default=''), - environ.get('LD_LIBRARY_PATH', default='')])} + env = {'GZ_SIM_SYSTEM_PLUGIN_PATH': + ':'.join([environ.get('GZ_SIM_SYSTEM_PLUGIN_PATH', default=''), + environ.get('LD_LIBRARY_PATH', default='')]), + 'IGN_GAZEBO_SYSTEM_PLUGIN_PATH': # TODO(CH3): To support pre-garden. Deprecated. + ':'.join([environ.get('IGN_GAZEBO_SYSTEM_PLUGIN_PATH', default=''), + environ.get('LD_LIBRARY_PATH', default='')])} return LaunchDescription([ - DeclareLaunchArgument('ign_args', default_value='', - description='Arguments to be passed to Ignition Gazebo'), - # Ignition Gazebo's major version - DeclareLaunchArgument('ign_version', default_value='@IGN_GAZEBO_VER@', - description='Ignition Gazebo\'s major version'), + DeclareLaunchArgument('gz_args', default_value='', + description='Arguments to be passed to Gazebo Sim'), + # Gazebo Sim's major version + DeclareLaunchArgument('gz_version', default_value='@GZ_SIM_VER@', + description='Gazebo Sim\'s major version'), + + # TODO(CH3): Deprecated. Remove on tock. + DeclareLaunchArgument( + 'ign_args', default_value='', + description='Deprecated: Arguments to be passed to Gazebo Sim' + ), + # Gazebo Sim's major version + DeclareLaunchArgument( + 'ign_version', default_value='@GZ_SIM_VER@', + description='Deprecated: Gazebo Sim\'s major version' + ), + ExecuteProcess( - cmd=['ign gazebo', + cmd=['gz sim', + LaunchConfiguration('gz_args'), LaunchConfiguration('ign_args'), '--force-version', + LaunchConfiguration('gz_version'), LaunchConfiguration('ign_version'), ], output='screen', diff --git a/ros_gz_sim/package.xml b/ros_gz_sim/package.xml index e54b6b5aa..634b9286a 100644 --- a/ros_gz_sim/package.xml +++ b/ros_gz_sim/package.xml @@ -1,7 +1,7 @@ - ros_ign_gazebo + ros_gz_sim 0.244.3 Tools for using Ignition Gazebo simulation with ROS. Alejandro Hernandez diff --git a/ros_gz_sim/src/create.cpp b/ros_gz_sim/src/create.cpp index 6e1204a03..d26bffc0f 100644 --- a/ros_gz_sim/src/create.cpp +++ b/ros_gz_sim/src/create.cpp @@ -58,7 +58,7 @@ int main(int _argc, char ** _argv) // World std::string world_name = FLAGS_world; if (world_name.empty()) { - // If caller doesn't provide a world name, get list of worlds from ign-gazebo server + // If caller doesn't provide a world name, get list of worlds from gz-sim server ignition::transport::Node node; bool executed{false}; diff --git a/ros_gz_sim_demos/CMakeLists.txt b/ros_gz_sim_demos/CMakeLists.txt index bf6a72532..387545634 100644 --- a/ros_gz_sim_demos/CMakeLists.txt +++ b/ros_gz_sim_demos/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) -project(ros_ign_gazebo_demos) +project(ros_gz_sim_demos) find_package(ament_cmake REQUIRED) diff --git a/ros_gz_sim_demos/launch/air_pressure.launch.py b/ros_gz_sim_demos/launch/air_pressure.launch.py index ccaa72519..272d6eb1a 100644 --- a/ros_gz_sim_demos/launch/air_pressure.launch.py +++ b/ros_gz_sim_demos/launch/air_pressure.launch.py @@ -12,7 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -"""Launch Ignition Gazebo with command line arguments.""" +"""Launch Gazebo Sim with command line arguments.""" import os @@ -30,21 +30,21 @@ def generate_launch_description(): - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['/air_pressure@sensor_msgs/msg/FluidPressure@ignition.msgs.FluidPressure'], parameters=[{'qos_overrides./air_pressure.publisher.reliability': 'best_effort'}], output='screen' ) - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), - launch_arguments={'ign_args': '-r sensors.sdf'}.items(), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={'gz_args': '-r sensors.sdf'}.items(), ) # RQt @@ -55,7 +55,7 @@ def generate_launch_description(): condition=IfCondition(LaunchConfiguration('rqt')) ) return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rqt', default_value='true', description='Open RQt.'), bridge, diff --git a/ros_gz_sim_demos/launch/battery.launch.py b/ros_gz_sim_demos/launch/battery.launch.py index 239e14a2a..4e32322a7 100644 --- a/ros_gz_sim_demos/launch/battery.launch.py +++ b/ros_gz_sim_demos/launch/battery.launch.py @@ -28,7 +28,7 @@ def generate_launch_description(): - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') # RQt rqt = Node( @@ -40,17 +40,17 @@ def generate_launch_description(): condition=IfCondition(LaunchConfiguration('rqt')) ) - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), launch_arguments={ - 'ign_args': '-r -z 1000000 linear_battery_demo.sdf' + 'gz_args': '-r -z 1000000 linear_battery_demo.sdf' }.items(), ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=[ '/model/vehicle_blue/cmd_vel@geometry_msgs/msg/Twist@ignition.msgs.Twist', @@ -61,7 +61,7 @@ def generate_launch_description(): ) return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rqt', default_value='true', description='Open RQt.'), bridge, diff --git a/ros_gz_sim_demos/launch/camera.launch.py b/ros_gz_sim_demos/launch/camera.launch.py index 903096e47..1bd9a8a0b 100644 --- a/ros_gz_sim_demos/launch/camera.launch.py +++ b/ros_gz_sim_demos/launch/camera.launch.py @@ -28,26 +28,26 @@ def generate_launch_description(): - pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos') - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), - launch_arguments={'ign_args': '-r camera_sensor.sdf'}.items(), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={'gz_args': '-r camera_sensor.sdf'}.items(), ) # RViz rviz = Node( package='rviz2', executable='rviz2', - arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'camera.rviz')], + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'camera.rviz')], condition=IfCondition(LaunchConfiguration('rviz')) ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['/camera@sensor_msgs/msg/Image@ignition.msgs.Image', '/camera_info@sensor_msgs/msg/CameraInfo@ignition.msgs.CameraInfo'], @@ -57,7 +57,7 @@ def generate_launch_description(): return LaunchDescription([ DeclareLaunchArgument('rviz', default_value='true', description='Open RViz.'), - ign_gazebo, + gz_sim, bridge, rviz ]) diff --git a/ros_gz_sim_demos/launch/depth_camera.launch.py b/ros_gz_sim_demos/launch/depth_camera.launch.py index d025c695c..d42ce8627 100644 --- a/ros_gz_sim_demos/launch/depth_camera.launch.py +++ b/ros_gz_sim_demos/launch/depth_camera.launch.py @@ -28,14 +28,14 @@ def generate_launch_description(): - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py') + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py') ), # launch_arguments={ - # 'ign_args': '-r depth_camera.sdf' + # 'gz_args': '-r depth_camera.sdf' # }.items(), ) @@ -52,21 +52,21 @@ def generate_launch_description(): package='rviz2', executable='rviz2', # FIXME: Generate new RViz config once this demo is usable again - # arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'depth_camera.rviz')], + # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'depth_camera.rviz')], condition=IfCondition(LaunchConfiguration('rviz')) ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['/depth_camera@sensor_msgs/msg/Image@ignition.msgs.Image'], output='screen' ) - # FIXME: need a SDF file (depth_camera.sdf) inside ros_ign_point_cloud + # FIXME: need a SDF file (depth_camera.sdf) inside ros_gz_point_cloud return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rviz', default_value='true', description='Open RViz.'), DeclareLaunchArgument('rqt', default_value='true', diff --git a/ros_gz_sim_demos/launch/diff_drive.launch.py b/ros_gz_sim_demos/launch/diff_drive.launch.py index 9cac29d1a..8a2975670 100644 --- a/ros_gz_sim_demos/launch/diff_drive.launch.py +++ b/ros_gz_sim_demos/launch/diff_drive.launch.py @@ -28,14 +28,14 @@ def generate_launch_description(): - pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos') - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), launch_arguments={ - 'ign_args': '-r diff_drive.sdf' + 'gz_args': '-r diff_drive.sdf' }.items(), ) @@ -43,13 +43,13 @@ def generate_launch_description(): rviz = Node( package='rviz2', executable='rviz2', - arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'diff_drive.rviz')], + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'diff_drive.rviz')], condition=IfCondition(LaunchConfiguration('rviz')) ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['/model/vehicle_blue/cmd_vel@geometry_msgs/msg/Twist@ignition.msgs.Twist', '/model/vehicle_blue/odometry@nav_msgs/msg/Odometry@ignition.msgs.Odometry', @@ -61,7 +61,7 @@ def generate_launch_description(): ) return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rviz', default_value='true', description='Open RViz.'), bridge, diff --git a/ros_gz_sim_demos/launch/gpu_lidar.launch.py b/ros_gz_sim_demos/launch/gpu_lidar.launch.py index 095a0a810..5cfdb08f8 100644 --- a/ros_gz_sim_demos/launch/gpu_lidar.launch.py +++ b/ros_gz_sim_demos/launch/gpu_lidar.launch.py @@ -28,13 +28,13 @@ def generate_launch_description(): - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), # launch_arguments={ - # 'ign_args': '-r gpu_lidar.sdf' + # 'gz_args': '-r gpu_lidar.sdf' # }.items(), ) @@ -43,21 +43,21 @@ def generate_launch_description(): package='rviz2', executable='rviz2', # FIXME: Generate new RViz config once this demo is usable again - # arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'gpu_lidar.rviz')], + # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'gpu_lidar.rviz')], condition=IfCondition(LaunchConfiguration('rviz')) ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['/lidar@sensor_msgs/msg/LaserScan@ignition.msgs.LaserScan/'], output='screen' ) - # FIXME: need a SDF file (gpu_lidar.sdf) inside ros_ign_point_cloud/ + # FIXME: need a SDF file (gpu_lidar.sdf) inside ros_gz_point_cloud/ return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rviz', default_value='true', description='Open RViz.'), bridge, diff --git a/ros_gz_sim_demos/launch/gpu_lidar_bridge.launch.py b/ros_gz_sim_demos/launch/gpu_lidar_bridge.launch.py index d45381b05..26bd36b80 100644 --- a/ros_gz_sim_demos/launch/gpu_lidar_bridge.launch.py +++ b/ros_gz_sim_demos/launch/gpu_lidar_bridge.launch.py @@ -28,14 +28,14 @@ def generate_launch_description(): - pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos') - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), launch_arguments={ - 'ign_args': '-r gpu_lidar_sensor.sdf' + 'gz_args': '-r gpu_lidar_sensor.sdf' }.items(), ) @@ -43,13 +43,13 @@ def generate_launch_description(): rviz = Node( package='rviz2', executable='rviz2', - arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'gpu_lidar_bridge.rviz')], + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'gpu_lidar_bridge.rviz')], condition=IfCondition(LaunchConfiguration('rviz')) ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['lidar@sensor_msgs/msg/LaserScan@ignition.msgs.LaserScan', '/lidar/points@sensor_msgs/msg/PointCloud2@ignition.msgs.PointCloudPacked'], @@ -57,7 +57,7 @@ def generate_launch_description(): ) return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rviz', default_value='true', description='Open RViz.'), bridge, diff --git a/ros_gz_sim_demos/launch/image_bridge.launch.py b/ros_gz_sim_demos/launch/image_bridge.launch.py index 642deb70e..91e81e330 100644 --- a/ros_gz_sim_demos/launch/image_bridge.launch.py +++ b/ros_gz_sim_demos/launch/image_bridge.launch.py @@ -28,13 +28,13 @@ def generate_launch_description(): - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), launch_arguments={ - 'ign_args': '-r sensors_demo.sdf' + 'gz_args': '-r sensors_demo.sdf' }.items(), ) @@ -48,14 +48,14 @@ def generate_launch_description(): # Bridge bridge = Node( - package='ros_ign_image', + package='ros_gz_image', executable='image_bridge', arguments=['camera', 'depth_camera', 'rgbd_camera/image', 'rgbd_camera/depth_image'], output='screen' ) return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rqt', default_value='true', description='Open RQt.'), DeclareLaunchArgument('image_topic', default_value='/camera', diff --git a/ros_gz_sim_demos/launch/imu.launch.py b/ros_gz_sim_demos/launch/imu.launch.py index 4d2d524f6..649ad359f 100644 --- a/ros_gz_sim_demos/launch/imu.launch.py +++ b/ros_gz_sim_demos/launch/imu.launch.py @@ -28,13 +28,13 @@ def generate_launch_description(): - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), launch_arguments={ - 'ign_args': '-r sensors.sdf' + 'gz_args': '-r sensors.sdf' }.items(), ) @@ -48,24 +48,24 @@ def generate_launch_description(): # RViz # FIXME: Add once there's an IMU display for RViz2 - # pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos') + # pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') # rviz = Node( # package='rviz2', # executable='rviz2', - # # arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'imu.rviz')], + # # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'imu.rviz')], # condition=IfCondition(LaunchConfiguration('rviz')) # ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['/imu@sensor_msgs/msg/Imu@ignition.msgs.IMU'], output='screen' ) return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument( 'rqt', default_value='true', description='Open RQt.' ), diff --git a/ros_gz_sim_demos/launch/joint_states.launch.py b/ros_gz_sim_demos/launch/joint_states.launch.py index a9dbac82c..20b330ec1 100644 --- a/ros_gz_sim_demos/launch/joint_states.launch.py +++ b/ros_gz_sim_demos/launch/joint_states.launch.py @@ -25,11 +25,11 @@ def generate_launch_description(): # Package Directories - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') - pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') # Parse robot description from xacro - robot_description_file = os.path.join(pkg_ros_ign_gazebo_demos, 'models', 'rrbot.xacro') + robot_description_file = os.path.join(pkg_ros_gz_sim_demos, 'models', 'rrbot.xacro') robot_description_config = xacro.process_file( robot_description_file ) @@ -44,24 +44,24 @@ def generate_launch_description(): parameters=[robot_description], ) - # Ignition gazebo + # Gazebo Sim gazebo = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py') + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py') ), - launch_arguments={'ign_args': '-r empty.sdf'}.items(), + launch_arguments={'gz_args': '-r empty.sdf'}.items(), ) # RViz rviz = Node( package='rviz2', executable='rviz2', - arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'joint_states.rviz')], + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'joint_states.rviz')], ) # Spawn spawn = Node( - package='ros_ign_gazebo', + package='ros_gz_sim', executable='create', arguments=[ '-name', 'rrbot', @@ -70,9 +70,9 @@ def generate_launch_description(): output='screen', ) - # Ign - ROS Bridge + # Gz - ROS Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=[ # Clock (IGN -> ROS2) diff --git a/ros_gz_sim_demos/launch/magnetometer.launch.py b/ros_gz_sim_demos/launch/magnetometer.launch.py index 155643470..0e026676a 100644 --- a/ros_gz_sim_demos/launch/magnetometer.launch.py +++ b/ros_gz_sim_demos/launch/magnetometer.launch.py @@ -28,13 +28,13 @@ def generate_launch_description(): - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), launch_arguments={ - 'ign_args': '-r sensors.sdf' + 'gz_args': '-r sensors.sdf' }.items(), ) @@ -48,14 +48,14 @@ def generate_launch_description(): # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['/magnetometer@sensor_msgs/msg/MagneticField@ignition.msgs.Magnetometer'], output='screen' ) return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rqt', default_value='true', description='Open RQt.'), bridge, diff --git a/ros_gz_sim_demos/launch/rgbd_camera.launch.py b/ros_gz_sim_demos/launch/rgbd_camera.launch.py index 39453647f..1ec8409bc 100644 --- a/ros_gz_sim_demos/launch/rgbd_camera.launch.py +++ b/ros_gz_sim_demos/launch/rgbd_camera.launch.py @@ -26,13 +26,13 @@ def generate_launch_description(): - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), # launch_arguments={ - # 'ign_args': '-r rgbd_camera.sdf' + # 'gz_args': '-r rgbd_camera.sdf' # }.items(), ) @@ -40,22 +40,22 @@ def generate_launch_description(): # rviz = Node( # package='rviz2', # executable='rviz2', - # arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'rgbd_camera.rviz')], + # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'rgbd_camera.rviz')], # condition=IfCondition(LaunchConfiguration('rviz')) # ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['/rgbd_camera/image@sensor_msgs/msg/Image@ignition.msgs.Image', '/rgbd_camera/depth_image@sensor_msgs/msg/Image@ignition.msgs.Image'], output='screen' ) - # FIXME: need a SDF file (depth_camera.sdf) inside ros_ign_point_cloud/ + # FIXME: need a SDF file (depth_camera.sdf) inside ros_gz_point_cloud/ return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rviz', default_value='true', description='Open RViz.'), bridge, diff --git a/ros_gz_sim_demos/launch/rgbd_camera_bridge.launch.py b/ros_gz_sim_demos/launch/rgbd_camera_bridge.launch.py index 07faece84..a318f6826 100644 --- a/ros_gz_sim_demos/launch/rgbd_camera_bridge.launch.py +++ b/ros_gz_sim_demos/launch/rgbd_camera_bridge.launch.py @@ -28,14 +28,14 @@ def generate_launch_description(): - pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos') - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), launch_arguments={ - 'ign_args': '-r sensors_demo.sdf' + 'gz_args': '-r sensors_demo.sdf' }.items(), ) @@ -44,14 +44,14 @@ def generate_launch_description(): package='rviz2', executable='rviz2', arguments=[ - '-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'rgbd_camera_bridge.rviz') + '-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'rgbd_camera_bridge.rviz') ], condition=IfCondition(LaunchConfiguration('rviz')) ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=[ '/rgbd_camera/image@sensor_msgs/msg/Image@ignition.msgs.Image', @@ -62,7 +62,7 @@ def generate_launch_description(): ) return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rviz', default_value='true', description='Open RViz.'), bridge, diff --git a/ros_gz_sim_demos/launch/robot_description_publisher.launch.py b/ros_gz_sim_demos/launch/robot_description_publisher.launch.py index 4f9d94e3a..882cdee38 100755 --- a/ros_gz_sim_demos/launch/robot_description_publisher.launch.py +++ b/ros_gz_sim_demos/launch/robot_description_publisher.launch.py @@ -56,27 +56,27 @@ def generate_launch_description(): parameters=[params], arguments=[]) - # Ignition gazebo - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + # Gazebo Sim + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') gazebo = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), - launch_arguments={'ign_args': '-r empty.sdf'}.items(), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={'gz_args': '-r empty.sdf'}.items(), ) # RViz - pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') rviz = Node( package='rviz2', executable='rviz2', arguments=[ '-d', - os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'robot_description_publisher.rviz') + os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'robot_description_publisher.rviz') ] ) # Spawn - spawn = Node(package='ros_ign_gazebo', executable='create', + spawn = Node(package='ros_gz_sim', executable='create', arguments=[ '-name', 'my_custom_model', '-x', '1.2', diff --git a/ros_gz_sim_demos/launch/tf_bridge.launch.py b/ros_gz_sim_demos/launch/tf_bridge.launch.py index ae995704c..3b2171d09 100644 --- a/ros_gz_sim_demos/launch/tf_bridge.launch.py +++ b/ros_gz_sim_demos/launch/tf_bridge.launch.py @@ -22,14 +22,14 @@ def generate_launch_description(): - pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') return LaunchDescription([ # Launch gazebo ExecuteProcess( cmd=[ 'ign', 'gazebo', '-r', os.path.join( - pkg_ros_ign_gazebo_demos, + pkg_ros_gz_sim_demos, 'models', 'double_pendulum_model.sdf' ) @@ -37,7 +37,7 @@ def generate_launch_description(): ), # Launch a bridge to forward tf and joint states to ros2 Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=[ '/world/default/model/double_pendulum_with_base0/joint_state@' @@ -54,6 +54,6 @@ def generate_launch_description(): Node( package='rviz2', executable='rviz2', - arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'tf_bridge.rviz')] + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'tf_bridge.rviz')] ) ]) diff --git a/ros_gz_sim_demos/launch/triggered_camera.launch.py b/ros_gz_sim_demos/launch/triggered_camera.launch.py index 4f3d7a85f..9e6362a2d 100644 --- a/ros_gz_sim_demos/launch/triggered_camera.launch.py +++ b/ros_gz_sim_demos/launch/triggered_camera.launch.py @@ -28,26 +28,26 @@ def generate_launch_description(): - pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos') - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), - launch_arguments={'ign_args': '-r triggered_camera_sensor.sdf'}.items(), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={'gz_args': '-r triggered_camera_sensor.sdf'}.items(), ) # RViz rviz = Node( package='rviz2', executable='rviz2', - arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'camera.rviz')], + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'camera.rviz')], condition=IfCondition(LaunchConfiguration('rviz')) ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['/camera@sensor_msgs/msg/Image@ignition.msgs.Image', '/camera/trigger@std_msgs/msg/Bool@ignition.msgs.Boolean', @@ -58,7 +58,7 @@ def generate_launch_description(): return LaunchDescription([ DeclareLaunchArgument('rviz', default_value='true', description='Open RViz.'), - ign_gazebo, + gz_sim, bridge, rviz ]) diff --git a/ros_gz_sim_demos/models/rrbot.xacro b/ros_gz_sim_demos/models/rrbot.xacro index 782154e39..00680c14c 100644 --- a/ros_gz_sim_demos/models/rrbot.xacro +++ b/ros_gz_sim_demos/models/rrbot.xacro @@ -159,7 +159,7 @@ - + \ No newline at end of file diff --git a/ros_gz_sim_demos/package.xml b/ros_gz_sim_demos/package.xml index a2ba4628e..c0f446a77 100644 --- a/ros_gz_sim_demos/package.xml +++ b/ros_gz_sim_demos/package.xml @@ -1,5 +1,5 @@ - ros_ign_gazebo_demos + ros_gz_sim_demos 0.244.3 Demos using Ignition Gazebo simulation with ROS. Apache 2.0 @@ -15,11 +15,11 @@ image_transport_plugins robot_state_publisher - ros_ign_bridge - ros_ign_gazebo - ros_ign_image - - + ros_gz_bridge + ros_gz_sim + ros_gz_image + + rqt_image_view rqt_plot rqt_topic