Skip to content

Commit

Permalink
Removed hector_ros2_utils test dependency.
Browse files Browse the repository at this point in the history
  • Loading branch information
StefanFabian committed May 20, 2022
1 parent ce8647a commit b18a445
Show file tree
Hide file tree
Showing 3 changed files with 30 additions and 24 deletions.
7 changes: 3 additions & 4 deletions ros2_babel_fish/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,6 @@ if (BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(example_interfaces REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(hector_ros2_utils REQUIRED)
include_directories(include)

ament_add_gtest(test_message test/message.cpp)
Expand All @@ -161,15 +160,15 @@ if (BUILD_TESTING)
target_link_libraries(test_message_decoding ${PROJECT_NAME})

ament_add_gtest(test_message_encoding test/message_encoding.cpp)
ament_target_dependencies(test_message_encoding geometry_msgs hector_ros2_utils ros2_babel_fish_test_msgs)
ament_target_dependencies(test_message_encoding geometry_msgs ros2_babel_fish_test_msgs)
target_link_libraries(test_message_encoding ${PROJECT_NAME})

ament_add_gtest(test_service_client test/service_client.cpp)
ament_target_dependencies(test_service_client example_interfaces hector_ros2_utils ros2_babel_fish_test_msgs)
ament_target_dependencies(test_service_client example_interfaces ros2_babel_fish_test_msgs)
target_link_libraries(test_service_client ${PROJECT_NAME})

ament_add_gtest(test_action_client test/action_client.cpp)
ament_target_dependencies(test_action_client example_interfaces hector_ros2_utils ros2_babel_fish_test_msgs)
ament_target_dependencies(test_action_client example_interfaces ros2_babel_fish_test_msgs)
target_link_libraries(test_action_client ${PROJECT_NAME})
endif ()

Expand Down
1 change: 0 additions & 1 deletion ros2_babel_fish/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
<depend>rcpputils</depend>
<test_depend>example_interfaces</test_depend>
<test_depend>geometry_msgs</test_depend>
<test_depend>hector_ros2_utils</test_depend>
<test_depend>ros2_babel_fish_test_msgs</test_depend>
<test_depend>std_msgs</test_depend>

Expand Down
46 changes: 27 additions & 19 deletions ros2_babel_fish/test/message_encoding.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
#include "message_comparison.hpp"

#include <ros2_babel_fish/babel_fish.hpp>
#include <hector_ros2_utils/communication/wait_for.hpp>

#include <gtest/gtest.h>
#include <rclcpp/rclcpp.hpp>
Expand All @@ -16,6 +15,20 @@ using namespace ros2_babel_fish;

std::shared_ptr<rclcpp::Node> node;

template<typename Message>
std::shared_ptr<Message> waitForMessage( const std::string &topic )
{
rclcpp::QoS qos = rclcpp::QoS( 1 ).transient_local();
auto sub = node->create_subscription<Message>( topic, qos, []( std::unique_ptr<Message> ) { } );
rclcpp::ThreadSafeWaitSet wait_set( std::vector<rclcpp::ThreadSafeWaitSet::SubscriptionEntry>{{ sub }} );
auto wait_result = wait_set.template wait();
if ( wait_result.kind() != rclcpp::WaitResultKind::Ready ) return nullptr;
std::shared_ptr<Message> result = std::make_shared<Message>();
rclcpp::MessageInfo info;
if ( !sub->take( *result, info )) return nullptr;
return result;
}

template<typename T, bool BOUNDED = false, bool FIXED_LENGTH = false>
typename std::enable_if<!std::is_same<T, bool>::value and !std::is_same<T, std::string>::value, void>::type
fillArray( ArrayMessage_<T, BOUNDED, FIXED_LENGTH> &msg, unsigned seed )
Expand Down Expand Up @@ -329,24 +342,20 @@ class MessageEncodingTest : public ::testing::Test

TEST_F( MessageEncodingTest, tests )
{
auto msg_header = hector::waitForMessage<std_msgs::msg::Header>( "/test_message_encoding/header", node,
hector::latched());
auto msg_header = waitForMessage<std_msgs::msg::Header>( "/test_message_encoding/header" );
EXPECT_TRUE( MESSAGE_CONTENT_EQUAL( *std_msgs_header, msg_header ));

auto msg_point = hector::waitForMessage<geometry_msgs::msg::Point>( "/test_message_encoding/point", node,
hector::latched());
auto msg_point = waitForMessage<geometry_msgs::msg::Point>( "/test_message_encoding/point" );
EXPECT_TRUE( MESSAGE_CONTENT_EQUAL( *geometry_msgs_point, msg_point ));

auto msg_quaternion = hector::waitForMessage<geometry_msgs::msg::Quaternion>( "/test_message_encoding/quaternion",
node, hector::latched());
auto msg_quaternion = waitForMessage<geometry_msgs::msg::Quaternion>( "/test_message_encoding/quaternion" );
EXPECT_TRUE( MESSAGE_CONTENT_EQUAL( *geometry_msgs_quaternion, msg_quaternion ));

auto msg_pose = hector::waitForMessage<geometry_msgs::msg::Pose>( "/test_message_encoding/pose", node,
hector::latched());
auto msg_pose = waitForMessage<geometry_msgs::msg::Pose>( "/test_message_encoding/pose" );
EXPECT_TRUE( MESSAGE_CONTENT_EQUAL( *geometry_msgs_pose, msg_pose ));

auto msg_pose_stamped = hector::waitForMessage<geometry_msgs::msg::PoseStamped>(
"/test_message_encoding/pose_stamped", node, hector::latched());
auto msg_pose_stamped = waitForMessage<geometry_msgs::msg::PoseStamped>(
"/test_message_encoding/pose_stamped" );
EXPECT_TRUE( MESSAGE_CONTENT_EQUAL( *geometry_msgs_pose_stamped, msg_pose_stamped ));
geometry_msgs::msg::PoseStamped pose_reference;
pose_reference.header.stamp = rclcpp::Time( 13.37 );
Expand All @@ -356,24 +365,23 @@ TEST_F( MessageEncodingTest, tests )
pose_reference.pose.position.z = 1.23;
pose_reference.pose.orientation.w = 1.23;

auto msg_test_message = hector::waitForMessage<ros2_babel_fish_test_msgs::msg::TestMessage>(
"/test_message_encoding/test_message", node, hector::latched());
auto msg_test_message = waitForMessage<ros2_babel_fish_test_msgs::msg::TestMessage>(
"/test_message_encoding/test_message" );
EXPECT_TRUE( MESSAGE_CONTENT_EQUAL( *test_msg, msg_test_message ));
}

TEST_F( MessageEncodingTest, arrayTests )
{
auto msg_header = hector::waitForMessage<std_msgs::msg::Header>( "/test_message_encoding/header", node,
hector::latched());
auto msg_header = waitForMessage<std_msgs::msg::Header>( "/test_message_encoding/header" );
EXPECT_TRUE( MESSAGE_CONTENT_EQUAL( *std_msgs_header, msg_header ));

auto msg_sub_test_array = hector::waitForMessage<ros2_babel_fish_test_msgs::msg::TestSubArray>(
"/test_message_encoding/sub_test_array", node, hector::latched());
auto msg_sub_test_array = waitForMessage<ros2_babel_fish_test_msgs::msg::TestSubArray>(
"/test_message_encoding/sub_test_array" );
EXPECT_TRUE(
MESSAGE_CONTENT_EQUAL((*test_array_msg)["subarrays"].as<CompoundArrayMessage>()[0], msg_sub_test_array ));

auto msg_test_array = hector::waitForMessage<ros2_babel_fish_test_msgs::msg::TestArray>(
"/test_message_encoding/test_array", node, hector::latched());
auto msg_test_array = waitForMessage<ros2_babel_fish_test_msgs::msg::TestArray>(
"/test_message_encoding/test_array" );
EXPECT_TRUE( MESSAGE_CONTENT_EQUAL( *test_array_msg, msg_test_array ));
}

Expand Down

0 comments on commit b18a445

Please sign in to comment.