Skip to content

Commit

Permalink
added intra process buffer test
Browse files Browse the repository at this point in the history
Signed-off-by: alberto <alberto.soragna@gmail.com>

Signed-off-by: alberto <alberto.soragna@gmail.com>
  • Loading branch information
alsora committed Jul 4, 2019
1 parent 7e5f55b commit c0d00c1
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 14 deletions.
3 changes: 1 addition & 2 deletions rclcpp/include/rclcpp/buffers/ring_buffer_implementation.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,8 +62,7 @@ class RingBufferImplementation : public BufferImplementationBase<BufferT>

if (is_full()) {
read_ = next(read_);
}
else {
} else {
_length++;
}

Expand Down
14 changes: 7 additions & 7 deletions rclcpp/include/rclcpp/subscription_intra_process.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,12 +88,12 @@ class SubscriptionIntraProcess : public SubscriptionIntraProcessBase
using ConstMessageSharedPtr = std::shared_ptr<const MessageT>;
using MessageUniquePtr = std::unique_ptr<MessageT, MessageDeleter>;

using BufferPtr = typename intra_process_buffer::IntraProcessBuffer<MessageT>::SharedPtr;
using SubscriptionPtr = typename Subscription<MessageT, Alloc>::SharedPtr;
using BufferSharedPtr = typename intra_process_buffer::IntraProcessBuffer<MessageT>::SharedPtr;
using SubscriptionSharedPtr = typename Subscription<MessageT, Alloc>::SharedPtr;

SubscriptionIntraProcess(
SubscriptionPtr subscription,
BufferPtr buffer)
SubscriptionSharedPtr subscription,
BufferSharedPtr buffer)
: subscription_(subscription), buffer_(buffer)
{
std::shared_ptr<rclcpp::Context> context_ptr =
Expand All @@ -107,7 +107,7 @@ class SubscriptionIntraProcess : public SubscriptionIntraProcessBase
&gc_, context_ptr->get_rcl_context().get(), guard_condition_options);

if (RCL_RET_OK != ret) {
throw std::runtime_error("IntraProcessWaitable init error initializing guard condition");
throw std::runtime_error("SubscriptionIntraProcess init error initializing guard condition");
}
}

Expand Down Expand Up @@ -183,8 +183,8 @@ class SubscriptionIntraProcess : public SubscriptionIntraProcessBase
std::recursive_mutex reentrant_mutex_;
rcl_guard_condition_t gc_;

SubscriptionPtr subscription_;
BufferPtr buffer_;
SubscriptionSharedPtr subscription_;
BufferSharedPtr buffer_;
};

} // namespace rclcpp
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/test/test_intra_process_buffer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -233,4 +233,4 @@ TEST(TestIntraProcessBuffer, unique_buffer_consume) {

EXPECT_EQ(original_value, *popped_unique_msg);
EXPECT_EQ(original_message_pointer, popped_message_pointer);
}
}
6 changes: 2 additions & 4 deletions rclcpp/test/test_ring_buffer_implementation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,9 @@
Construtctor
*/
TEST(TestRingBufferImplementation, constructor) {

// Cannot create a buffer of size zero.
EXPECT_THROW(rclcpp::intra_process_buffer::RingBufferImplementation<char> rb(0), std::invalid_argument);
EXPECT_THROW(
rclcpp::intra_process_buffer::RingBufferImplementation<char> rb(0), std::invalid_argument);

rclcpp::intra_process_buffer::RingBufferImplementation<char> rb(1);

Expand All @@ -42,10 +42,8 @@ TEST(TestRingBufferImplementation, constructor) {
- overwrite old data writing over the buffer capacity
*/
TEST(TestRingBufferImplementation, basic_usage) {

rclcpp::intra_process_buffer::RingBufferImplementation<char> rb(2);


rb.enqueue('a');

EXPECT_EQ(true, rb.has_data());
Expand Down

0 comments on commit c0d00c1

Please sign in to comment.