Skip to content

Commit

Permalink
Support ros_ign migration (#282)
Browse files Browse the repository at this point in the history
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 <LIB>, ros_ign_ci

Signed-off-by: methylDragon <methylDragon@gmail.com>
  • Loading branch information
methylDragon committed Aug 17, 2022
1 parent ee51d08 commit 07bca97
Show file tree
Hide file tree
Showing 96 changed files with 702 additions and 658 deletions.
2 changes: 1 addition & 1 deletion ros_gz/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.5)
project(ros_ign)
project(ros_gz)
find_package(ament_cmake REQUIRED)

if(BUILD_TESTING)
Expand Down
12 changes: 6 additions & 6 deletions ros_gz/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,20 +3,20 @@
<package format="2">
<!-- TODO: Make this a metapackage, see
https://github.com/ros2/ros2/issues/408 -->
<name>ros_ign</name>
<name>ros_gz</name>
<version>0.244.3</version>
<description>Meta-package containing interfaces for using ROS 2 with <a href="https://gazebosim.org">Gazebo</a> simulation.</description>
<maintainer email="louise@openrobotics.org">Louise Poubel</maintainer>
<license>Apache 2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>

<exec_depend>ros_ign_bridge</exec_depend>
<exec_depend>ros_ign_gazebo</exec_depend>
<exec_depend>ros_ign_gazebo_demos</exec_depend>
<exec_depend>ros_ign_image</exec_depend>
<exec_depend>ros_gz_bridge</exec_depend>
<exec_depend>ros_gz_gazebo</exec_depend>
<exec_depend>ros_gz_gazebo_demos</exec_depend>
<exec_depend>ros_gz_image</exec_depend>
<!-- See https://github.com/gazebosim/ros_gz/issues/40 -->
<!--exec_depend>ros_ign_point_cloud</exec_depend-->
<!--exec_depend>ros_gz_point_cloud</exec_depend-->

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
38 changes: 19 additions & 19 deletions ros_gz_bridge/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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)
Expand All @@ -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)
Expand Down Expand Up @@ -67,7 +67,7 @@ set(PACKAGES
builtin_interfaces
geometry_msgs
nav_msgs
ros_ign_interfaces
ros_gz_interfaces
rosgraph_msgs
sensor_msgs
std_msgs
Expand Down Expand Up @@ -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}
Expand Down Expand Up @@ -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
)

Expand All @@ -190,7 +190,7 @@ if(BUILD_TESTING)
geometry_msgs
nav_msgs
rclcpp
ros_ign_interfaces
ros_gz_interfaces
rosgraph_msgs
sensor_msgs
std_msgs
Expand All @@ -206,22 +206,22 @@ 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
test/subscribers/ros_subscriber/trajectory_msgs_subscriber.cpp)

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)
Expand All @@ -230,21 +230,21 @@ 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}
)

add_launch_test(test/launch/test_ros_subscriber.launch.py
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()
Expand Down
22 changes: 11 additions & 11 deletions ros_gz_bridge/include/ros_gz_bridge/convert.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 <ros_ign_bridge/convert/geometry_msgs.hpp>
#include <ros_ign_bridge/convert/nav_msgs.hpp>
#include <ros_ign_bridge/convert/ros_ign_interfaces.hpp>
#include <ros_ign_bridge/convert/rosgraph_msgs.hpp>
#include <ros_ign_bridge/convert/sensor_msgs.hpp>
#include <ros_ign_bridge/convert/std_msgs.hpp>
#include <ros_ign_bridge/convert/tf2_msgs.hpp>
#include <ros_ign_bridge/convert/trajectory_msgs.hpp>
#include <ros_gz_bridge/convert/geometry_msgs.hpp>
#include <ros_gz_bridge/convert/nav_msgs.hpp>
#include <ros_gz_bridge/convert/ros_gz_interfaces.hpp>
#include <ros_gz_bridge/convert/rosgraph_msgs.hpp>
#include <ros_gz_bridge/convert/sensor_msgs.hpp>
#include <ros_gz_bridge/convert/std_msgs.hpp>
#include <ros_gz_bridge/convert/tf2_msgs.hpp>
#include <ros_gz_bridge/convert/trajectory_msgs.hpp>

#endif // ROS_IGN_BRIDGE__CONVERT_HPP_
#endif // ROS_GZ_BRIDGE__CONVERT_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -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 <ignition/msgs/time.pb.h>

#include <builtin_interfaces/msg/time.hpp>

#include "ros_ign_bridge/convert_decl.hpp"
#include "ros_gz_bridge/convert_decl.hpp"

namespace ros_gz_bridge
{
Expand All @@ -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_
8 changes: 4 additions & 4 deletions ros_gz_bridge/include/ros_gz_bridge/convert/geometry_msgs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 <ignition/msgs/quaternion.pb.h>
Expand All @@ -36,7 +36,7 @@
#include <geometry_msgs/msg/twist_with_covariance.hpp>
#include <geometry_msgs/msg/wrench.hpp>

#include <ros_ign_bridge/convert_decl.hpp>
#include <ros_gz_bridge/convert_decl.hpp>

namespace ros_gz_bridge
{
Expand Down Expand Up @@ -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_
8 changes: 4 additions & 4 deletions ros_gz_bridge/include/ros_gz_bridge/convert/nav_msgs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 <ignition/msgs/odometry.pb.h>
Expand All @@ -22,7 +22,7 @@
// ROS 2 messages
#include <nav_msgs/msg/odometry.hpp>

#include <ros_ign_bridge/convert_decl.hpp>
#include <ros_gz_bridge/convert_decl.hpp>

namespace ros_gz_bridge
{
Expand Down Expand Up @@ -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_
Loading

0 comments on commit 07bca97

Please sign in to comment.