Skip to content

Commit d66cd96

Browse files
authored
Adding tests basic getters (#1291)
* Add tests serialize functions * Add test getter const get_service_handle * Add basic tests getters publisher * Add == operator tests * Improve check on QOS depth * Remove extra line, copy directly string * Expect specific error throws Signed-off-by: Jorge Perez <jjperez@ekumenlabs.com>
1 parent 3f0f2e2 commit d66cd96

4 files changed

Lines changed: 188 additions & 0 deletions

File tree

rclcpp/test/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -373,6 +373,7 @@ if(TARGET test_service)
373373
"rmw"
374374
"rosidl_runtime_cpp"
375375
"rosidl_typesupport_cpp"
376+
"test_msgs"
376377
)
377378
target_link_libraries(test_service ${PROJECT_NAME})
378379
endif()

rclcpp/test/rclcpp/test_publisher.cpp

Lines changed: 56 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -203,3 +203,59 @@ TEST_F(TestPublisherSub, construction_and_destruction) {
203203
}, rclcpp::exceptions::InvalidTopicNameError);
204204
}
205205
}
206+
207+
// Auxiliary class used to test getter for const PublisherBase
208+
const rosidl_message_type_support_t EmptyTypeSupport()
209+
{
210+
return *rosidl_typesupport_cpp::get_message_type_support_handle<test_msgs::msg::Empty>();
211+
}
212+
213+
const rcl_publisher_options_t PublisherOptions()
214+
{
215+
return rclcpp::PublisherOptionsWithAllocator<std::allocator<void>>().template
216+
to_rcl_publisher_options<test_msgs::msg::Empty>(rclcpp::QoS(10));
217+
}
218+
219+
class TestPublisherBase : public rclcpp::PublisherBase
220+
{
221+
public:
222+
explicit TestPublisherBase(rclcpp::Node * node)
223+
: rclcpp::PublisherBase(
224+
node->get_node_base_interface().get(), "topic", EmptyTypeSupport(), PublisherOptions()) {}
225+
};
226+
227+
/*
228+
Testing some publisher getters
229+
*/
230+
TEST_F(TestPublisher, basic_getters) {
231+
initialize();
232+
using test_msgs::msg::Empty;
233+
{
234+
using rclcpp::QoS;
235+
using rclcpp::KeepLast;
236+
const size_t qos_depth_size = 10u;
237+
auto publisher = node->create_publisher<Empty>("topic", QoS(KeepLast(qos_depth_size)));
238+
239+
size_t publisher_queue_size = publisher->get_queue_size();
240+
EXPECT_EQ(qos_depth_size, publisher_queue_size);
241+
242+
const rmw_gid_t & publisher_rmw_gid = publisher->get_gid();
243+
EXPECT_NE(nullptr, publisher_rmw_gid.implementation_identifier);
244+
245+
std::shared_ptr<rcl_publisher_t> publisher_handle = publisher->get_publisher_handle();
246+
EXPECT_NE(nullptr, publisher_handle);
247+
248+
EXPECT_TRUE(publisher->assert_liveliness());
249+
}
250+
{
251+
const TestPublisherBase publisher = TestPublisherBase(node.get());
252+
std::shared_ptr<const rcl_publisher_t> publisher_handle = publisher.get_publisher_handle();
253+
EXPECT_NE(nullptr, publisher_handle);
254+
255+
const rmw_gid_t & publisher_rmw_gid = publisher.get_gid();
256+
EXPECT_NE(nullptr, publisher_rmw_gid.implementation_identifier);
257+
258+
// Test == operator of publisher with rmw_gid_t
259+
EXPECT_EQ(publisher, publisher_rmw_gid);
260+
}
261+
}

rclcpp/test/rclcpp/test_serialized_message.cpp

Lines changed: 93 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -140,6 +140,20 @@ TEST(TestSerializedMessage, release) {
140140
EXPECT_EQ(RCL_RET_OK, rmw_serialized_message_fini(&released_handle));
141141
}
142142

143+
TEST(TestSerializedMessage, reserve) {
144+
rclcpp::SerializedMessage serialized_msg(13);
145+
EXPECT_EQ(13u, serialized_msg.capacity());
146+
147+
// Resize using reserve method
148+
serialized_msg.reserve(15);
149+
EXPECT_EQ(15u, serialized_msg.capacity());
150+
151+
// Use invalid value throws exception
152+
EXPECT_THROW(
153+
{serialized_msg.reserve(-1);},
154+
rclcpp::exceptions::RCLBadAlloc);
155+
}
156+
143157
TEST(TestSerializedMessage, serialization) {
144158
using MessageT = test_msgs::msg::BasicTypes;
145159

@@ -159,6 +173,85 @@ TEST(TestSerializedMessage, serialization) {
159173
}
160174
}
161175

176+
TEST(TestSerializedMessage, assignment_operators) {
177+
const std::string content = "Hello World";
178+
const auto content_size = content.size() + 1; // accounting for null terminator
179+
auto default_allocator = rcl_get_default_allocator();
180+
auto rcl_serialized_msg = rmw_get_zero_initialized_serialized_message();
181+
auto ret = rmw_serialized_message_init(&rcl_serialized_msg, 13, &default_allocator);
182+
ASSERT_EQ(RCL_RET_OK, ret);
183+
184+
// manually copy some content
185+
std::memcpy(rcl_serialized_msg.buffer, content.c_str(), content_size);
186+
rcl_serialized_msg.buffer_length = content_size;
187+
EXPECT_EQ(13u, rcl_serialized_msg.buffer_capacity);
188+
rclcpp::SerializedMessage serialized_message_to_assign(rcl_serialized_msg);
189+
EXPECT_EQ(13u, serialized_message_to_assign.capacity());
190+
EXPECT_EQ(content_size, serialized_message_to_assign.size());
191+
192+
// Test copy assignment with = operator, on another rclcpp::SerializedMessage
193+
rclcpp::SerializedMessage serialized_msg_copy(2);
194+
EXPECT_EQ(2u, serialized_msg_copy.capacity());
195+
EXPECT_EQ(0u, serialized_msg_copy.size());
196+
serialized_msg_copy = serialized_message_to_assign;
197+
EXPECT_EQ(13u, serialized_msg_copy.capacity());
198+
EXPECT_EQ(content_size, serialized_msg_copy.size());
199+
200+
// Test copy assignment with = operator, with a rcl_serialized_message_t
201+
rclcpp::SerializedMessage serialized_msg_copy_rcl(2);
202+
EXPECT_EQ(2u, serialized_msg_copy_rcl.capacity());
203+
EXPECT_EQ(0u, serialized_msg_copy_rcl.size());
204+
serialized_msg_copy_rcl = rcl_serialized_msg;
205+
EXPECT_EQ(13u, serialized_msg_copy_rcl.capacity());
206+
EXPECT_EQ(content_size, serialized_msg_copy_rcl.size());
207+
208+
// Test move assignment with = operator
209+
rclcpp::SerializedMessage serialized_msg_move(2);
210+
EXPECT_EQ(2u, serialized_msg_move.capacity());
211+
EXPECT_EQ(0u, serialized_msg_move.size());
212+
serialized_msg_move = std::move(serialized_message_to_assign);
213+
EXPECT_EQ(13u, serialized_msg_move.capacity());
214+
EXPECT_EQ(content_size, serialized_msg_move.size());
215+
EXPECT_EQ(0u, serialized_message_to_assign.capacity());
216+
EXPECT_EQ(0u, serialized_message_to_assign.size());
217+
218+
// Test move assignment with = operator, with a rcl_serialized_message_t
219+
rclcpp::SerializedMessage serialized_msg_move_rcl(2);
220+
EXPECT_EQ(2u, serialized_msg_move_rcl.capacity());
221+
EXPECT_EQ(0u, serialized_msg_move_rcl.size());
222+
serialized_msg_move_rcl = std::move(rcl_serialized_msg);
223+
EXPECT_EQ(13u, serialized_msg_move_rcl.capacity());
224+
EXPECT_EQ(content_size, serialized_msg_move_rcl.size());
225+
EXPECT_EQ(0u, rcl_serialized_msg.buffer_capacity);
226+
227+
// Error because it was moved
228+
EXPECT_EQ(RCUTILS_RET_INVALID_ARGUMENT, rmw_serialized_message_fini(&rcl_serialized_msg));
229+
}
230+
231+
TEST(TestSerializedMessage, failed_init_throws) {
232+
rclcpp::SerializedMessage serialized_msg(13);
233+
EXPECT_EQ(13u, serialized_msg.capacity());
234+
235+
// Constructor with invalid size throws exception
236+
EXPECT_THROW(
237+
{rclcpp::SerializedMessage serialized_msg_fail(-1);},
238+
rclcpp::exceptions::RCLBadAlloc);
239+
240+
// Constructor copy with rmw_serialized bad msg throws
241+
auto default_allocator = rcl_get_default_allocator();
242+
auto rcl_serialized_msg = rmw_get_zero_initialized_serialized_message();
243+
auto ret = rmw_serialized_message_init(&rcl_serialized_msg, 13, &default_allocator);
244+
ASSERT_EQ(RCL_RET_OK, ret);
245+
EXPECT_EQ(13u, rcl_serialized_msg.buffer_capacity);
246+
rcl_serialized_msg.buffer_capacity = -1;
247+
EXPECT_THROW(
248+
{rclcpp::SerializedMessage serialized_msg_fail_2(rcl_serialized_msg);},
249+
rclcpp::exceptions::RCLBadAlloc);
250+
251+
rcl_serialized_msg.buffer_capacity = 13;
252+
EXPECT_EQ(RCL_RET_OK, rmw_serialized_message_fini(&rcl_serialized_msg));
253+
}
254+
162255
void serialize_default_ros_msg()
163256
{
164257
using MessageT = test_msgs::msg::BasicTypes;

rclcpp/test/rclcpp/test_service.cpp

Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,8 @@
2121
#include "rclcpp/rclcpp.hpp"
2222

2323
#include "rcl_interfaces/srv/list_parameters.hpp"
24+
#include "test_msgs/srv/empty.hpp"
25+
#include "test_msgs/srv/empty.h"
2426

2527
class TestService : public ::testing::Test
2628
{
@@ -105,3 +107,39 @@ TEST_F(TestServiceSub, construction_and_destruction) {
105107
}, rclcpp::exceptions::InvalidServiceNameError);
106108
}
107109
}
110+
111+
/* Testing basic getters */
112+
TEST_F(TestService, basic_public_getters) {
113+
using rcl_interfaces::srv::ListParameters;
114+
auto callback =
115+
[](const ListParameters::Request::SharedPtr, ListParameters::Response::SharedPtr) {
116+
};
117+
auto service = node->create_service<ListParameters>("service", callback);
118+
EXPECT_STREQ(service->get_service_name(), "/ns/service");
119+
std::shared_ptr<rcl_service_t> service_handle = service->get_service_handle();
120+
EXPECT_NE(nullptr, service_handle);
121+
122+
{
123+
// Create a extern defined const service
124+
auto node_handle_int = rclcpp::Node::make_shared("base_node");
125+
rcl_service_t service_handle = rcl_get_zero_initialized_service();
126+
rcl_service_options_t service_options = rcl_service_get_default_options();
127+
const rosidl_service_type_support_t * ts =
128+
rosidl_typesupport_cpp::get_service_type_support_handle<test_msgs::srv::Empty>();
129+
rcl_ret_t ret = rcl_service_init(
130+
&service_handle,
131+
node_handle_int->get_node_base_interface()->get_rcl_node_handle(),
132+
ts, "base_node_service", &service_options);
133+
if (ret != RCL_RET_OK) {
134+
FAIL();
135+
return;
136+
}
137+
rclcpp::AnyServiceCallback<test_msgs::srv::Empty> cb;
138+
const rclcpp::Service<test_msgs::srv::Empty> base(
139+
node_handle_int->get_node_base_interface()->get_shared_rcl_node_handle(),
140+
&service_handle, cb);
141+
// Use get_service_handle specific to const service
142+
std::shared_ptr<const rcl_service_t> const_service_handle = base.get_service_handle();
143+
EXPECT_NE(nullptr, const_service_handle);
144+
}
145+
}

0 commit comments

Comments
 (0)