Skip to content

Commit

Permalink
Improve modularity of ign/ros publisher tests (#194)
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <michael@openrobotics.org>
Signed-off-by: Louise Poubel <louise@openrobotics.org>

Co-authored-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
mjcarroll and chapulina committed Feb 7, 2022
1 parent 2587cca commit cf6a2d6
Show file tree
Hide file tree
Showing 11 changed files with 2,759 additions and 2,434 deletions.
58 changes: 16 additions & 42 deletions ros_ign_bridge/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -146,27 +146,20 @@ if(BUILD_TESTING)
find_package(launch_testing_ament_cmake REQUIRED)
ament_find_gtest()

add_executable(test_ros_publisher test/publishers/ros_publisher.cpp)
ament_target_dependencies(test_ros_publisher
geometry_msgs
nav_msgs
rclcpp
ros_ign_interfaces
rosgraph_msgs
sensor_msgs
std_msgs
tf2_msgs
trajectory_msgs
add_library(test_utils
test/utils/ign_test_msg.cpp
test/utils/ros_test_msg.cpp
)

target_include_directories(test_utils
PUBLIC test ${GTEST_INCLUDE_DIRS}
)
target_link_libraries(test_ros_publisher
target_link_libraries(test_utils
${GTEST_LIBRARIES}
ignition-msgs${IGN_MSGS_VER}::core
ignition-transport${IGN_TRANSPORT_VER}::core
)
target_include_directories(test_ros_publisher PUBLIC ${GTEST_INCLUDE_DIRS})

add_executable(test_ros_subscriber test/subscribers/ros_subscriber.cpp)
ament_target_dependencies(test_ros_subscriber
ament_target_dependencies(test_utils
geometry_msgs
nav_msgs
rclcpp
Expand All @@ -178,36 +171,17 @@ if(BUILD_TESTING)
trajectory_msgs
)

target_link_libraries(test_ros_subscriber
${GTEST_LIBRARIES}
ignition-msgs${IGN_MSGS_VER}::core
ignition-transport${IGN_TRANSPORT_VER}::core
)
target_include_directories(test_ros_subscriber PUBLIC ${GTEST_INCLUDE_DIRS})
add_executable(test_ros_publisher test/publishers/ros_publisher.cpp)
target_link_libraries(test_ros_publisher test_utils)

add_executable(test_ros_subscriber test/subscribers/ros_subscriber.cpp)
target_link_libraries(test_ros_subscriber test_utils)

add_executable(test_ign_publisher test/publishers/ign_publisher.cpp)
ament_target_dependencies(test_ign_publisher
ros_ign_interfaces
rclcpp
)
target_link_libraries(test_ign_publisher
${GTEST_LIBRARIES}
ignition-msgs${IGN_MSGS_VER}::core
ignition-transport${IGN_TRANSPORT_VER}::core
)
target_include_directories(test_ign_publisher PUBLIC ${GTEST_INCLUDE_DIRS})
target_link_libraries(test_ign_publisher test_utils)

add_executable(test_ign_subscriber test/subscribers/ign_subscriber.cpp)
ament_target_dependencies(test_ign_subscriber
ros_ign_interfaces
rclcpp
)
target_link_libraries(test_ign_subscriber
${GTEST_LIBRARIES}
ignition-msgs${IGN_MSGS_VER}::core
ignition-transport${IGN_TRANSPORT_VER}::core
)
target_include_directories(test_ign_subscriber PUBLIC ${GTEST_INCLUDE_DIRS})
target_link_libraries(test_ign_subscriber test_utils)

install(TARGETS
test_ros_publisher
Expand Down
3 changes: 2 additions & 1 deletion ros_ign_bridge/test/publishers/ign_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,8 @@
#include <string>
#include <thread>

#include "../test_utils.hpp"
#include "utils/test_utils.hpp"
#include "utils/ign_test_msg.hpp"

/// \brief Flag used to break the publisher loop and terminate the program.
static std::atomic<bool> g_terminatePub(false);
Expand Down
32 changes: 2 additions & 30 deletions ros_ign_bridge/test/publishers/ros_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,37 +12,9 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <geometry_msgs/msg/quaternion.hpp>
#include <geometry_msgs/msg/transform.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <geometry_msgs/msg/twist.hpp>
#include <geometry_msgs/msg/vector3.hpp>
// #include <mav_msgs/msg/actuators.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <rclcpp/rclcpp.hpp>
#include <ros_ign_interfaces/msg/light.hpp>
#include <rosgraph_msgs/msg/clock.hpp>
#include <sensor_msgs/msg/battery_state.hpp>
#include <sensor_msgs/msg/camera_info.hpp>
#include <sensor_msgs/msg/fluid_pressure.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/msg/imu.hpp>
#include <sensor_msgs/msg/joint_state.hpp>
#include <sensor_msgs/msg/laser_scan.hpp>
#include <sensor_msgs/msg/magnetic_field.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <std_msgs/msg/bool.hpp>
#include <std_msgs/msg/color_rgba.hpp>
#include <std_msgs/msg/empty.hpp>
#include <std_msgs/msg/float32.hpp>
#include <std_msgs/msg/float64.hpp>
#include <std_msgs/msg/header.hpp>
#include <std_msgs/msg/string.hpp>
#include <tf2_msgs/msg/tf_message.hpp>
#include <trajectory_msgs/msg/joint_trajectory.hpp>
#include "../test_utils.hpp"
#include "utils/test_utils.hpp"
#include "utils/ros_test_msg.hpp"

//////////////////////////////////////////////////
int main(int argc, char ** argv)
Expand Down
4 changes: 3 additions & 1 deletion ros_ign_bridge/test/subscribers/ign_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,9 @@
#include <chrono>
#include <memory>
#include <string>
#include "../test_utils.hpp"

#include "utils/test_utils.hpp"
#include "utils/ign_test_msg.hpp"

//////////////////////////////////////////////////
/// \brief A class for testing Ignition Transport topic subscription.
Expand Down
35 changes: 5 additions & 30 deletions ros_ign_bridge/test/subscribers/ros_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,40 +13,15 @@
// limitations under the License.

#include <gtest/gtest.h>

#include <rclcpp/rclcpp.hpp>

#include <chrono>
#include <memory>
#include <string>

#include "geometry_msgs/msg/pose.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/quaternion.hpp"
#include "geometry_msgs/msg/transform.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "geometry_msgs/msg/vector3.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "rclcpp/rclcpp.hpp"
#include "ros_ign_interfaces/msg/light.hpp"
#include "rosgraph_msgs/msg/clock.hpp"
#include "sensor_msgs/msg/battery_state.hpp"
#include "sensor_msgs/msg/camera_info.hpp"
#include "sensor_msgs/msg/fluid_pressure.hpp"
#include "sensor_msgs/msg/image.hpp"
#include "sensor_msgs/msg/imu.hpp"
#include "sensor_msgs/msg/joint_state.hpp"
#include "sensor_msgs/msg/laser_scan.hpp"
#include "sensor_msgs/msg/magnetic_field.hpp"
#include "sensor_msgs/msg/point_cloud2.hpp"
#include "std_msgs/msg/bool.hpp"
#include "std_msgs/msg/color_rgba.hpp"
#include "std_msgs/msg/empty.hpp"
#include "std_msgs/msg/float32.hpp"
#include "std_msgs/msg/header.hpp"
#include "std_msgs/msg/string.hpp"
#include "tf2_msgs/msg/tf_message.hpp"
#include "trajectory_msgs/msg/joint_trajectory.hpp"

#include "../test_utils.hpp"
#include "utils/test_utils.hpp"
#include "utils/ros_test_msg.hpp"

using std::placeholders::_1;

Expand Down
Loading

0 comments on commit cf6a2d6

Please sign in to comment.