From 1f936b99448fc668c4cbf113dd6b60e37b6101cb Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 25 Jul 2022 16:17:47 -0700 Subject: [PATCH 1/2] 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 | 12 +- ros_gz_bridge/CMakeLists.txt | 38 ++--- .../include/ros_gz_bridge/convert.hpp | 22 +-- .../convert/builtin_interfaces.hpp | 8 +- .../ros_gz_bridge/convert/geometry_msgs.hpp | 8 +- .../ros_gz_bridge/convert/nav_msgs.hpp | 8 +- .../convert/ros_gz_interfaces.hpp | 74 ++++----- .../ros_gz_bridge/convert/rosgraph_msgs.hpp | 8 +- .../ros_gz_bridge/convert/sensor_msgs.hpp | 8 +- .../ros_gz_bridge/convert/std_msgs.hpp | 8 +- .../ros_gz_bridge/convert/tf2_msgs.hpp | 8 +- .../ros_gz_bridge/convert/trajectory_msgs.hpp | 8 +- .../include/ros_gz_bridge/convert_decl.hpp | 6 +- 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 | 82 +++++----- 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 | 8 +- .../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 | 146 +++++++++--------- .../src/factories/ros_gz_interfaces.hpp | 8 +- 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 | 18 +-- .../service_factories/ros_gz_interfaces.hpp | 8 +- 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 | 54 +++---- ros_gz_bridge/test/serverclient/gz_server.cpp | 2 +- .../test/serverclient/ros_client.cpp | 6 +- .../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/gz_test_msg.hpp | 6 +- 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_image/test/test_utils.h | 6 +- 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_point_cloud/src/point_cloud.hh | 4 +- ros_gz_sim/CMakeLists.txt | 12 +- ros_gz_sim/launch/gz_sim.launch.py.in | 51 ++++-- 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 | 10 +- 96 files changed, 702 insertions(+), 658 deletions(-) diff --git a/ros_gz/CMakeLists.txt b/ros_gz/CMakeLists.txt index 80524e92..db4e01a7 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 014ad199..16d8df6a 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 Gazebo simulation. Louise Poubel @@ -11,12 +11,12 @@ ament_cmake - ros_ign_bridge - ros_ign_gazebo - ros_ign_gazebo_demos - ros_ign_image + ros_gz_bridge + ros_gz_gazebo + ros_gz_gazebo_demos + ros_gz_image - + ament_lint_auto ament_lint_common diff --git a/ros_gz_bridge/CMakeLists.txt b/ros_gz_bridge/CMakeLists.txt index d3d45161..57249f0f 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) @@ -67,7 +67,7 @@ set(PACKAGES builtin_interfaces geometry_msgs nav_msgs - ros_ign_interfaces + ros_gz_interfaces rosgraph_msgs sensor_msgs std_msgs @@ -114,14 +114,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} @@ -173,7 +173,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 ) @@ -190,7 +190,7 @@ if(BUILD_TESTING) geometry_msgs nav_msgs rclcpp - ros_ign_interfaces + ros_gz_interfaces rosgraph_msgs sensor_msgs std_msgs @@ -206,7 +206,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 @@ -214,14 +214,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) @@ -230,9 +230,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} ) @@ -240,11 +240,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 7d0d0e3f..b426c3c0 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert.hpp @@ -12,16 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT_HPP_ -#define ROS_IGN_BRIDGE__CONVERT_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT_HPP_ +#define ROS_GZ_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_ +#endif // ROS_GZ_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 9fcd2d3c..a2b1999e 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 @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT__BUILTIN_INTERFACES_HPP_ -#define ROS_IGN_BRIDGE__CONVERT__BUILTIN_INTERFACES_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT__BUILTIN_INTERFACES_HPP_ +#define ROS_GZ_BRIDGE__CONVERT__BUILTIN_INTERFACES_HPP_ #include #include -#include "ros_ign_bridge/convert_decl.hpp" +#include "ros_gz_bridge/convert_decl.hpp" namespace ros_gz_bridge { @@ -38,4 +38,4 @@ convert_gz_to_ros( } // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT__BUILTIN_INTERFACES_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT__BUILTIN_INTERFACES_HPP_ 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 4d4a334c..e67ee598 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 @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT__GEOMETRY_MSGS_HPP_ -#define ROS_IGN_BRIDGE__CONVERT__GEOMETRY_MSGS_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT__GEOMETRY_MSGS_HPP_ +#define ROS_GZ_BRIDGE__CONVERT__GEOMETRY_MSGS_HPP_ // Gazebo Msgs #include @@ -36,7 +36,7 @@ #include #include -#include +#include namespace ros_gz_bridge { @@ -176,4 +176,4 @@ convert_gz_to_ros( } // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT__GEOMETRY_MSGS_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT__GEOMETRY_MSGS_HPP_ 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 8dcdfbb3..4c52c5b9 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 @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT__NAV_MSGS_HPP_ -#define ROS_IGN_BRIDGE__CONVERT__NAV_MSGS_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT__NAV_MSGS_HPP_ +#define ROS_GZ_BRIDGE__CONVERT__NAV_MSGS_HPP_ // Gazebo Msgs #include @@ -22,7 +22,7 @@ // ROS 2 messages #include -#include +#include namespace ros_gz_bridge { @@ -53,4 +53,4 @@ convert_gz_to_ros( } // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT__NAV_MSGS_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT__NAV_MSGS_HPP_ 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 aebca3a7..0fe64821 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 @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT__ROS_IGN_INTERFACES_HPP_ -#define ROS_IGN_BRIDGE__CONVERT__ROS_IGN_INTERFACES_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT__ROS_GZ_INTERFACES_HPP_ +#define ROS_GZ_BRIDGE__CONVERT__ROS_GZ_INTERFACES_HPP_ // Gazebo Msgs #include @@ -28,18 +28,18 @@ #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_gz_bridge { @@ -47,134 +47,134 @@ namespace ros_gz_bridge template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::JointWrench & ros_msg, + const ros_gz_interfaces::msg::JointWrench & ros_msg, ignition::msgs::JointWrench & gz_msg); template<> void convert_gz_to_ros( const ignition::msgs::JointWrench & gz_msg, - ros_ign_interfaces::msg::JointWrench & ros_msg); + ros_gz_interfaces::msg::JointWrench & ros_msg); template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::Entity & ros_msg, + const ros_gz_interfaces::msg::Entity & ros_msg, ignition::msgs::Entity & gz_msg); template<> void convert_gz_to_ros( const ignition::msgs::Entity & gz_msg, - ros_ign_interfaces::msg::Entity & ros_msg); + ros_gz_interfaces::msg::Entity & ros_msg); template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::Contact & ros_msg, + const ros_gz_interfaces::msg::Contact & ros_msg, ignition::msgs::Contact & gz_msg); template<> void convert_gz_to_ros( const ignition::msgs::Contact & gz_msg, - ros_ign_interfaces::msg::Contact & ros_msg); + ros_gz_interfaces::msg::Contact & ros_msg); template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::Contacts & ros_msg, + const ros_gz_interfaces::msg::Contacts & ros_msg, ignition::msgs::Contacts & gz_msg); template<> void convert_gz_to_ros( const ignition::msgs::Contacts & gz_msg, - ros_ign_interfaces::msg::Contacts & ros_msg); + ros_gz_interfaces::msg::Contacts & ros_msg); template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::GuiCamera & ros_msg, + const ros_gz_interfaces::msg::GuiCamera & ros_msg, ignition::msgs::GUICamera & gz_msg); template<> void convert_gz_to_ros( const ignition::msgs::GUICamera & gz_msg, - ros_ign_interfaces::msg::GuiCamera & ros_msg); + ros_gz_interfaces::msg::GuiCamera & ros_msg); template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::Light & ros_msg, + const ros_gz_interfaces::msg::Light & ros_msg, ignition::msgs::Light & gz_msg); template<> void convert_gz_to_ros( const ignition::msgs::Light & gz_msg, - ros_ign_interfaces::msg::Light & ros_msg); + ros_gz_interfaces::msg::Light & ros_msg); template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::StringVec & ros_msg, + const ros_gz_interfaces::msg::StringVec & ros_msg, ignition::msgs::StringMsg_V & gz_msg); template<> void convert_gz_to_ros( const ignition::msgs::StringMsg_V & gz_msg, - ros_ign_interfaces::msg::StringVec & ros_msg); + ros_gz_interfaces::msg::StringVec & ros_msg); template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::TrackVisual & ros_msg, + const ros_gz_interfaces::msg::TrackVisual & ros_msg, ignition::msgs::TrackVisual & gz_msg); template<> void convert_gz_to_ros( const ignition::msgs::TrackVisual & gz_msg, - ros_ign_interfaces::msg::TrackVisual & ros_msg); + ros_gz_interfaces::msg::TrackVisual & ros_msg); template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::VideoRecord & ros_msg, + const ros_gz_interfaces::msg::VideoRecord & ros_msg, ignition::msgs::VideoRecord & gz_msg); template<> void convert_gz_to_ros( const ignition::msgs::VideoRecord & gz_msg, - ros_ign_interfaces::msg::VideoRecord & ros_msg); + ros_gz_interfaces::msg::VideoRecord & ros_msg); template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::WorldControl & ros_msg, + const ros_gz_interfaces::msg::WorldControl & ros_msg, ignition::msgs::WorldControl & gz_msg); template<> void convert_gz_to_ros( const ignition::msgs::WorldControl & gz_msg, - ros_ign_interfaces::msg::WorldControl & ros_msg); + ros_gz_interfaces::msg::WorldControl & ros_msg); template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::WorldReset & ros_msg, + const ros_gz_interfaces::msg::WorldReset & ros_msg, ignition::msgs::WorldReset & gz_msg); template<> void convert_gz_to_ros( const ignition::msgs::WorldReset & gz_msg, - ros_ign_interfaces::msg::WorldReset & ros_msg); + ros_gz_interfaces::msg::WorldReset & ros_msg); } // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT__ROS_IGN_INTERFACES_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT__ROS_GZ_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 e1d69d03..c67073bb 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 @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT__ROSGRAPH_MSGS_HPP_ -#define ROS_IGN_BRIDGE__CONVERT__ROSGRAPH_MSGS_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT__ROSGRAPH_MSGS_HPP_ +#define ROS_GZ_BRIDGE__CONVERT__ROSGRAPH_MSGS_HPP_ // Gazebo Msgs #include @@ -21,7 +21,7 @@ // ROS 2 messages #include -#include +#include namespace ros_gz_bridge { @@ -40,4 +40,4 @@ convert_ros_to_gz( } // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT__ROSGRAPH_MSGS_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT__ROSGRAPH_MSGS_HPP_ 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 cd78aa84..de6724f4 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 @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT__SENSOR_MSGS_HPP_ -#define ROS_IGN_BRIDGE__CONVERT__SENSOR_MSGS_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT__SENSOR_MSGS_HPP_ +#define ROS_GZ_BRIDGE__CONVERT__SENSOR_MSGS_HPP_ // Gazebo Msgs #include @@ -37,7 +37,7 @@ #include #include -#include +#include namespace ros_gz_bridge { @@ -153,4 +153,4 @@ convert_gz_to_ros( } // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT__SENSOR_MSGS_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT__SENSOR_MSGS_HPP_ 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 f09d58d9..155a7cdd 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 @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT__STD_MSGS_HPP_ -#define ROS_IGN_BRIDGE__CONVERT__STD_MSGS_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT__STD_MSGS_HPP_ +#define ROS_GZ_BRIDGE__CONVERT__STD_MSGS_HPP_ // Gazebo Msgs #include @@ -37,7 +37,7 @@ #include #include -#include +#include namespace ros_gz_bridge { @@ -152,4 +152,4 @@ convert_gz_to_ros( } // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT__STD_MSGS_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT__STD_MSGS_HPP_ 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 33bd760c..a254df5c 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 @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT__TF2_MSGS_HPP_ -#define ROS_IGN_BRIDGE__CONVERT__TF2_MSGS_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT__TF2_MSGS_HPP_ +#define ROS_GZ_BRIDGE__CONVERT__TF2_MSGS_HPP_ // Gazebo Msgs #include @@ -21,7 +21,7 @@ // ROS 2 messages #include -#include +#include namespace ros_gz_bridge { @@ -40,4 +40,4 @@ convert_gz_to_ros( } // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT__TF2_MSGS_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT__TF2_MSGS_HPP_ 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 ab299cfc..f3efbbe2 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 @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT__TRAJECTORY_MSGS_HPP_ -#define ROS_IGN_BRIDGE__CONVERT__TRAJECTORY_MSGS_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT__TRAJECTORY_MSGS_HPP_ +#define ROS_GZ_BRIDGE__CONVERT__TRAJECTORY_MSGS_HPP_ // Gazebo Msgs #include @@ -21,7 +21,7 @@ // ROS 2 messages #include -#include +#include namespace ros_gz_bridge { @@ -53,4 +53,4 @@ convert_gz_to_ros( } // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT__TRAJECTORY_MSGS_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT__TRAJECTORY_MSGS_HPP_ diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert_decl.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert_decl.hpp index 51711bbb..31419975 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert_decl.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert_decl.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT_DECL_HPP_ -#define ROS_IGN_BRIDGE__CONVERT_DECL_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT_DECL_HPP_ +#define ROS_GZ_BRIDGE__CONVERT_DECL_HPP_ namespace ros_gz_bridge { @@ -32,4 +32,4 @@ convert_gz_to_ros( } // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT_DECL_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT_DECL_HPP_ diff --git a/ros_gz_bridge/package.xml b/ros_gz_bridge/package.xml index 75991a90..8c4119a4 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 Gazebo 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 d24ad001..fa5548eb 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_gz_bridge { diff --git a/ros_gz_bridge/src/convert/geometry_msgs.cpp b/ros_gz_bridge/src/convert/geometry_msgs.cpp index 1dd827cd..039d5bd2 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_gz_bridge { diff --git a/ros_gz_bridge/src/convert/nav_msgs.cpp b/ros_gz_bridge/src/convert/nav_msgs.cpp index 99e423c3..092ac3f1 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_gz_bridge { diff --git a/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp b/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp index 82e6e040..6b282bbb 100644 --- a/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp +++ b/ros_gz_bridge/src/convert/ros_gz_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/ros_ign_interfaces.hpp" +#include "ros_gz_bridge/convert/ros_gz_interfaces.hpp" namespace ros_gz_bridge { @@ -20,7 +20,7 @@ namespace ros_gz_bridge template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::JointWrench & ros_msg, + const ros_gz_interfaces::msg::JointWrench & ros_msg, ignition::msgs::JointWrench & gz_msg) { convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); @@ -36,7 +36,7 @@ template<> void convert_gz_to_ros( const ignition::msgs::JointWrench & gz_msg, - ros_ign_interfaces::msg::JointWrench & ros_msg) + ros_gz_interfaces::msg::JointWrench & ros_msg) { convert_gz_to_ros(gz_msg.header(), ros_msg.header); ros_msg.body_1_name.data = gz_msg.body_1_name(); @@ -50,34 +50,34 @@ convert_gz_to_ros( template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::Entity & ros_msg, + const ros_gz_interfaces::msg::Entity & ros_msg, ignition::msgs::Entity & gz_msg) { gz_msg.set_id(ros_msg.id); gz_msg.set_name(ros_msg.name); switch (ros_msg.type) { - case ros_ign_interfaces::msg::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: + case ros_gz_interfaces::msg::Entity::LIGHT: gz_msg.set_type(ignition::msgs::Entity::LIGHT); break; - case ros_ign_interfaces::msg::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: + case ros_gz_interfaces::msg::Entity::LINK: gz_msg.set_type(ignition::msgs::Entity::LINK); break; - case ros_ign_interfaces::msg::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: + case ros_gz_interfaces::msg::Entity::COLLISION: gz_msg.set_type(ignition::msgs::Entity::COLLISION); break; - case ros_ign_interfaces::msg::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: + case ros_gz_interfaces::msg::Entity::JOINT: gz_msg.set_type(ignition::msgs::Entity::JOINT); break; default: @@ -89,26 +89,26 @@ template<> void convert_gz_to_ros( const ignition::msgs::Entity & gz_msg, - ros_ign_interfaces::msg::Entity & ros_msg) + ros_gz_interfaces::msg::Entity & ros_msg) { 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_ign_interfaces::msg::Entity::NONE; + ros_msg.type = ros_gz_interfaces::msg::Entity::NONE; } else if (gz_msg.type() == ignition::msgs::Entity::LIGHT) { - ros_msg.type = ros_ign_interfaces::msg::Entity::LIGHT; + ros_msg.type = ros_gz_interfaces::msg::Entity::LIGHT; } else if (gz_msg.type() == ignition::msgs::Entity::MODEL) { - ros_msg.type = ros_ign_interfaces::msg::Entity::MODEL; + ros_msg.type = ros_gz_interfaces::msg::Entity::MODEL; } else if (gz_msg.type() == ignition::msgs::Entity::LINK) { - ros_msg.type = ros_ign_interfaces::msg::Entity::LINK; + ros_msg.type = ros_gz_interfaces::msg::Entity::LINK; } else if (gz_msg.type() == ignition::msgs::Entity::VISUAL) { - ros_msg.type = ros_ign_interfaces::msg::Entity::VISUAL; + ros_msg.type = ros_gz_interfaces::msg::Entity::VISUAL; } else if (gz_msg.type() == ignition::msgs::Entity::COLLISION) { - ros_msg.type = ros_ign_interfaces::msg::Entity::COLLISION; + ros_msg.type = ros_gz_interfaces::msg::Entity::COLLISION; } else if (gz_msg.type() == ignition::msgs::Entity::SENSOR) { - ros_msg.type = ros_ign_interfaces::msg::Entity::SENSOR; + ros_msg.type = ros_gz_interfaces::msg::Entity::SENSOR; } else if (gz_msg.type() == ignition::msgs::Entity::JOINT) { - ros_msg.type = ros_ign_interfaces::msg::Entity::JOINT; + ros_msg.type = ros_gz_interfaces::msg::Entity::JOINT; } else { std::cerr << "Unsupported Entity [" << gz_msg.type() << "]" << std::endl; @@ -118,7 +118,7 @@ convert_gz_to_ros( template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::Contact & ros_msg, + const ros_gz_interfaces::msg::Contact & ros_msg, ignition::msgs::Contact & gz_msg) { convert_ros_to_gz(ros_msg.collision1, (*gz_msg.mutable_collision1())); @@ -147,7 +147,7 @@ template<> void convert_gz_to_ros( const ignition::msgs::Contact & gz_msg, - ros_ign_interfaces::msg::Contact & ros_msg) + ros_gz_interfaces::msg::Contact & ros_msg) { convert_gz_to_ros(gz_msg.collision1(), ros_msg.collision1); convert_gz_to_ros(gz_msg.collision2(), ros_msg.collision2); @@ -165,7 +165,7 @@ convert_gz_to_ros( ros_msg.depths.push_back(gz_msg.depth(i)); } for (auto i = 0; i < gz_msg.wrench_size(); ++i) { - ros_ign_interfaces::msg::JointWrench ros_joint_wrench; + 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); } @@ -174,7 +174,7 @@ convert_gz_to_ros( template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::Contacts & ros_msg, + const ros_gz_interfaces::msg::Contacts & ros_msg, ignition::msgs::Contacts & gz_msg) { convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); @@ -189,11 +189,11 @@ template<> void convert_gz_to_ros( const ignition::msgs::Contacts & gz_msg, - ros_ign_interfaces::msg::Contacts & ros_msg) + ros_gz_interfaces::msg::Contacts & ros_msg) { convert_gz_to_ros(gz_msg.header(), ros_msg.header); for (auto i = 0; i < gz_msg.contact_size(); ++i) { - ros_ign_interfaces::msg::Contact ros_contact; + ros_gz_interfaces::msg::Contact ros_contact; convert_gz_to_ros(gz_msg.contact(i), ros_contact); ros_msg.contacts.push_back(ros_contact); } @@ -202,7 +202,7 @@ convert_gz_to_ros( template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::GuiCamera & ros_msg, + const ros_gz_interfaces::msg::GuiCamera & ros_msg, ignition::msgs::GUICamera & gz_msg) { convert_ros_to_gz(ros_msg.header, *gz_msg.mutable_header()); @@ -217,7 +217,7 @@ template<> void convert_gz_to_ros( const ignition::msgs::GUICamera & gz_msg, - ros_ign_interfaces::msg::GuiCamera & ros_msg) + ros_gz_interfaces::msg::GuiCamera & ros_msg) { convert_gz_to_ros(gz_msg.header(), ros_msg.header); ros_msg.name = gz_msg.name(); @@ -230,7 +230,7 @@ convert_gz_to_ros( template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::Light & ros_msg, + const ros_gz_interfaces::msg::Light & ros_msg, ignition::msgs::Light & gz_msg) { convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); @@ -269,7 +269,7 @@ template<> void convert_gz_to_ros( const ignition::msgs::Light & gz_msg, - ros_ign_interfaces::msg::Light & ros_msg) + ros_gz_interfaces::msg::Light & ros_msg) { convert_gz_to_ros(gz_msg.header(), ros_msg.header); @@ -307,7 +307,7 @@ convert_gz_to_ros( template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::StringVec & ros_msg, + const ros_gz_interfaces::msg::StringVec & ros_msg, ignition::msgs::StringMsg_V & gz_msg) { convert_ros_to_gz(ros_msg.header, *gz_msg.mutable_header()); @@ -321,7 +321,7 @@ template<> void convert_gz_to_ros( const ignition::msgs::StringMsg_V & gz_msg, - ros_ign_interfaces::msg::StringVec & ros_msg) + ros_gz_interfaces::msg::StringVec & ros_msg) { convert_gz_to_ros(gz_msg.header(), ros_msg.header); for (const auto & elem : gz_msg.data()) { @@ -332,7 +332,7 @@ convert_gz_to_ros( template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::TrackVisual & ros_msg, + const ros_gz_interfaces::msg::TrackVisual & ros_msg, ignition::msgs::TrackVisual & gz_msg) { convert_ros_to_gz(ros_msg.header, *gz_msg.mutable_header()); @@ -351,7 +351,7 @@ template<> void convert_gz_to_ros( const ignition::msgs::TrackVisual & gz_msg, - ros_ign_interfaces::msg::TrackVisual & ros_msg) + ros_gz_interfaces::msg::TrackVisual & ros_msg) { convert_gz_to_ros(gz_msg.header(), ros_msg.header); ros_msg.name = gz_msg.name(); @@ -368,7 +368,7 @@ convert_gz_to_ros( template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::VideoRecord & ros_msg, + const ros_gz_interfaces::msg::VideoRecord & ros_msg, ignition::msgs::VideoRecord & gz_msg) { convert_ros_to_gz(ros_msg.header, *gz_msg.mutable_header()); @@ -382,7 +382,7 @@ template<> void convert_gz_to_ros( const ignition::msgs::VideoRecord & gz_msg, - ros_ign_interfaces::msg::VideoRecord & ros_msg) + ros_gz_interfaces::msg::VideoRecord & ros_msg) { convert_gz_to_ros(gz_msg.header(), ros_msg.header); ros_msg.start = gz_msg.start(); @@ -394,7 +394,7 @@ convert_gz_to_ros( template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::WorldControl & ros_msg, + const ros_gz_interfaces::msg::WorldControl & ros_msg, ignition::msgs::WorldControl & gz_msg) { gz_msg.set_pause(ros_msg.pause); @@ -409,7 +409,7 @@ template<> void convert_gz_to_ros( const ignition::msgs::WorldControl & gz_msg, - ros_ign_interfaces::msg::WorldControl & ros_msg) + ros_gz_interfaces::msg::WorldControl & ros_msg) { ros_msg.pause = gz_msg.pause(); ros_msg.step = gz_msg.step(); @@ -422,7 +422,7 @@ convert_gz_to_ros( template<> void convert_ros_to_gz( - const ros_ign_interfaces::msg::WorldReset & ros_msg, + const ros_gz_interfaces::msg::WorldReset & ros_msg, ignition::msgs::WorldReset & gz_msg) { gz_msg.set_all(ros_msg.all); @@ -434,7 +434,7 @@ template<> void convert_gz_to_ros( const ignition::msgs::WorldReset & gz_msg, - ros_ign_interfaces::msg::WorldReset & ros_msg) + ros_gz_interfaces::msg::WorldReset & ros_msg) { ros_msg.all = gz_msg.all(); ros_msg.time_only = gz_msg.time_only(); diff --git a/ros_gz_bridge/src/convert/rosgraph_msgs.cpp b/ros_gz_bridge/src/convert/rosgraph_msgs.cpp index 249bf412..c6da7fc9 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_gz_bridge { diff --git a/ros_gz_bridge/src/convert/sensor_msgs.cpp b/ros_gz_bridge/src/convert/sensor_msgs.cpp index 6580f836..c7519dbc 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_gz_bridge { diff --git a/ros_gz_bridge/src/convert/std_msgs.cpp b/ros_gz_bridge/src/convert/std_msgs.cpp index dcea1855..dcde74b3 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_gz_bridge { diff --git a/ros_gz_bridge/src/convert/tf2_msgs.cpp b/ros_gz_bridge/src/convert/tf2_msgs.cpp index a5c581ec..2a1b2142 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_gz_bridge { diff --git a/ros_gz_bridge/src/convert/trajectory_msgs.cpp b/ros_gz_bridge/src/convert/trajectory_msgs.cpp index c94688ad..db877c2e 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_gz_bridge { diff --git a/ros_gz_bridge/src/factories.cpp b/ros_gz_bridge/src/factories.cpp index e81524f3..c5cf0aeb 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_gz_bridge { @@ -50,7 +50,7 @@ get_factory_impl( impl = get_factory__nav_msgs(ros_type_name, gz_type_name); if (impl) {return impl;} - impl = get_factory__ros_ign_interfaces(ros_type_name, gz_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, gz_type_name); @@ -90,7 +90,7 @@ get_service_factory( { std::shared_ptr impl; - impl = get_service_factory__ros_ign_interfaces( + impl = get_service_factory__ros_gz_interfaces( ros_type_name, gz_req_type_name, gz_rep_type_name); if (impl) {return impl;} diff --git a/ros_gz_bridge/src/factories/builtin_interfaces.cpp b/ros_gz_bridge/src/factories/builtin_interfaces.cpp index bc9b13fc..39041710 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_gz_bridge { diff --git a/ros_gz_bridge/src/factories/geometry_msgs.cpp b/ros_gz_bridge/src/factories/geometry_msgs.cpp index 847e4599..5f41a482 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_gz_bridge { diff --git a/ros_gz_bridge/src/factories/nav_msgs.cpp b/ros_gz_bridge/src/factories/nav_msgs.cpp index 8db47a99..9ac5dd59 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_gz_bridge { diff --git a/ros_gz_bridge/src/factories/ros_gz_interfaces.cpp b/ros_gz_bridge/src/factories/ros_gz_interfaces.cpp index 90c8a920..243e7a6e 100644 --- a/ros_gz_bridge/src/factories/ros_gz_interfaces.cpp +++ b/ros_gz_bridge/src/factories/ros_gz_interfaces.cpp @@ -12,131 +12,131 @@ // 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_gz_bridge { std::shared_ptr -get_factory__ros_ign_interfaces( +get_factory__ros_gz_interfaces( const std::string & ros_type_name, const std::string & gz_type_name) { - if ((ros_type_name == "ros_ign_interfaces/msg/JointWrench" || ros_type_name.empty()) && + 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", gz_type_name); + >("ros_gz_interfaces/msg/JointWrench", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/Entity" || ros_type_name.empty()) && + 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", gz_type_name); + >("ros_gz_interfaces/msg/Entity", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/Contact" || ros_type_name.empty()) && + 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", gz_type_name); + >("ros_gz_interfaces/msg/Contact", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/Contacts" || ros_type_name.empty()) && + 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", gz_type_name); + >("ros_gz_interfaces/msg/Contacts", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/GuiCamera" || ros_type_name.empty()) && + 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", gz_type_name); + >("ros_gz_interfaces/msg/GuiCamera", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/Light" || ros_type_name.empty()) && + 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", gz_type_name); + >("ros_gz_interfaces/msg/Light", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/StringVec" || ros_type_name.empty()) && + 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", gz_type_name); + >("ros_gz_interfaces/msg/StringVec", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/TrackVisual" || ros_type_name.empty()) && + 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", gz_type_name); + >("ros_gz_interfaces/msg/TrackVisual", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/VideoRecord" || ros_type_name.empty()) && + 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", gz_type_name); + >("ros_gz_interfaces/msg/VideoRecord", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/WorldControl" || ros_type_name.empty()) && + 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", gz_type_name); + >("ros_gz_interfaces/msg/WorldControl", gz_type_name); } return nullptr; } @@ -144,10 +144,10 @@ get_factory__ros_ign_interfaces( template<> void Factory< - ros_ign_interfaces::msg::JointWrench, + ros_gz_interfaces::msg::JointWrench, ignition::msgs::JointWrench >::convert_ros_to_gz( - const ros_ign_interfaces::msg::JointWrench & ros_msg, + const ros_gz_interfaces::msg::JointWrench & ros_msg, ignition::msgs::JointWrench & gz_msg) { ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); @@ -156,11 +156,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::JointWrench, + ros_gz_interfaces::msg::JointWrench, ignition::msgs::JointWrench >::convert_gz_to_ros( const ignition::msgs::JointWrench & gz_msg, - ros_ign_interfaces::msg::JointWrench & ros_msg) + ros_gz_interfaces::msg::JointWrench & ros_msg) { ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } @@ -168,10 +168,10 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::Entity, + ros_gz_interfaces::msg::Entity, ignition::msgs::Entity >::convert_ros_to_gz( - const ros_ign_interfaces::msg::Entity & ros_msg, + const ros_gz_interfaces::msg::Entity & ros_msg, ignition::msgs::Entity & gz_msg) { ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); @@ -180,11 +180,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::Entity, + ros_gz_interfaces::msg::Entity, ignition::msgs::Entity >::convert_gz_to_ros( const ignition::msgs::Entity & gz_msg, - ros_ign_interfaces::msg::Entity & ros_msg) + ros_gz_interfaces::msg::Entity & ros_msg) { ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } @@ -192,10 +192,10 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::Contact, + ros_gz_interfaces::msg::Contact, ignition::msgs::Contact >::convert_ros_to_gz( - const ros_ign_interfaces::msg::Contact & ros_msg, + const ros_gz_interfaces::msg::Contact & ros_msg, ignition::msgs::Contact & gz_msg) { ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); @@ -204,11 +204,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::Contact, + ros_gz_interfaces::msg::Contact, ignition::msgs::Contact >::convert_gz_to_ros( const ignition::msgs::Contact & gz_msg, - ros_ign_interfaces::msg::Contact & ros_msg) + ros_gz_interfaces::msg::Contact & ros_msg) { ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } @@ -216,10 +216,10 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::Contacts, + ros_gz_interfaces::msg::Contacts, ignition::msgs::Contacts >::convert_ros_to_gz( - const ros_ign_interfaces::msg::Contacts & ros_msg, + const ros_gz_interfaces::msg::Contacts & ros_msg, ignition::msgs::Contacts & gz_msg) { ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); @@ -228,11 +228,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::Contacts, + ros_gz_interfaces::msg::Contacts, ignition::msgs::Contacts >::convert_gz_to_ros( const ignition::msgs::Contacts & gz_msg, - ros_ign_interfaces::msg::Contacts & ros_msg) + ros_gz_interfaces::msg::Contacts & ros_msg) { ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } @@ -240,10 +240,10 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::GuiCamera, + ros_gz_interfaces::msg::GuiCamera, ignition::msgs::GUICamera >::convert_ros_to_gz( - const ros_ign_interfaces::msg::GuiCamera & ros_msg, + const ros_gz_interfaces::msg::GuiCamera & ros_msg, ignition::msgs::GUICamera & gz_msg) { ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); @@ -252,11 +252,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::GuiCamera, + ros_gz_interfaces::msg::GuiCamera, ignition::msgs::GUICamera >::convert_gz_to_ros( const ignition::msgs::GUICamera & gz_msg, - ros_ign_interfaces::msg::GuiCamera & ros_msg) + ros_gz_interfaces::msg::GuiCamera & ros_msg) { ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } @@ -264,10 +264,10 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::Light, + ros_gz_interfaces::msg::Light, ignition::msgs::Light >::convert_ros_to_gz( - const ros_ign_interfaces::msg::Light & ros_msg, + const ros_gz_interfaces::msg::Light & ros_msg, ignition::msgs::Light & gz_msg) { ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); @@ -276,11 +276,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::Light, + ros_gz_interfaces::msg::Light, ignition::msgs::Light >::convert_gz_to_ros( const ignition::msgs::Light & gz_msg, - ros_ign_interfaces::msg::Light & ros_msg) + ros_gz_interfaces::msg::Light & ros_msg) { ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } @@ -288,10 +288,10 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::StringVec, + ros_gz_interfaces::msg::StringVec, ignition::msgs::StringMsg_V >::convert_ros_to_gz( - const ros_ign_interfaces::msg::StringVec & ros_msg, + const ros_gz_interfaces::msg::StringVec & ros_msg, ignition::msgs::StringMsg_V & gz_msg) { ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); @@ -300,11 +300,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::StringVec, + ros_gz_interfaces::msg::StringVec, ignition::msgs::StringMsg_V >::convert_gz_to_ros( const ignition::msgs::StringMsg_V & gz_msg, - ros_ign_interfaces::msg::StringVec & ros_msg) + ros_gz_interfaces::msg::StringVec & ros_msg) { ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } @@ -312,10 +312,10 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::TrackVisual, + ros_gz_interfaces::msg::TrackVisual, ignition::msgs::TrackVisual >::convert_ros_to_gz( - const ros_ign_interfaces::msg::TrackVisual & ros_msg, + const ros_gz_interfaces::msg::TrackVisual & ros_msg, ignition::msgs::TrackVisual & gz_msg) { ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); @@ -324,11 +324,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::TrackVisual, + ros_gz_interfaces::msg::TrackVisual, ignition::msgs::TrackVisual >::convert_gz_to_ros( const ignition::msgs::TrackVisual & gz_msg, - ros_ign_interfaces::msg::TrackVisual & ros_msg) + ros_gz_interfaces::msg::TrackVisual & ros_msg) { ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } @@ -336,10 +336,10 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::VideoRecord, + ros_gz_interfaces::msg::VideoRecord, ignition::msgs::VideoRecord >::convert_ros_to_gz( - const ros_ign_interfaces::msg::VideoRecord & ros_msg, + const ros_gz_interfaces::msg::VideoRecord & ros_msg, ignition::msgs::VideoRecord & gz_msg) { ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); @@ -348,11 +348,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::VideoRecord, + ros_gz_interfaces::msg::VideoRecord, ignition::msgs::VideoRecord >::convert_gz_to_ros( const ignition::msgs::VideoRecord & gz_msg, - ros_ign_interfaces::msg::VideoRecord & ros_msg) + ros_gz_interfaces::msg::VideoRecord & ros_msg) { ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } @@ -360,10 +360,10 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::WorldControl, + ros_gz_interfaces::msg::WorldControl, ignition::msgs::WorldControl >::convert_ros_to_gz( - const ros_ign_interfaces::msg::WorldControl & ros_msg, + const ros_gz_interfaces::msg::WorldControl & ros_msg, ignition::msgs::WorldControl & gz_msg) { ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); @@ -372,11 +372,11 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::WorldControl, + ros_gz_interfaces::msg::WorldControl, ignition::msgs::WorldControl >::convert_gz_to_ros( const ignition::msgs::WorldControl & gz_msg, - ros_ign_interfaces::msg::WorldControl & ros_msg) + ros_gz_interfaces::msg::WorldControl & ros_msg) { ros_gz_bridge::convert_gz_to_ros(gz_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 d6339517..84c57a01 100644 --- a/ros_gz_bridge/src/factories/ros_gz_interfaces.hpp +++ b/ros_gz_bridge/src/factories/ros_gz_interfaces.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef FACTORIES__ROS_IGN_INTERFACES_HPP_ -#define FACTORIES__ROS_IGN_INTERFACES_HPP_ +#ifndef FACTORIES__ROS_GZ_INTERFACES_HPP_ +#define FACTORIES__ROS_GZ_INTERFACES_HPP_ #include #include @@ -24,10 +24,10 @@ namespace ros_gz_bridge { std::shared_ptr -get_factory__ros_ign_interfaces( +get_factory__ros_gz_interfaces( const std::string & ros_type_name, const std::string & gz_type_name); } // namespace ros_gz_bridge -#endif // FACTORIES__ROS_IGN_INTERFACES_HPP_ +#endif // FACTORIES__ROS_GZ_INTERFACES_HPP_ diff --git a/ros_gz_bridge/src/factories/rosgraph_msgs.cpp b/ros_gz_bridge/src/factories/rosgraph_msgs.cpp index 4552db13..33e432af 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_gz_bridge { diff --git a/ros_gz_bridge/src/factories/sensor_msgs.cpp b/ros_gz_bridge/src/factories/sensor_msgs.cpp index 6166d144..2ec68f6e 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_gz_bridge { diff --git a/ros_gz_bridge/src/factories/std_msgs.cpp b/ros_gz_bridge/src/factories/std_msgs.cpp index a17b8a9a..c6ed161f 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_gz_bridge { diff --git a/ros_gz_bridge/src/factories/tf2_msgs.cpp b/ros_gz_bridge/src/factories/tf2_msgs.cpp index 7dc6a39a..b8f0876a 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_gz_bridge { diff --git a/ros_gz_bridge/src/factories/trajectory_msgs.cpp b/ros_gz_bridge/src/factories/trajectory_msgs.cpp index 08f4e632..76bcb901 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_gz_bridge { diff --git a/ros_gz_bridge/src/parameter_bridge.cpp b/ros_gz_bridge/src/parameter_bridge.cpp index d814baee..3966971f 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 897d51f7..49160bab 100644 --- a/ros_gz_bridge/src/service_factories/ros_gz_interfaces.cpp +++ b/ros_gz_bridge/src/service_factories/ros_gz_interfaces.cpp @@ -12,34 +12,34 @@ // 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_gz_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 & gz_req_type_name, const std::string & gz_rep_type_name) { if ( - ros_type_name == "ros_ign_interfaces/srv/ControlWorld" && + 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"); @@ -51,7 +51,7 @@ get_service_factory__ros_ign_interfaces( template<> void convert_ros_to_gz( - const ros_ign_interfaces::srv::ControlWorld::Request & ros_req, + const ros_gz_interfaces::srv::ControlWorld::Request & ros_req, ignition::msgs::WorldControl & gz_req) { convert_ros_to_gz(ros_req.world_control, gz_req); @@ -61,14 +61,14 @@ template<> void convert_gz_to_ros( const ignition::msgs::Boolean & gz_rep, - ros_ign_interfaces::srv::ControlWorld::Response & ros_res) + ros_gz_interfaces::srv::ControlWorld::Response & ros_res) { ros_res.success = gz_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 Gazebo 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 37f0ba04..572c1b70 100644 --- a/ros_gz_bridge/src/service_factories/ros_gz_interfaces.hpp +++ b/ros_gz_bridge/src/service_factories/ros_gz_interfaces.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SERVICE_FACTORIES__ROS_IGN_INTERFACES_HPP_ -#define SERVICE_FACTORIES__ROS_IGN_INTERFACES_HPP_ +#ifndef SERVICE_FACTORIES__ROS_GZ_INTERFACES_HPP_ +#define SERVICE_FACTORIES__ROS_GZ_INTERFACES_HPP_ #include #include @@ -24,11 +24,11 @@ namespace ros_gz_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 & gz_req_type_name, const std::string & gz_rep_type_name); } // namespace ros_gz_bridge -#endif // SERVICE_FACTORIES__ROS_IGN_INTERFACES_HPP_ +#endif // SERVICE_FACTORIES__ROS_GZ_INTERFACES_HPP_ diff --git a/ros_gz_bridge/src/service_factory.hpp b/ros_gz_bridge/src/service_factory.hpp index 35429a6f..d4a44d74 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 b94deb3d..13770de5 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=[ - '/gz_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 2df7cb00..7430e662 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 93415b7a..f411ea30 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 4d181e32..29cab89b 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 551c0fd5..5aa45d1d 100644 --- a/ros_gz_bridge/test/publishers/ros_publisher.cpp +++ b/ros_gz_bridge/test/publishers/ros_publisher.cpp @@ -146,58 +146,58 @@ int main(int argc, char ** argv) geometry_msgs::msg::Wrench wrench_msg; ros_gz_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; + 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; + 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; + 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; + 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; + 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; + 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; + 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; + 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; + 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. diff --git a/ros_gz_bridge/test/serverclient/gz_server.cpp b/ros_gz_bridge/test/serverclient/gz_server.cpp index e8c9bb4f..c8f10e3e 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 46d9e14c..ff21e464 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; @@ -28,11 +28,11 @@ TEST(ROSClientTest, WorldControl) { rclcpp::init(0, NULL); auto node = std::make_shared("test_ros_client_to_gz_service"); - auto client = node->create_client( + 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 10e2ed91..48ef381f 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 Gazebo 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 df4d1c1c..a4e885e9 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_gz_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_gz_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_gz_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_gz_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_gz_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_gz_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_gz_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_gz_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_gz_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 c6278fb4..81f02974 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/gz_test_msg.hpp b/ros_gz_bridge/test/utils/gz_test_msg.hpp index 092807c1..cb2d253f 100644 --- a/ros_gz_bridge/test/utils/gz_test_msg.hpp +++ b/ros_gz_bridge/test/utils/gz_test_msg.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef UTILS__IGN_TEST_MSG_HPP_ -#define UTILS__IGN_TEST_MSG_HPP_ +#ifndef UTILS__GZ_TEST_MSG_HPP_ +#define UTILS__GZ_TEST_MSG_HPP_ #include #include @@ -397,4 +397,4 @@ void compareTestMsg(const std::shared_ptr & _msg); } // namespace testing } // namespace ros_gz_bridge -#endif // UTILS__IGN_TEST_MSG_HPP_ +#endif // UTILS__GZ_TEST_MSG_HPP_ diff --git a/ros_gz_bridge/test/utils/ros_test_msg.cpp b/ros_gz_bridge/test/utils/ros_test_msg.cpp index b09fa861..5bee732d 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 dad3edbd..fbe7668e 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 ac23e448..5552287c 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) @@ -75,7 +75,7 @@ target_link_libraries(${executable} ament_target_dependencies(${executable} "image_transport" - "ros_ign_bridge" + "ros_gz_bridge" "rclcpp" "sensor_msgs" ) @@ -91,7 +91,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 8775ac45..a01642b5 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 Gazebo 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 e1bcfe38..00aacca5 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, gz_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 cbe8634b..e4e451a5 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 a5fb11f3..192a2b39 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_image/test/test_utils.h b/ros_gz_image/test/test_utils.h index 3694f34d..02996f3e 100644 --- a/ros_gz_image/test/test_utils.h +++ b/ros_gz_image/test/test_utils.h @@ -15,8 +15,8 @@ * */ -#ifndef ROS_IGN_IMAGE__TEST_UTILS_H_ -#define ROS_IGN_IMAGE__TEST_UTILS_H_ +#ifndef ROS_GZ_IMAGE__TEST_UTILS_H_ +#define ROS_GZ_IMAGE__TEST_UTILS_H_ #include #include @@ -213,4 +213,4 @@ namespace testing } } -#endif // ROS_IGN_BRIDGE__TEST_UTILS_H_ +#endif // ROS_GZ_BRIDGE__TEST_UTILS_H_ diff --git a/ros_gz_interfaces/CMakeLists.txt b/ros_gz_interfaces/CMakeLists.txt index df877646..0353319c 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 90235356..98d2cef8 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 e709e178..40232e51 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 f08cb6f5..efa22fb9 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 f677765c..b9da959b 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 Gazebo from ROS2. Apache 2.0 diff --git a/ros_gz_interfaces/srv/ControlWorld.srv b/ros_gz_interfaces/srv/ControlWorld.srv index 92f7a712..d8e41f24 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 d922e7f9..13b3e1fd 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 f1fbec7e..b749488c 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 cb85e438..35d5df59 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 e8bcf251..afcce424 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 5292d6ff..574d0ce4 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 cb38b1b0..7bd3a735 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 12bea4e6..64a77b6a 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 30922758..b3d5717e 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 Gazebo simulation with ROS. Apache 2.0 diff --git a/ros_gz_point_cloud/src/point_cloud.hh b/ros_gz_point_cloud/src/point_cloud.hh index ce182b79..437efac9 100644 --- a/ros_gz_point_cloud/src/point_cloud.hh +++ b/ros_gz_point_cloud/src/point_cloud.hh @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_POINTCLOUD__POINTCLOUD_HPP_ -#define ROS_IGN_POINTCLOUD__POINTCLOUD_HPP_ +#ifndef ROS_GZ_POINTCLOUD__POINTCLOUD_HPP_ +#define ROS_GZ_POINTCLOUD__POINTCLOUD_HPP_ #include #include diff --git a/ros_gz_sim/CMakeLists.txt b/ros_gz_sim/CMakeLists.txt index 68958f2f..1834bf50 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) @@ -92,17 +92,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 7adb02ce..44173b50 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 @@ -20,20 +20,39 @@ from launch import LaunchDescription from launch.actions import DeclareLaunchArgument from launch.actions import ExecuteProcess from launch.substitutions import LaunchConfiguration +from launch.conditions import LaunchConfigurationEquals, LaunchConfigurationNotEquals 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='', + description='Deprecated: Gazebo Sim\'s major version' + ), + + # NOTE(CH3): We need ign gazebo to support pre-garden... + # It's deprecated. Remove on tock. ExecuteProcess( + condition=LaunchConfigurationNotEquals('ign_version', ''), cmd=['ign gazebo', LaunchConfiguration('ign_args'), '--force-version', @@ -42,5 +61,17 @@ def generate_launch_description(): output='screen', additional_env=env, shell=True - ) + ), + + ExecuteProcess( + condition=LaunchConfigurationEquals('ign_version', ''), + cmd=['ign gazebo', + LaunchConfiguration('gz_args'), + '--force-version', + LaunchConfiguration('gz_version'), + ], + output='screen', + additional_env=env, + shell=True + ), ]) diff --git a/ros_gz_sim/package.xml b/ros_gz_sim/package.xml index 979362fe..01dd3d06 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 Gazebo Sim simulation with ROS. Alejandro Hernandez diff --git a/ros_gz_sim/src/create.cpp b/ros_gz_sim/src/create.cpp index 1c39645c..016f8b57 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 bf6a7253..38754563 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 ccaa7251..272d6eb1 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 239e14a2..4e32322a 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 903096e4..1bd9a8a0 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 d025c695..d42ce862 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 9cac29d1..8a297567 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 095a0a81..5cfdb08f 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 d45381b0..26bd36b8 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 642deb70..91e81e33 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 4d2d524f..649ad359 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 a9dbac82..20b330ec 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 15564347..0e026676 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 39453647..1ec8409b 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 07faece8..a318f682 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 4f9d94e3..882cdee3 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 ae995704..3b2171d0 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 4f3d7a85..9e6362a2 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 782154e3..00680c14 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 e38f25e6..22d56c10 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 Gazebo Sim 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 From 75c58281eaff8d97fe730319b403bb6680477497 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 1 Aug 2022 13:24:18 -0700 Subject: [PATCH 2/2] Implement shims Signed-off-by: methylDragon --- ros_gz_shims/README.md | 13 + ros_gz_shims/ros_ign/CMakeLists.txt | 10 + ros_gz_shims/ros_ign/README.md | 2 + ros_gz_shims/ros_ign/package.xml | 28 ++ ros_gz_shims/ros_ign_bridge/CMakeLists.txt | 29 ++ ros_gz_shims/ros_ign_bridge/README.md | 2 + ros_gz_shims/ros_ign_bridge/package.xml | 19 ++ .../src/parameter_bridge_shim.cpp | 30 ++ .../ros_ign_bridge/src/static_bridge_shim.cpp | 30 ++ ros_gz_shims/ros_ign_gazebo/CMakeLists.txt | 45 +++ .../launch/ign_gazebo.launch.py.in | 77 +++++ ros_gz_shims/ros_ign_gazebo/package.xml | 19 ++ .../ros_ign_gazebo/src/create_shim.cpp | 30 ++ .../ros_ign_gazebo_demos/CMakeLists.txt | 29 ++ ros_gz_shims/ros_ign_gazebo_demos/README.md | 2 + .../launch/air_pressure.launch.py | 63 +++++ .../launch/battery.launch.py | 69 +++++ .../launch/camera.launch.py | 63 +++++ .../launch/depth_camera.launch.py | 77 +++++ .../launch/diff_drive.launch.py | 69 +++++ .../launch/gpu_lidar.launch.py | 65 +++++ .../launch/gpu_lidar_bridge.launch.py | 65 +++++ .../launch/image_bridge.launch.py | 65 +++++ .../ros_ign_gazebo_demos/launch/imu.launch.py | 78 +++++ .../launch/joint_states.launch.py | 98 +++++++ .../launch/magnetometer.launch.py | 63 +++++ .../launch/rgbd_camera.launch.py | 63 +++++ .../launch/rgbd_camera_bridge.launch.py | 70 +++++ .../robot_description_publisher.launch.py | 93 ++++++ .../launch/tf_bridge.launch.py | 59 ++++ .../launch/triggered_camera.launch.py | 64 +++++ .../models/double_pendulum_model.sdf | 266 ++++++++++++++++++ .../ros_ign_gazebo_demos/models/rrbot.xacro | 165 +++++++++++ ros_gz_shims/ros_ign_gazebo_demos/package.xml | 17 ++ .../ros_ign_gazebo_demos/rviz/camera.rviz | 137 +++++++++ .../rviz/depth_camera.rviz | 147 ++++++++++ .../ros_ign_gazebo_demos/rviz/diff_drive.rviz | 123 ++++++++ .../ros_ign_gazebo_demos/rviz/gpu_lidar.rviz | 181 ++++++++++++ .../rviz/gpu_lidar_bridge.rviz | 167 +++++++++++ .../ros_ign_gazebo_demos/rviz/imu.rviz | 130 +++++++++ .../rviz/joint_states.rviz | 190 +++++++++++++ .../rviz/rgbd_camera.rviz | 159 +++++++++++ .../rviz/rgbd_camera_bridge.rviz | 142 ++++++++++ .../rviz/robot_description_publisher.rviz | 148 ++++++++++ .../ros_ign_gazebo_demos/rviz/tf_bridge.rviz | 163 +++++++++++ ros_gz_shims/ros_ign_image/CMakeLists.txt | 26 ++ ros_gz_shims/ros_ign_image/README.md | 2 + ros_gz_shims/ros_ign_image/package.xml | 19 ++ .../ros_ign_image/src/image_bridge_shim.cpp | 30 ++ .../ros_ign_interfaces/CMakeLists.txt | 49 ++++ ros_gz_shims/ros_ign_interfaces/README.md | 2 + .../ros_ign_interfaces/msg/Contact.msg | 6 + .../ros_ign_interfaces/msg/Contacts.msg | 2 + .../ros_ign_interfaces/msg/Entity.msg | 13 + .../ros_ign_interfaces/msg/EntityFactory.msg | 11 + .../ros_ign_interfaces/msg/GuiCamera.msg | 12 + .../ros_ign_interfaces/msg/JointWrench.msg | 8 + ros_gz_shims/ros_ign_interfaces/msg/Light.msg | 29 ++ .../ros_ign_interfaces/msg/StringVec.msg | 7 + .../ros_ign_interfaces/msg/TrackVisual.msg | 33 +++ .../ros_ign_interfaces/msg/VideoRecord.msg | 16 ++ .../ros_ign_interfaces/msg/WorldControl.msg | 7 + .../ros_ign_interfaces/msg/WorldReset.msg | 3 + ros_gz_shims/ros_ign_interfaces/package.xml | 27 ++ .../ros_ign_interfaces/srv/ControlWorld.srv | 3 + .../ros_ign_interfaces/srv/DeleteEntity.srv | 3 + .../ros_ign_interfaces/srv/SetEntityPose.srv | 4 + .../ros_ign_interfaces/srv/SpawnEntity.srv | 3 + 68 files changed, 3939 insertions(+) create mode 100644 ros_gz_shims/README.md create mode 100644 ros_gz_shims/ros_ign/CMakeLists.txt create mode 100644 ros_gz_shims/ros_ign/README.md create mode 100644 ros_gz_shims/ros_ign/package.xml create mode 100644 ros_gz_shims/ros_ign_bridge/CMakeLists.txt create mode 100644 ros_gz_shims/ros_ign_bridge/README.md create mode 100644 ros_gz_shims/ros_ign_bridge/package.xml create mode 100644 ros_gz_shims/ros_ign_bridge/src/parameter_bridge_shim.cpp create mode 100644 ros_gz_shims/ros_ign_bridge/src/static_bridge_shim.cpp create mode 100644 ros_gz_shims/ros_ign_gazebo/CMakeLists.txt create mode 100644 ros_gz_shims/ros_ign_gazebo/launch/ign_gazebo.launch.py.in create mode 100644 ros_gz_shims/ros_ign_gazebo/package.xml create mode 100644 ros_gz_shims/ros_ign_gazebo/src/create_shim.cpp create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/CMakeLists.txt create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/README.md create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/air_pressure.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/battery.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/camera.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/depth_camera.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/diff_drive.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar_bridge.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/image_bridge.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/imu.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/joint_states.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/magnetometer.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera_bridge.launch.py create mode 100755 ros_gz_shims/ros_ign_gazebo_demos/launch/robot_description_publisher.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/tf_bridge.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/triggered_camera.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/models/double_pendulum_model.sdf create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/models/rrbot.xacro create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/package.xml create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/camera.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/depth_camera.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/diff_drive.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar_bridge.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/imu.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/joint_states.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera_bridge.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/robot_description_publisher.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/tf_bridge.rviz create mode 100644 ros_gz_shims/ros_ign_image/CMakeLists.txt create mode 100644 ros_gz_shims/ros_ign_image/README.md create mode 100644 ros_gz_shims/ros_ign_image/package.xml create mode 100644 ros_gz_shims/ros_ign_image/src/image_bridge_shim.cpp create mode 100644 ros_gz_shims/ros_ign_interfaces/CMakeLists.txt create mode 100644 ros_gz_shims/ros_ign_interfaces/README.md create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/Contact.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/Contacts.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/Entity.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/EntityFactory.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/GuiCamera.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/JointWrench.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/Light.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/StringVec.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/TrackVisual.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/VideoRecord.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/WorldControl.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/WorldReset.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/package.xml create mode 100644 ros_gz_shims/ros_ign_interfaces/srv/ControlWorld.srv create mode 100644 ros_gz_shims/ros_ign_interfaces/srv/DeleteEntity.srv create mode 100644 ros_gz_shims/ros_ign_interfaces/srv/SetEntityPose.srv create mode 100644 ros_gz_shims/ros_ign_interfaces/srv/SpawnEntity.srv diff --git a/ros_gz_shims/README.md b/ros_gz_shims/README.md new file mode 100644 index 00000000..b653a6fc --- /dev/null +++ b/ros_gz_shims/README.md @@ -0,0 +1,13 @@ +# Description + +These are shim packages for `ros_gz` that redirect executable calls to the related `ros_gz` executable. +These require `ros_gz` to be installed though, but are set up to depend on `ros_gz`. + +This allows users to do either of these and get equivalent behavior: + +```bash +ros2 run ros_gz parameter_bridge [...] +ros2 run ros_ign parameter_bridge [...] # Will emit deprecation warning +``` + +Additionally, installed files like launchfiles, message interfaces etc. are **duplicated** versions of the ones in `ros_gz` (but renamed as appropriate), and point to `ros_gz` dependencies as well (e.g. launchfiles pointing to `ros_gz` nodes.) diff --git a/ros_gz_shims/ros_ign/CMakeLists.txt b/ros_gz_shims/ros_ign/CMakeLists.txt new file mode 100644 index 00000000..80524e92 --- /dev/null +++ b/ros_gz_shims/ros_ign/CMakeLists.txt @@ -0,0 +1,10 @@ +cmake_minimum_required(VERSION 3.5) +project(ros_ign) +find_package(ament_cmake REQUIRED) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() diff --git a/ros_gz_shims/ros_ign/README.md b/ros_gz_shims/ros_ign/README.md new file mode 100644 index 00000000..d6f36599 --- /dev/null +++ b/ros_gz_shims/ros_ign/README.md @@ -0,0 +1,2 @@ +# This is a shim meta-package +For [ros_gz](https://github.com/gazebosim/ros_gz) diff --git a/ros_gz_shims/ros_ign/package.xml b/ros_gz_shims/ros_ign/package.xml new file mode 100644 index 00000000..03e41bcb --- /dev/null +++ b/ros_gz_shims/ros_ign/package.xml @@ -0,0 +1,28 @@ + + + + + ros_ign + 0.0.1 + Shim meta-package to redirect to ros_gz. + Brandon Ong + Apache 2.0 + + ament_cmake + ros_gz + + ros_ign_bridge + ros_ign_gazebo + ros_ign_gazebo_demos + ros_ign_image + + + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/ros_gz_shims/ros_ign_bridge/CMakeLists.txt b/ros_gz_shims/ros_ign_bridge/CMakeLists.txt new file mode 100644 index 00000000..7be505b0 --- /dev/null +++ b/ros_gz_shims/ros_ign_bridge/CMakeLists.txt @@ -0,0 +1,29 @@ +cmake_minimum_required(VERSION 3.5) +project(ros_ign_bridge) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wpedantic") +endif() + +find_package(ament_cmake REQUIRED) +find_package(ament_index_cpp REQUIRED) + +add_executable(parameter_bridge src/parameter_bridge_shim.cpp) +ament_target_dependencies(parameter_bridge ament_index_cpp) + +add_executable(static_bridge src/static_bridge_shim.cpp) +ament_target_dependencies(static_bridge ament_index_cpp) + +ament_export_dependencies(ament_index_cpp ros_gz_bridge) + +install(TARGETS + parameter_bridge + static_bridge + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/ros_gz_shims/ros_ign_bridge/README.md b/ros_gz_shims/ros_ign_bridge/README.md new file mode 100644 index 00000000..e93d8f26 --- /dev/null +++ b/ros_gz_shims/ros_ign_bridge/README.md @@ -0,0 +1,2 @@ +# This is a shim package +For [ros_gz_bridge](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_bridge) diff --git a/ros_gz_shims/ros_ign_bridge/package.xml b/ros_gz_shims/ros_ign_bridge/package.xml new file mode 100644 index 00000000..c85b8c97 --- /dev/null +++ b/ros_gz_shims/ros_ign_bridge/package.xml @@ -0,0 +1,19 @@ + + + + ros_ign_bridge + 0.0.1 + Shim package to redirect to ros_gz_bridge. + Brandon Ong + + Apache 2.0 + + ament_cmake + ament_index_cpp + + ros_gz_bridge + + + ament_cmake + + diff --git a/ros_gz_shims/ros_ign_bridge/src/parameter_bridge_shim.cpp b/ros_gz_shims/ros_ign_bridge/src/parameter_bridge_shim.cpp new file mode 100644 index 00000000..b6b613e5 --- /dev/null +++ b/ros_gz_shims/ros_ign_bridge/src/parameter_bridge_shim.cpp @@ -0,0 +1,30 @@ +// Shim to redirect "ros_ign_bridge parameter_bridge" call to "ros_gz_bridge parameter_bridge" + +#include +#include +#include +#include + +#include + + +int main(int argc, char * argv[]) +{ + std::stringstream cli_call; + + cli_call << ament_index_cpp::get_package_prefix("ros_gz_bridge") + << "/lib/ros_gz_bridge/parameter_bridge"; + + if (argc > 1) + { + for (int i = 1; i < argc; i++) + cli_call << " " << argv[i]; + } + + std::cerr << "[ros_ign_bridge] is deprecated! " + << "Redirecting to use [ros_gz_bridge] instead!" + << std::endl << std::endl; + system(cli_call.str().c_str()); + + return 0; +} diff --git a/ros_gz_shims/ros_ign_bridge/src/static_bridge_shim.cpp b/ros_gz_shims/ros_ign_bridge/src/static_bridge_shim.cpp new file mode 100644 index 00000000..56c577b8 --- /dev/null +++ b/ros_gz_shims/ros_ign_bridge/src/static_bridge_shim.cpp @@ -0,0 +1,30 @@ +// Shim to redirect "ros_ign_bridge static_bridge" call to "ros_gz_bridge static_bridge" + +#include +#include +#include +#include + +#include + + +int main(int argc, char * argv[]) +{ + std::stringstream cli_call; + + cli_call << ament_index_cpp::get_package_prefix("ros_gz_bridge") + << "/lib/ros_gz_bridge/static_bridge"; + + if (argc > 1) + { + for (int i = 1; i < argc; i++) + cli_call << " " << argv[i]; + } + + std::cerr << "[ros_ign_bridge] is deprecated! " + << "Redirecting to use [ros_gz_bridge] instead!" + << std::endl << std::endl; + system(cli_call.str().c_str()); + + return 0; +} diff --git a/ros_gz_shims/ros_ign_gazebo/CMakeLists.txt b/ros_gz_shims/ros_ign_gazebo/CMakeLists.txt new file mode 100644 index 00000000..86974a76 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo/CMakeLists.txt @@ -0,0 +1,45 @@ +cmake_minimum_required(VERSION 3.5) +project(ros_ign_gazebo) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wpedantic") +endif() + +find_package(ament_cmake REQUIRED) +find_package(ament_index_cpp REQUIRED) + +add_executable(create + src/create_shim.cpp +) +ament_target_dependencies(create ament_index_cpp) + +ament_export_dependencies( + ament_index_cpp + ros_gz_bridge +) + +configure_file( + launch/ign_gazebo.launch.py.in + launch/ign_gazebo.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" +) + +install(FILES + "${CMAKE_CURRENT_BINARY_DIR}/launch/ign_gazebo.launch.py" + DESTINATION share/${PROJECT_NAME}/launch +) + +install(TARGETS + create + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/ros_gz_shims/ros_ign_gazebo/launch/ign_gazebo.launch.py.in b/ros_gz_shims/ros_ign_gazebo/launch/ign_gazebo.launch.py.in new file mode 100644 index 00000000..44173b50 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo/launch/ign_gazebo.launch.py.in @@ -0,0 +1,77 @@ +# Copyright 2020 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Launch Gazebo Sim with command line arguments.""" + +from os import environ + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import ExecuteProcess +from launch.substitutions import LaunchConfiguration +from launch.conditions import LaunchConfigurationEquals, LaunchConfigurationNotEquals + + +def generate_launch_description(): + 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('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='', + description='Deprecated: Gazebo Sim\'s major version' + ), + + # NOTE(CH3): We need ign gazebo to support pre-garden... + # It's deprecated. Remove on tock. + ExecuteProcess( + condition=LaunchConfigurationNotEquals('ign_version', ''), + cmd=['ign gazebo', + LaunchConfiguration('ign_args'), + '--force-version', + LaunchConfiguration('ign_version'), + ], + output='screen', + additional_env=env, + shell=True + ), + + ExecuteProcess( + condition=LaunchConfigurationEquals('ign_version', ''), + cmd=['ign gazebo', + LaunchConfiguration('gz_args'), + '--force-version', + LaunchConfiguration('gz_version'), + ], + output='screen', + additional_env=env, + shell=True + ), + ]) diff --git a/ros_gz_shims/ros_ign_gazebo/package.xml b/ros_gz_shims/ros_ign_gazebo/package.xml new file mode 100644 index 00000000..c0683a53 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo/package.xml @@ -0,0 +1,19 @@ + + + + ros_ign_gazebo + 0.0.1 + Shim package to redirect to ros_gz_sim. + Brandon Ong + + Apache 2.0 + + ament_cmake + ament_index_cpp + + ros_gz_sim + + + ament_cmake + + diff --git a/ros_gz_shims/ros_ign_gazebo/src/create_shim.cpp b/ros_gz_shims/ros_ign_gazebo/src/create_shim.cpp new file mode 100644 index 00000000..dbaa029e --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo/src/create_shim.cpp @@ -0,0 +1,30 @@ +// Shim to redirect "ros_ign_bridge parameter_bridge" call to "ros_gz_sim parameter_bridge" + +#include +#include +#include +#include + +#include + + +int main(int argc, char * argv[]) +{ + std::stringstream cli_call; + + cli_call << ament_index_cpp::get_package_prefix("ros_gz_sim") + << "/lib/ros_gz_sim/create"; + + if (argc > 1) + { + for (int i = 1; i < argc; i++) + cli_call << " " << argv[i]; + } + + std::cerr << "[ros_ign_gazebo] is deprecated! " + << "Redirecting to use [ros_gz_sim] instead!" + << std::endl << std::endl; + system(cli_call.str().c_str()); + + return 0; +} diff --git a/ros_gz_shims/ros_ign_gazebo_demos/CMakeLists.txt b/ros_gz_shims/ros_ign_gazebo_demos/CMakeLists.txt new file mode 100644 index 00000000..0a7ae4fe --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/CMakeLists.txt @@ -0,0 +1,29 @@ +cmake_minimum_required(VERSION 3.5) +project(ros_ign_gazebo_demos) + +find_package(ament_cmake REQUIRED) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +install( + DIRECTORY + launch/ + DESTINATION share/${PROJECT_NAME}/launch +) + +install( + DIRECTORY + rviz/ + DESTINATION share/${PROJECT_NAME}/rviz +) + +install( + DIRECTORY + models/ + DESTINATION share/${PROJECT_NAME}/models +) + +ament_package() diff --git a/ros_gz_shims/ros_ign_gazebo_demos/README.md b/ros_gz_shims/ros_ign_gazebo_demos/README.md new file mode 100644 index 00000000..b2ce4368 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/README.md @@ -0,0 +1,2 @@ +# This is a shim package +For [ros_gz_sim_demos](https://github.com/gazebosim/ros_gz/tree/ros2/ros_ign_gazebo_demos) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/air_pressure.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/air_pressure.launch.py new file mode 100644 index 00000000..272d6eb1 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/air_pressure.launch.py @@ -0,0 +1,63 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Launch Gazebo Sim with command line arguments.""" + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + # Bridge + bridge = Node( + 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' + ) + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={'gz_args': '-r sensors.sdf'}.items(), + ) + + # RQt + rqt = Node( + package='rqt_topic', + executable='rqt_topic', + arguments=['-t'], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rqt', default_value='true', + description='Open RQt.'), + bridge, + rqt + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/battery.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/battery.launch.py new file mode 100644 index 00000000..4e32322a --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/battery.launch.py @@ -0,0 +1,69 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + # RQt + rqt = Node( + package='rqt_plot', + executable='rqt_plot', + # FIXME: Why isn't the topic being populated on the UI? RQt issue? + arguments=['--force-discover', + '/model/vehicle_blue/battery/linear_battery/state/percentage'], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r -z 1000000 linear_battery_demo.sdf' + }.items(), + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=[ + '/model/vehicle_blue/cmd_vel@geometry_msgs/msg/Twist@ignition.msgs.Twist', + '/model/vehicle_blue/battery/linear_battery/state@sensor_msgs/msg/BatteryState@' + 'ignition.msgs.BatteryState' + ], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rqt', default_value='true', + description='Open RQt.'), + bridge, + rqt + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/camera.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/camera.launch.py new file mode 100644 index 00000000..1bd9a8a0 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/camera.launch.py @@ -0,0 +1,63 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + 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_gz_sim_demos, 'rviz', 'camera.rviz')], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + 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'], + output='screen' + ) + + return LaunchDescription([ + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + gz_sim, + bridge, + rviz + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/depth_camera.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/depth_camera.launch.py new file mode 100644 index 00000000..d42ce862 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/depth_camera.launch.py @@ -0,0 +1,77 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py') + ), + # launch_arguments={ + # 'gz_args': '-r depth_camera.sdf' + # }.items(), + ) + + # RQt + rqt = Node( + package='rqt_image_view', + executable='rqt_image_view', + arguments=['/camera'], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + # FIXME: Generate new RViz config once this demo is usable again + # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'depth_camera.rviz')], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + 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_gz_point_cloud + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + DeclareLaunchArgument('rqt', default_value='true', + description='Open RQt.'), + bridge, + rviz, + rqt + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/diff_drive.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/diff_drive.launch.py new file mode 100644 index 00000000..8a297567 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/diff_drive.launch.py @@ -0,0 +1,69 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r diff_drive.sdf' + }.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'diff_drive.rviz')], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + 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', + '/model/vehicle_green/cmd_vel@geometry_msgs/msg/Twist@ignition.msgs.Twist', + '/model/vehicle_green/odometry@nav_msgs/msg/Odometry@ignition.msgs.Odometry'], + parameters=[{'qos_overrides./model/vehicle_blue.subscriber.reliability': 'reliable', + 'qos_overrides./model/vehicle_green.subscriber.reliability': 'reliable'}], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + bridge, + rviz + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar.launch.py new file mode 100644 index 00000000..5cfdb08f --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar.launch.py @@ -0,0 +1,65 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + # launch_arguments={ + # 'gz_args': '-r gpu_lidar.sdf' + # }.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + # FIXME: Generate new RViz config once this demo is usable again + # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'gpu_lidar.rviz')], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + 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_gz_point_cloud/ + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + bridge, + rviz + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar_bridge.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar_bridge.launch.py new file mode 100644 index 00000000..26bd36b8 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar_bridge.launch.py @@ -0,0 +1,65 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r gpu_lidar_sensor.sdf' + }.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'gpu_lidar_bridge.rviz')], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + 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'], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + bridge, + rviz, + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/image_bridge.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/image_bridge.launch.py new file mode 100644 index 00000000..91e81e33 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/image_bridge.launch.py @@ -0,0 +1,65 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r sensors_demo.sdf' + }.items(), + ) + + # RQt + rqt = Node( + package='rqt_image_view', + executable='rqt_image_view', + arguments=[LaunchConfiguration('image_topic')], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + + # Bridge + bridge = Node( + package='ros_gz_image', + executable='image_bridge', + arguments=['camera', 'depth_camera', 'rgbd_camera/image', 'rgbd_camera/depth_image'], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rqt', default_value='true', + description='Open RQt.'), + DeclareLaunchArgument('image_topic', default_value='/camera', + description='Topic to start viewing in RQt.'), + bridge, + rqt + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/imu.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/imu.launch.py new file mode 100644 index 00000000..649ad359 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/imu.launch.py @@ -0,0 +1,78 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r sensors.sdf' + }.items(), + ) + + # RQt + rqt = Node( + package='rqt_topic', + executable='rqt_topic', + arguments=['-t'], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + + # RViz + # FIXME: Add once there's an IMU display for RViz2 + # 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_gz_sim_demos, 'rviz', 'imu.rviz')], + # condition=IfCondition(LaunchConfiguration('rviz')) + # ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/imu@sensor_msgs/msg/Imu@ignition.msgs.IMU'], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument( + 'rqt', default_value='true', description='Open RQt.' + ), + DeclareLaunchArgument( + 'rviz', default_value='true', description='Open RViz.' + ), + bridge, + rqt + # rviz + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/joint_states.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/joint_states.launch.py new file mode 100644 index 00000000..20b330ec --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/joint_states.launch.py @@ -0,0 +1,98 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch_ros.actions import Node +import xacro + + +def generate_launch_description(): + + # Package Directories + 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_gz_sim_demos, 'models', 'rrbot.xacro') + robot_description_config = xacro.process_file( + robot_description_file + ) + robot_description = {'robot_description': robot_description_config.toxml()} + + # Robot state publisher + robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + output='both', + parameters=[robot_description], + ) + + # Gazebo Sim + gazebo = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py') + ), + launch_arguments={'gz_args': '-r empty.sdf'}.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'joint_states.rviz')], + ) + + # Spawn + spawn = Node( + package='ros_gz_sim', + executable='create', + arguments=[ + '-name', 'rrbot', + '-topic', 'robot_description', + ], + output='screen', + ) + + # Gz - ROS Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=[ + # Clock (IGN -> ROS2) + '/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock', + # Joint states (IGN -> ROS2) + '/world/empty/model/rrbot/joint_state@sensor_msgs/msg/JointState[ignition.msgs.Model', + ], + remappings=[ + ('/world/empty/model/rrbot/joint_state', 'joint_states'), + ], + output='screen' + ) + + return LaunchDescription( + [ + # Nodes and Launches + gazebo, + spawn, + bridge, + robot_state_publisher, + rviz, + ] + ) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/magnetometer.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/magnetometer.launch.py new file mode 100644 index 00000000..0e026676 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/magnetometer.launch.py @@ -0,0 +1,63 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r sensors.sdf' + }.items(), + ) + + # RQt + rqt = Node( + package='rqt_topic', + executable='rqt_topic', + arguments=['-t'], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/magnetometer@sensor_msgs/msg/MagneticField@ignition.msgs.Magnetometer'], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rqt', default_value='true', + description='Open RQt.'), + bridge, + rqt + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera.launch.py new file mode 100644 index 00000000..1ec8409b --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera.launch.py @@ -0,0 +1,63 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + # launch_arguments={ + # 'gz_args': '-r rgbd_camera.sdf' + # }.items(), + ) + + # FIXME: need rviz configuration migration + # rviz = Node( + # package='rviz2', + # executable='rviz2', + # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'rgbd_camera.rviz')], + # condition=IfCondition(LaunchConfiguration('rviz')) + # ) + + # Bridge + bridge = Node( + 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_gz_point_cloud/ + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + bridge, + # rviz, + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera_bridge.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera_bridge.launch.py new file mode 100644 index 00000000..a318f682 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera_bridge.launch.py @@ -0,0 +1,70 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r sensors_demo.sdf' + }.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + arguments=[ + '-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'rgbd_camera_bridge.rviz') + ], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + 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', + '/rgbd_camera/points@sensor_msgs/msg/PointCloud2@ignition.msgs.PointCloudPacked' + ], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + bridge, + rviz, + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/robot_description_publisher.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/robot_description_publisher.launch.py new file mode 100755 index 00000000..882cdee3 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/robot_description_publisher.launch.py @@ -0,0 +1,93 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch_ros.actions import Node + + +def generate_launch_description(): + # Import the model urdf (load from file, xacro ...) + robot_desc = \ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + '' + + # Robot state publisher + params = {'use_sim_time': True, 'robot_description': robot_desc} + robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + output='screen', + parameters=[params], + arguments=[]) + + # Gazebo Sim + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + gazebo = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={'gz_args': '-r empty.sdf'}.items(), + ) + + # RViz + 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_gz_sim_demos, 'rviz', 'robot_description_publisher.rviz') + ] + ) + + # Spawn + spawn = Node(package='ros_gz_sim', executable='create', + arguments=[ + '-name', 'my_custom_model', + '-x', '1.2', + '-z', '2.3', + '-Y', '3.4', + '-topic', '/robot_description'], + output='screen') + + return LaunchDescription([ + gazebo, + robot_state_publisher, + rviz, + spawn + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/tf_bridge.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/tf_bridge.launch.py new file mode 100644 index 00000000..3b2171d0 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/tf_bridge.launch.py @@ -0,0 +1,59 @@ +# Copyright 2022 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import ExecuteProcess +from launch_ros.actions import Node + + +def generate_launch_description(): + 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_gz_sim_demos, + 'models', + 'double_pendulum_model.sdf' + ) + ] + ), + # Launch a bridge to forward tf and joint states to ros2 + Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=[ + '/world/default/model/double_pendulum_with_base0/joint_state@' + 'sensor_msgs/msg/JointState[ignition.msgs.Model', + '/model/double_pendulum_with_base0/pose@' + 'tf2_msgs/msg/TFMessage[ignition.msgs.Pose_V' + ], + remappings=[ + ('/model/double_pendulum_with_base0/pose', '/tf'), + ('/world/default/model/double_pendulum_with_base0/joint_state', '/joint_states') + ] + ), + # Launch rviz + Node( + package='rviz2', + executable='rviz2', + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'tf_bridge.rviz')] + ) + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/triggered_camera.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/triggered_camera.launch.py new file mode 100644 index 00000000..9e6362a2 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/triggered_camera.launch.py @@ -0,0 +1,64 @@ +# Copyright 2022 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + 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_gz_sim_demos, 'rviz', 'camera.rviz')], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + 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', + '/camera_info@sensor_msgs/msg/CameraInfo@ignition.msgs.CameraInfo'], + output='screen' + ) + + return LaunchDescription([ + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + gz_sim, + bridge, + rviz + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/models/double_pendulum_model.sdf b/ros_gz_shims/ros_ign_gazebo_demos/models/double_pendulum_model.sdf new file mode 100644 index 00000000..91e072e4 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/models/double_pendulum_model.sdf @@ -0,0 +1,266 @@ + + + + + 0.001 + 1 + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 0 0 1 + 100 100 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + 0 0 0 0 0 0 + + + + 100 + + + 0 0 0.01 0 0 0 + + + 0.8 + 0.02 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + -0.275 0 1.1 0 0 0 + + + 0.2 0.2 2.2 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 0.01 0 0 0 + + + 0.8 + 0.02 + + + + + -0.275 0 1.1 0 0 0 + + + 0.2 0.2 2.2 + + + + + + + 0 0 2.1 -1.5708 0 0 + 0 + + 0 0 0.5 0 0 0 + + + -0.05 0 0 0 1.5708 0 + + + 0.1 + 0.3 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 1.0 0 1.5708 0 + + + 0.1 + 0.2 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + -0.05 0 0 0 1.5708 0 + + + 0.1 + 0.3 + + + + + 0 0 1.0 0 1.5708 0 + + + 0.1 + 0.2 + + + + + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + + + + 0.25 1.0 2.1 -2 0 0 + 0 + + 0 0 0.5 0 0 0 + + + 0 0 0 0 1.5708 0 + + + 0.08 + 0.3 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 0 0 1.5708 0 + + + 0.08 + 0.3 + + + + + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + + + + base + upper_link + + 1.0 0 0 + + + + + upper_link + lower_link + + 1.0 0 0 + + + + + + + + true + + true + + + + + + diff --git a/ros_gz_shims/ros_ign_gazebo_demos/models/rrbot.xacro b/ros_gz_shims/ros_ign_gazebo_demos/models/rrbot.xacro new file mode 100644 index 00000000..00680c14 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/models/rrbot.xacro @@ -0,0 +1,165 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 0.423529412 0.039215686 1 + 1 0.423529412 0.039215686 1 + 1 0.423529412 0.039215686 1 + + + + + + 0.2 + 0.2 + + 0 0 0 1 + 0 0 0 1 + 0 0 0 1 + + + + + + 0.2 + 0.2 + + 1 0.423529412 0.039215686 1 + 1 0.423529412 0.039215686 1 + 1 0.423529412 0.039215686 1 + + + + + + + + + \ No newline at end of file diff --git a/ros_gz_shims/ros_ign_gazebo_demos/package.xml b/ros_gz_shims/ros_ign_gazebo_demos/package.xml new file mode 100644 index 00000000..55bf4a5c --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/package.xml @@ -0,0 +1,17 @@ + + ros_ign_gazebo_demos + 0.0.1 + Shim package to redirect to ros_gz_sim_demos. + Apache 2.0 + Brandon Ong + + ament_cmake + ros_gz_sim_demos + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/camera.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/camera.rviz new file mode 100644 index 00000000..81398197 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/camera.rviz @@ -0,0 +1,137 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Camera1 + - /Camera1/Status1 + - /Image1 + Splitter Ratio: 0.5 + Tree Height: 557 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: rviz_default_plugins/Camera + Enabled: true + Image Rendering: background and overlay + Name: Camera + Overlay Alpha: 0.5 + Queue Size: 10 + Topic: /camera + Unreliable: false + Value: true + Visibility: + Grid: true + Image: true + Value: true + Zoom Factor: 1 + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 10 + Topic: /camera + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: camera/link/camera + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: /move_base_simple/goal + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 19.73822784423828 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.7903980016708374 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.785398006439209 + Saved: ~ +Window Geometry: + Camera: + collapsed: false + Displays: + collapsed: false + Height: 702 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd00000004000000000000015600000268fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b00000268000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c0000026100000001000001c700000268fc0200000005fb0000000c00430061006d006500720061010000003b0000011f0000002800fffffffb0000000a0049006d0061006700650100000160000001430000002800fffffffb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000000320000026800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 859 + X: 517 + Y: 361 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/depth_camera.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/depth_camera.rviz new file mode 100644 index 00000000..6957e15f --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/depth_camera.rviz @@ -0,0 +1,147 @@ +Panels: + - Class: rviz/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Image1 + - /PointCloud21 + Splitter Ratio: 0.5 + Tree Height: 423 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: Image +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Class: rviz/Image + Enabled: true + Image Topic: /depth_camera + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.019999999552965164 + Style: Flat Squares + Topic: /depth_camera/points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Global Options: + Background Color: 255; 255; 255 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 6.307931423187256 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.024829570204019547 + Y: -0.440496027469635 + Z: 1.0747597217559814 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: -1.3397971391677856 + Target Frame: + Value: Orbit (rviz) + Yaw: 4.723598957061768 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 568 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000001e2fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001e2000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d0065007200610000000272000000c1000000000000000000000001000001b8000001e2fc0200000006fb0000000a0049006d006100670065010000003b000001e20000001600fffffffb0000000c00430061006d00650072006100000001ae000001850000000000000000fb0000000c00430061006d00650072006101000001ba000001790000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b000000052fc0100000002fb0000000800540069006d006502000001a70000029a000004b000000052fb0000000800540069006d0065010000000000000450000000000000000000000196000001e200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 405 + Y: 378 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/diff_drive.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/diff_drive.rviz new file mode 100644 index 00000000..e647f4c9 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/diff_drive.rviz @@ -0,0 +1,123 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Odometry1 + - /Odometry1/Status1 + Splitter Ratio: 0.5 + Tree Height: 701 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Angle Tolerance: 0.10000000149011612 + Class: rviz_default_plugins/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Keep: 1000 + Name: Odometry + Position Tolerance: 0.10000000149011612 + Shape: + Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Color: 255; 25; 0 + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Value: Arrow + Topic: /model/vehicle_blue/odometry + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: vehicle_blue/odom + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: /move_base_simple/goal + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 68.66040802001953 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -1.2689772844314575 + Y: 10.203336715698242 + Z: -2.8907392024993896 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 1.5697963237762451 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.8253979682922363 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000004000000000000023d000002f8fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002f8000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f8fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d006501000000000000045000000000000000000000026d000002f800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 325 + Y: 158 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar.rviz new file mode 100644 index 00000000..9161d0c8 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar.rviz @@ -0,0 +1,181 @@ +Panels: + - Class: rviz/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /LaserScan1 + - /PointCloud21 + Splitter Ratio: 0.5 + Tree Height: 366 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: LaserScan +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 0 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.029999999329447746 + Style: Flat Squares + Topic: /lidar + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.029999999329447746 + Style: Flat Squares + Topic: /custom_params/pc2 + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: custom_params/link + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 10.596034049987793 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 1.855783224105835 + Y: -0.6233639717102051 + Z: 0.7489486932754517 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.5402030348777771 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.7535903453826904 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 511 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000001a9fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001a9000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c0000026100000001000001b8000002f8fc0200000006fb0000000a0049006d006100670065000000003b0000016d0000000000000000fb0000000c00430061006d006500720061000000003b000002f80000000000000000fb0000000c00430061006d00650072006101000001ba000001790000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b000000052fc0100000002fb0000000800540069006d006502000001a70000029a000004b000000052fb0000000800540069006d0065010000000000000450000000000000000000000161000001a900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 701 + X: 352 + Y: 269 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar_bridge.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar_bridge.rviz new file mode 100644 index 00000000..42968c2b --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar_bridge.rviz @@ -0,0 +1,167 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /LaserScan1/Status1 + - /PointCloud21/Status1 + Splitter Ratio: 0.504601240158081 + Tree Height: 701 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/LaserScan + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 0 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /lidar + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: "" + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: "" + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /lidar + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: model_with_lidar/link/gpu_lidar + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: /move_base_simple/goal + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 15.735194206237793 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 2.550645589828491 + Y: -0.290515273809433 + Z: -1.1467934846878052 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.7253980040550232 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.7385823726654053 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd0000000400000000000001ef000002f8fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000002ed00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002f8000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f8fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000002bb000002f800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1200 + X: 338 + Y: 1176 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/imu.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/imu.rviz new file mode 100644 index 00000000..0169390a --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/imu.rviz @@ -0,0 +1,130 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Imu1 + - /Imu1/Status1 + Splitter Ratio: 0.5 + Tree Height: 352 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz_plugin_tutorials/Imu + Color: 204; 51; 204 + Enabled: true + History Length: 1 + Name: Imu + Topic: /imu + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: sensors/sensors_box/link/imu + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 33.22251510620117 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -1.7206333875656128 + Y: -0.9246708154678345 + Z: 1.870512843132019 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.785398006439209 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.785398006439209 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 575 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000191000001e9fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001e9000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002b4000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003d70000003efc0100000002fb0000000800540069006d00650000000000000003d70000024400fffffffb0000000800540069006d00650100000000000004500000000000000000000001a2000001e900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 825 + X: 751 + Y: 92 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/joint_states.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/joint_states.rviz new file mode 100644 index 00000000..06920d70 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/joint_states.rviz @@ -0,0 +1,190 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1 + - /TF1 + Splitter Ratio: 0.5 + Tree Height: 802 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 0.800000011920929 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + link1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz_default_plugins/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + link1: + Value: true + link2: + Value: true + link3: + Value: true + world: + Value: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + link1: + link2: + link3: + {} + world: + {} + Update Interval: 0 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: world + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 6.524543762207031 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.106326624751091 + Y: 0.5023337006568909 + Z: 1.1979976892471313 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.7303980588912964 + Target Frame: + Value: Orbit (rviz) + Yaw: 5.698581218719482 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1025 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000003abfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000003ab000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000003abfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000003ab000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000004cc000003ab00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1853 + X: 67 + Y: 27 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera.rviz new file mode 100644 index 00000000..d6933fc6 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera.rviz @@ -0,0 +1,159 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /PointCloud21 + - /Image2 + Splitter Ratio: 0.5 + Tree Height: 317 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: Image +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Class: rviz/Image + Enabled: true + Image Topic: /rgbd_camera/depth_image + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.029999999329447746 + Style: Flat Squares + Topic: /default_params/points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /rgbd_camera/image + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: default_params + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 3.1044178009033203 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.04919945076107979 + Y: -0.08779548853635788 + Z: 2.6499500274658203 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: -1.3547965288162231 + Target Frame: + Value: Orbit (rviz) + Yaw: 4.718593597412109 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 540 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000001c6fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001c6000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000012d000001c6fc0200000007fb0000000a0049006d006100670065010000003b000000d60000001600fffffffb0000000a0049006d0061006700650100000117000000ea0000001600fffffffc000001ce000001650000000000fffffffa000000000100000002fb0000000a0049006d0061006700650100000000ffffffff0000000000000000fb0000000c00430061006d006500720061000000044c000000640000000000000000fb0000000c00430061006d00650072006101000001ba000001790000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b000000052fc0100000002fb0000000800540069006d006502000001a70000029a000004b000000052fb0000000800540069006d006501000000000000045000000000000000000000011a000001c600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 937 + X: 147 + Y: 349 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera_bridge.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera_bridge.rviz new file mode 100644 index 00000000..58955045 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera_bridge.rviz @@ -0,0 +1,142 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /PointCloud21/Status1 + Splitter Ratio: 0.3251533806324005 + Tree Height: 701 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.05000000074505806 + Style: Flat Squares + Topic: /rgbd_camera/points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 10 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: false + Queue Size: 10 + Topic: /rgbd_camera/depth_image + Unreliable: false + Value: true + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 10 + Topic: /rgbd_camera/image + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: rgbd_camera/link/rgbd_camera + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: /move_base_simple/goal + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 5.996953964233398 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0.10905617475509644 + Y: 0.08000272512435913 + Z: 0.346417099237442 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.29039809107780457 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.0753986835479736 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd000000040000000000000174000002f8fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000002ed00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002f8000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f8fc0200000005fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0049006d006100670065010000003b000002020000002800fffffffb0000000a0049006d0061006700650100000243000000f00000002800fffffffb0000000a0056006900650077007300000000cf00000264000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d0065010000000000000450000000000000000000000221000002f800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 375 + Y: 1116 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/robot_description_publisher.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/robot_description_publisher.rviz new file mode 100644 index 00000000..058a47f4 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/robot_description_publisher.rviz @@ -0,0 +1,148 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /RobotModel1/Description Topic1 + Splitter Ratio: 0.5 + Tree Height: 878 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 77; 77; 79 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 50 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + Enabled: true + Global Options: + Background Color: 207; 207; 207 + Fixed Frame: link + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /move_base_simple/goal + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 49.51093292236328 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0.8779783248901367 + Y: 0.15285056829452515 + Z: 0.762141764163971 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.6602023243904114 + Target Frame: + Value: Orbit (rviz) + Yaw: 4.142223358154297 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1023 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000222000003a9fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000003a9000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f8fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d0065010000000000000450000000000000000000000198000003a900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 960 + X: 898 + Y: 27 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/tf_bridge.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/tf_bridge.rviz new file mode 100644 index 00000000..76c42557 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/tf_bridge.rviz @@ -0,0 +1,163 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /TF1 + - /TF1/Frames1 + Splitter Ratio: 0.516339898109436 + Tree Height: 549 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: rviz_default_plugins/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + double_pendulum_with_base0: + Value: true + double_pendulum_with_base0/base: + Value: true + double_pendulum_with_base0/lower_link: + Value: true + double_pendulum_with_base0/upper_link: + Value: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + double_pendulum_with_base0: + double_pendulum_with_base0/base: + {} + double_pendulum_with_base0/lower_link: + {} + double_pendulum_with_base0/upper_link: + {} + Update Interval: 0 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: double_pendulum_with_base0 + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 8.114859580993652 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.3453984260559082 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.2535715103149414 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd0000000400000000000002ff000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000066f0000003efc0100000002fb0000000800540069006d006501000000000000066f000002eb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000255000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1647 + X: 251 + Y: 169 diff --git a/ros_gz_shims/ros_ign_image/CMakeLists.txt b/ros_gz_shims/ros_ign_image/CMakeLists.txt new file mode 100644 index 00000000..5fa4b91b --- /dev/null +++ b/ros_gz_shims/ros_ign_image/CMakeLists.txt @@ -0,0 +1,26 @@ +cmake_minimum_required(VERSION 3.5) + +project(ros_ign_image) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wpedantic") +endif() + +find_package(ament_cmake REQUIRED) +find_package(ament_index_cpp REQUIRED) + +add_executable(image_bridge src/image_bridge_shim.cpp) +ament_target_dependencies(image_bridge ament_index_cpp) + +ament_export_dependencies(ament_index_cpp ros_gz_image) + +install(TARGETS + image_bridge + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/ros_gz_shims/ros_ign_image/README.md b/ros_gz_shims/ros_ign_image/README.md new file mode 100644 index 00000000..517ccdd8 --- /dev/null +++ b/ros_gz_shims/ros_ign_image/README.md @@ -0,0 +1,2 @@ +# This is a shim package +For [ros_gz_image](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_image) diff --git a/ros_gz_shims/ros_ign_image/package.xml b/ros_gz_shims/ros_ign_image/package.xml new file mode 100644 index 00000000..7b621801 --- /dev/null +++ b/ros_gz_shims/ros_ign_image/package.xml @@ -0,0 +1,19 @@ + + + + ros_ign_image + 0.0.1 + Shim package to redirect to ros_gz_image. + Brandon Ong + + Apache 2.0 + + ament_cmake + ament_index_cpp + + ros_gz_image + + + ament_cmake + + diff --git a/ros_gz_shims/ros_ign_image/src/image_bridge_shim.cpp b/ros_gz_shims/ros_ign_image/src/image_bridge_shim.cpp new file mode 100644 index 00000000..c004a7dc --- /dev/null +++ b/ros_gz_shims/ros_ign_image/src/image_bridge_shim.cpp @@ -0,0 +1,30 @@ +// Shim to redirect "ros_ign_image image_bridge" call to "ros_gz_image image_bridge" + +#include +#include +#include +#include + +#include + + +int main(int argc, char * argv[]) +{ + std::stringstream cli_call; + + cli_call << ament_index_cpp::get_package_prefix("ros_gz_image") + << "/lib/ros_gz_image/image_bridge"; + + if (argc > 1) + { + for (int i = 1; i < argc; i++) + cli_call << " " << argv[i]; + } + + std::cerr << "[ros_ign_bridge] is deprecated! " + << "Redirecting to use [ros_gz_image] instead!" + << std::endl << std::endl; + system(cli_call.str().c_str()); + + return 0; +} diff --git a/ros_gz_shims/ros_ign_interfaces/CMakeLists.txt b/ros_gz_shims/ros_ign_interfaces/CMakeLists.txt new file mode 100644 index 00000000..b397466b --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/CMakeLists.txt @@ -0,0 +1,49 @@ +cmake_minimum_required(VERSION 3.5) +project(ros_ign_interfaces) + +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(builtin_interfaces REQUIRED) +find_package(std_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(ros_gz_interfaces REQUIRED) +find_package(rosidl_default_generators REQUIRED) + +set(msg_files + "msg/Contact.msg" + "msg/Contacts.msg" + "msg/Entity.msg" + "msg/EntityFactory.msg" + "msg/GuiCamera.msg" + "msg/JointWrench.msg" + "msg/Light.msg" + "msg/StringVec.msg" + "msg/TrackVisual.msg" + "msg/VideoRecord.msg" + "msg/WorldControl.msg" + "msg/WorldReset.msg" +) + +set(srv_files + "srv/ControlWorld.srv" + "srv/DeleteEntity.srv" + "srv/SetEntityPose.srv" + "srv/SpawnEntity.srv" +) + +rosidl_generate_interfaces(${PROJECT_NAME} + ${msg_files} + ${srv_files} + DEPENDENCIES builtin_interfaces std_msgs geometry_msgs ros_gz_interfaces + ADD_LINTER_TESTS +) + +ament_export_dependencies(rosidl_default_runtime) +ament_package() diff --git a/ros_gz_shims/ros_ign_interfaces/README.md b/ros_gz_shims/ros_ign_interfaces/README.md new file mode 100644 index 00000000..b2ce4368 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/README.md @@ -0,0 +1,2 @@ +# This is a shim package +For [ros_gz_sim_demos](https://github.com/gazebosim/ros_gz/tree/ros2/ros_ign_gazebo_demos) diff --git a/ros_gz_shims/ros_ign_interfaces/msg/Contact.msg b/ros_gz_shims/ros_ign_interfaces/msg/Contact.msg new file mode 100644 index 00000000..98d2cef8 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/Contact.msg @@ -0,0 +1,6 @@ +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_gz_interfaces/JointWrench[] wrenches # List of joint wrenches including forces/torques diff --git a/ros_gz_shims/ros_ign_interfaces/msg/Contacts.msg b/ros_gz_shims/ros_ign_interfaces/msg/Contacts.msg new file mode 100644 index 00000000..40232e51 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/Contacts.msg @@ -0,0 +1,2 @@ +std_msgs/Header header # Time stamp +ros_gz_interfaces/Contact[] contacts # List of contacts diff --git a/ros_gz_shims/ros_ign_interfaces/msg/Entity.msg b/ros_gz_shims/ros_ign_interfaces/msg/Entity.msg new file mode 100644 index 00000000..b785c7ed --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/Entity.msg @@ -0,0 +1,13 @@ +# Entity type: constant definition +uint8 NONE = 0 +uint8 LIGHT = 1 +uint8 MODEL = 2 +uint8 LINK = 3 +uint8 VISUAL = 4 +uint8 COLLISION = 5 +uint8 SENSOR = 6 +uint8 JOINT = 7 + +uint64 id # Entity unique identifier accross all types. Defaults to 0 +string name # Entity name, which is not guaranteed to be unique. +uint8 type # Entity type. diff --git a/ros_gz_shims/ros_ign_interfaces/msg/EntityFactory.msg b/ros_gz_shims/ros_ign_interfaces/msg/EntityFactory.msg new file mode 100644 index 00000000..4576c003 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/EntityFactory.msg @@ -0,0 +1,11 @@ +string name # New name for the entity, overrides the name on the SDF +bool allow_renaming false # Whether the server is allowed to rename the entity in case of + # overlap with existing entities. + +# Only one method is supported at a time (sdf,sdf_filename,clone_name) +string sdf # SDF description in string format +string sdf_filename # Full path to SDF file. +string clone_name # Name of entity to clone + +geometry_msgs/Pose pose # Pose where the entity will be spawned in the world. +string relative_to "world" # Pose is defined relative to the frame of this entity. diff --git a/ros_gz_shims/ros_ign_interfaces/msg/GuiCamera.msg b/ros_gz_shims/ros_ign_interfaces/msg/GuiCamera.msg new file mode 100644 index 00000000..d45fd9b8 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/GuiCamera.msg @@ -0,0 +1,12 @@ +# Message for a GUI Camera. + +# Optional header data. +std_msgs/Header header + +string name +string view_controller +geometry_msgs/Pose pose +TrackVisual track + +# Type of projection: "perspective" or "orthographic". +string projection_type diff --git a/ros_gz_shims/ros_ign_interfaces/msg/JointWrench.msg b/ros_gz_shims/ros_ign_interfaces/msg/JointWrench.msg new file mode 100644 index 00000000..2da89094 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/JointWrench.msg @@ -0,0 +1,8 @@ +std_msgs/Header header # Time stamp +std_msgs/String body_1_name # Body 1 name string +std_msgs/UInt32 body_1_id # Body 1 id +std_msgs/String body_2_name # Body 2 name string +std_msgs/UInt32 body_2_id # Body 2 id + +geometry_msgs/Wrench body_1_wrench # Body 1 wrench +geometry_msgs/Wrench body_2_wrench # Body 2 wrench diff --git a/ros_gz_shims/ros_ign_interfaces/msg/Light.msg b/ros_gz_shims/ros_ign_interfaces/msg/Light.msg new file mode 100644 index 00000000..911e20bd --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/Light.msg @@ -0,0 +1,29 @@ +std_msgs/Header header # Optional header data + +string name # Light name + +# Light type: constant definition +uint8 POINT = 0 +uint8 SPOT = 1 +uint8 DIRECTIONAL = 2 + +uint8 type # Light type (from constant definitions) + +geometry_msgs/Pose pose # Light pose +std_msgs/ColorRGBA diffuse # Light diffuse emission +std_msgs/ColorRGBA specular # Light specular emission +float32 attenuation_constant # Constant variable in attenuation formula +float32 attenuation_linear # Linear variable in attenuation formula +float32 attenuation_quadratic # Quadratic variable in attenuation formula +geometry_msgs/Vector3 direction # Light direction +float32 range # Light range +bool cast_shadows # Enable/disable shadow casting +float32 spot_inner_angle # Spotlight inner cone angle +float32 spot_outer_angle # Spotlight outer cone angle +float32 spot_falloff # Falloff between inner and outer cone + +uint32 id # Unique id of the light + +uint32 parent_id # Unique id of the light's parent + +float32 intensity # Light intensity diff --git a/ros_gz_shims/ros_ign_interfaces/msg/StringVec.msg b/ros_gz_shims/ros_ign_interfaces/msg/StringVec.msg new file mode 100644 index 00000000..15a7dda9 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/StringVec.msg @@ -0,0 +1,7 @@ +# A message for a vector of string data. + +# Optional header data. +std_msgs/Header header + +# The vector of strings. +string[] data diff --git a/ros_gz_shims/ros_ign_interfaces/msg/TrackVisual.msg b/ros_gz_shims/ros_ign_interfaces/msg/TrackVisual.msg new file mode 100644 index 00000000..c09f4785 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/TrackVisual.msg @@ -0,0 +1,33 @@ +# Message for a tracking a rendering::Visual with a rendering::Camera. + +# Optional header data. +std_msgs/Header header + +# Name of the visual to track. +string name + +# Id of the visual to track. +uint32 id + +# True to have the tracking camera inherit the orientation of +# the tracked visual. +bool inherit_orientation + +# Minimum follow distance. +float64 min_dist + +# Maximum follow distance. +float64 max_dist + +# If set to true, the position of the camera is fixed. +bool is_static + +# If set to true, the position of the camera is relative to the. +# model reference frame. +bool use_model_frame + +# Position of the camera. +geometry_msgs/Vector3 xyz + +# If set to true, the camera inherits the yaw rotation of the model. +bool inherit_yaw diff --git a/ros_gz_shims/ros_ign_interfaces/msg/VideoRecord.msg b/ros_gz_shims/ros_ign_interfaces/msg/VideoRecord.msg new file mode 100644 index 00000000..02bafde0 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/VideoRecord.msg @@ -0,0 +1,16 @@ +# A message that allows for control of video recording functions. + +# Optional header data. +std_msgs/Header header + +# True to start video recording. +bool start + +# True to stop video recording. +bool stop + +# Video encoding format, e.g. "mp4", "ogv". +string format + +# filename of the recorded video. +string save_filename diff --git a/ros_gz_shims/ros_ign_interfaces/msg/WorldControl.msg b/ros_gz_shims/ros_ign_interfaces/msg/WorldControl.msg new file mode 100644 index 00000000..efa22fb9 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/WorldControl.msg @@ -0,0 +1,7 @@ +bool pause # Paused state. +bool step # +uint32 multi_step 0 # Paused after stepping multi_step. +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_shims/ros_ign_interfaces/msg/WorldReset.msg b/ros_gz_shims/ros_ign_interfaces/msg/WorldReset.msg new file mode 100644 index 00000000..46f5971f --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/WorldReset.msg @@ -0,0 +1,3 @@ +bool all false # Reset time and model +bool time_only false # Reset time only +bool model_only false # Reset model only diff --git a/ros_gz_shims/ros_ign_interfaces/package.xml b/ros_gz_shims/ros_ign_interfaces/package.xml new file mode 100644 index 00000000..4c0909e1 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/package.xml @@ -0,0 +1,27 @@ + + ros_ign_interfaces + 0.0.1 + Shim package to redirect to ros_gz_interfaces. + Apache 2.0 + Brandon Ong + Zhenpeng Ge + ament_cmake + rosidl_default_generators + + builtin_interfaces + ros_gz_interfaces + std_msgs + geometry_msgs + + builtin_interfaces + ros_gz_interfaces + std_msgs + geometry_msgs + rosidl_default_runtime + + ament_lint_common + rosidl_interface_packages + + ament_cmake + + diff --git a/ros_gz_shims/ros_ign_interfaces/srv/ControlWorld.srv b/ros_gz_shims/ros_ign_interfaces/srv/ControlWorld.srv new file mode 100644 index 00000000..d8e41f24 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/srv/ControlWorld.srv @@ -0,0 +1,3 @@ +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_shims/ros_ign_interfaces/srv/DeleteEntity.srv b/ros_gz_shims/ros_ign_interfaces/srv/DeleteEntity.srv new file mode 100644 index 00000000..13b3e1fd --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/srv/DeleteEntity.srv @@ -0,0 +1,3 @@ +ros_gz_interfaces/Entity entity # Gazebo Sim entity to be deleted. +--- +bool success # Return true if deletion is successful. diff --git a/ros_gz_shims/ros_ign_interfaces/srv/SetEntityPose.srv b/ros_gz_shims/ros_ign_interfaces/srv/SetEntityPose.srv new file mode 100644 index 00000000..b749488c --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/srv/SetEntityPose.srv @@ -0,0 +1,4 @@ +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_shims/ros_ign_interfaces/srv/SpawnEntity.srv b/ros_gz_shims/ros_ign_interfaces/srv/SpawnEntity.srv new file mode 100644 index 00000000..35d5df59 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/srv/SpawnEntity.srv @@ -0,0 +1,3 @@ +ros_gz_interfaces/EntityFactory entity_factory # Message to create a new entity +--- +bool success # Return true if spawned successfully.