Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix compilation against master #111

Merged
merged 8 commits into from
May 7, 2019
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Prev Previous commit
Next Next commit
partial update
Signed-off-by: Dirk Thomas <dirk-thomas@users.noreply.github.com>
  • Loading branch information
dirk-thomas authored and Karsten1987 committed May 4, 2019
commit 5a387e3895ff512dc8f6108dd4cba0fcc9485656
2 changes: 1 addition & 1 deletion rosbag2/test/rosbag2/test_sequential_reader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ class SequentialReaderTest : public Test

rosbag2_storage::TopicMetadata topic_with_type;
topic_with_type.name = "topic";
topic_with_type.type = "test_msgs/Primitives";
topic_with_type.type = "test_msgs/BasicTypes";
auto topics_and_types = std::vector<rosbag2_storage::TopicMetadata>{topic_with_type};
EXPECT_CALL(*storage_, get_all_topics_and_types())
.Times(AtMost(1)).WillRepeatedly(Return(topics_and_types));
Expand Down
2 changes: 1 addition & 1 deletion rosbag2/test/rosbag2/test_typesupport_helpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ TEST(TypesupportHelpersTest, throws_exception_if_library_cannot_be_found) {

TEST(TypesupportHelpersTest, returns_c_type_info_for_valid_library) {
auto string_typesupport =
rosbag2::get_typesupport("test_msgs/Primitives", "rosidl_typesupport_cpp");
rosbag2::get_typesupport("test_msgs/BasicTypes", "rosidl_typesupport_cpp");

EXPECT_THAT(std::string(string_typesupport->typesupport_identifier),
ContainsRegex("rosidl_typesupport"));
Expand Down
4 changes: 2 additions & 2 deletions rosbag2/test/rosbag2/test_writer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ TEST_F(WriterTest,
auto message = std::make_shared<rosbag2::SerializedBagMessage>();
message->topic_name = "test_topic";
writer_->open(storage_options_, {input_format, storage_serialization_format});
writer_->create_topic({"test_topic", "test_msgs/Primitives", ""});
writer_->create_topic({"test_topic", "test_msgs/BasicTypes", ""});
writer_->write(message);
}

Expand All @@ -91,7 +91,7 @@ TEST_F(WriterTest, write_does_not_use_converters_if_input_and_output_format_are_
auto message = std::make_shared<rosbag2::SerializedBagMessage>();
message->topic_name = "test_topic";
writer_->open(storage_options_, {storage_serialization_format, storage_serialization_format});
writer_->create_topic({"test_topic", "test_msgs/Primitives", ""});
writer_->create_topic({"test_topic", "test_msgs/BasicTypes", ""});
writer_->write(message);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ class CdrConverterTestFixture : public Test
};

TEST_F(CdrConverterTestFixture, deserialize_converts_cdr_into_ros_message_for_primitives) {
auto message = get_messages_primitives()[0];
auto message = get_messages_basic_types()[0];
message->string_value = "test_deserialize";
message->float64_value = 102.34;
message->int32_value = 10101010;
Expand All @@ -74,13 +74,13 @@ TEST_F(CdrConverterTestFixture, deserialize_converts_cdr_into_ros_message_for_pr
serialized_message->time_stamp = 1;

auto ros_message = make_shared_ros_message();
test_msgs::msg::Primitives primitive_test_msg;
test_msgs::msg::BasicTypes primitive_test_msg;
ros_message->message = &primitive_test_msg;
auto type_support = rosbag2::get_typesupport("test_msgs/Primitives", "rosidl_typesupport_cpp");
auto type_support = rosbag2::get_typesupport("test_msgs/BasicTypes", "rosidl_typesupport_cpp");

converter_->deserialize(serialized_message, type_support, ros_message);

auto cast_message = static_cast<test_msgs::msg::Primitives *>(ros_message->message);
auto cast_message = static_cast<test_msgs::msg::BasicTypes *>(ros_message->message);
EXPECT_THAT(*cast_message, Eq(*message));
EXPECT_THAT(ros_message->time_stamp, Eq(serialized_message->time_stamp));
EXPECT_THAT(ros_message->topic_name, StrEq(serialized_message->topic_name));
Expand All @@ -89,19 +89,19 @@ TEST_F(CdrConverterTestFixture, deserialize_converts_cdr_into_ros_message_for_pr
TEST_F(CdrConverterTestFixture, serialize_converts_ros_message_into_cdr_for_primitives) {
auto ros_message = make_shared_ros_message(topic_name_);
ros_message->time_stamp = 1;
auto message = get_messages_primitives()[0];
auto message = get_messages_basic_types()[0];
message->string_value = "test_serialize";
message->float64_value = 102.34;
message->int32_value = 10101010;
ros_message->message = message.get();

auto serialized_message = std::make_shared<rosbag2::SerializedBagMessage>();
serialized_message->serialized_data = memory_management_->make_initialized_message();
auto type_support = rosbag2::get_typesupport("test_msgs/Primitives", "rosidl_typesupport_cpp");
auto type_support = rosbag2::get_typesupport("test_msgs/BasicTypes", "rosidl_typesupport_cpp");

converter_->serialize(ros_message, type_support, serialized_message);

auto deserialized_msg = memory_management_->deserialize_message<test_msgs::msg::Primitives>(
auto deserialized_msg = memory_management_->deserialize_message<test_msgs::msg::BasicTypes>(
serialized_message->serialized_data);
EXPECT_THAT(*deserialized_msg, Eq(*message));
EXPECT_THAT(serialized_message->topic_name, StrEq(topic_name_));
Expand All @@ -120,14 +120,14 @@ TEST_F(CdrConverterTestFixture, deserialize_converts_cdr_into_ros_message_for_st
serialized_message->time_stamp = 1;

auto ros_message = make_shared_ros_message();
test_msgs::msg::StaticArrayPrimitives primitive_test_msg;
test_msgs::msg::Arrays primitive_test_msg;
ros_message->message = &primitive_test_msg;
auto type_support = rosbag2::get_typesupport(
"test_msgs/StaticArrayPrimitives", "rosidl_typesupport_cpp");
"test_msgs/Arrays", "rosidl_typesupport_cpp");

converter_->deserialize(serialized_message, type_support, ros_message);

auto cast_message = static_cast<test_msgs::msg::StaticArrayPrimitives *>(ros_message->message);
auto cast_message = static_cast<test_msgs::msg::Arrays *>(ros_message->message);
EXPECT_THAT(*cast_message, Eq(*message));
EXPECT_THAT(ros_message->time_stamp, Eq(serialized_message->time_stamp));
EXPECT_THAT(ros_message->topic_name, StrEq(serialized_message->topic_name));
Expand All @@ -145,23 +145,23 @@ TEST_F(CdrConverterTestFixture, serialize_converts_ros_message_into_cdr_for_stat
auto serialized_message = std::make_shared<rosbag2::SerializedBagMessage>();
serialized_message->serialized_data = memory_management_->make_initialized_message();
auto type_support = rosbag2::get_typesupport(
"test_msgs/StaticArrayPrimitives", "rosidl_typesupport_cpp");
"test_msgs/Arrays", "rosidl_typesupport_cpp");

converter_->serialize(ros_message, type_support, serialized_message);

auto deserialized_msg = memory_management_->
deserialize_message<test_msgs::msg::StaticArrayPrimitives>(serialized_message->serialized_data);
deserialize_message<test_msgs::msg::Arrays>(serialized_message->serialized_data);
EXPECT_THAT(*deserialized_msg, Eq(*message));
EXPECT_THAT(serialized_message->topic_name, StrEq(topic_name_));
EXPECT_THAT(serialized_message->time_stamp, Eq(ros_message->time_stamp));
}

TEST_F(CdrConverterTestFixture, deserialize_converts_cdr_into_ros_message_for_dynamic_array_nest) {
auto message = get_messages_dynamic_array_nested()[0];
test_msgs::msg::Primitives first_primitive_message;
test_msgs::msg::BasicTypes first_primitive_message;
first_primitive_message.string_value = "I am the first";
first_primitive_message.float32_value = 35.7f;
test_msgs::msg::Primitives second_primitive_message;
test_msgs::msg::BasicTypes second_primitive_message;
second_primitive_message.string_value = "I am the second";
second_primitive_message.float32_value = 135.72f;
message->primitive_values.push_back(first_primitive_message);
Expand Down Expand Up @@ -190,10 +190,10 @@ TEST_F(CdrConverterTestFixture, serialize_converts_ros_message_into_cdr_for_dyna
auto ros_message = make_shared_ros_message(topic_name_);
ros_message->time_stamp = 1;
auto message = get_messages_dynamic_array_nested()[0];
test_msgs::msg::Primitives first_primitive_message;
test_msgs::msg::BasicTypes first_primitive_message;
first_primitive_message.string_value = "I am the first";
first_primitive_message.float32_value = 35.7f;
test_msgs::msg::Primitives second_primitive_message;
test_msgs::msg::BasicTypes second_primitive_message;
second_primitive_message.string_value = "I am the second";
second_primitive_message.float32_value = 135.72f;
message->primitive_values.push_back(first_primitive_message);
Expand Down
4 changes: 2 additions & 2 deletions rosbag2_tests/resources/cdr_test/metadata.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -11,11 +11,11 @@ rosbag2_bagfile_information:
topics_with_message_count:
- topic_metadata:
name: /test_topic
type: test_msgs/Primitives
type: test_msgs/BasicTypes
serialization_format: cdr
message_count: 3
- topic_metadata:
name: /array_topic
type: test_msgs/StaticArrayPrimitives
type: test_msgs/Arrays
serialization_format: cdr
message_count: 4
4 changes: 2 additions & 2 deletions rosbag2_tests/resources/wrong_rmw_test/metadata.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -11,11 +11,11 @@ rosbag2_bagfile_information:
topics_with_message_count:
- topic_metadata:
name: /test_topic
type: test_msgs/Primitives
type: test_msgs/BasicTypes
serialization_format: wrong_format
message_count: 3
- topic_metadata:
name: /array_topic
type: test_msgs/StaticArrayPrimitives
type: test_msgs/Arrays
serialization_format: wrong_format
message_count: 4
4 changes: 2 additions & 2 deletions rosbag2_tests/test/rosbag2_tests/record_fixture.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@

#include "rclcpp/rclcpp.hpp"

#include "test_msgs/msg/primitives.hpp"
#include "test_msgs/msg/static_array_primitives.hpp"
#include "test_msgs/msg/arrays.hpp"
#include "test_msgs/msg/basic_types.hpp"
#include "test_msgs/message_fixtures.hpp"
#include "rosbag2_storage/filesystem_helper.hpp"
#include "rosbag2_storage_default_plugins/sqlite/sqlite_storage.hpp"
Expand Down
2 changes: 1 addition & 1 deletion rosbag2_tests/test/rosbag2_tests/test_converter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ class ConverterTestFixture : public Test
{
auto correctly_typed_ros_message =
reinterpret_cast<test_msgs::msg::DynamicArrayNested *>(message->message);
auto primitive_msgs = get_messages_primitives();
auto primitive_msgs = get_messages_basic_types();
for (const auto & primitive_msg : primitive_msgs) {
correctly_typed_ros_message->primitive_values.push_back(*primitive_msg);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,9 +50,9 @@ TEST_F(InfoEndToEndTestFixture, info_end_to_end_test) {
"\nMessages: 7"
"\nTopic information: "));
EXPECT_THAT(output, HasSubstr(
"Topic: /test_topic | Type: test_msgs/Primitives | Count: 3 | Serialization Format: cdr\n"));
"Topic: /test_topic | Type: test_msgs/BasicTypes | Count: 3 | Serialization Format: cdr\n"));
EXPECT_THAT(output, HasSubstr(
"Topic: /array_topic | Type: test_msgs/StaticArrayPrimitives | Count: 4 | "
"Topic: /array_topic | Type: test_msgs/Arrays | Count: 4 | "
"Serialization Format: cdr"));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,8 @@
#include "rclcpp/rclcpp.hpp"
#include "rosbag2_test_common/process_execution_helpers.hpp"

#include "test_msgs/msg/primitives.hpp"
#include "test_msgs/msg/static_array_primitives.hpp"
#include "test_msgs/msg/arrays.hpp"
#include "test_msgs/msg/basic_types.hpp"
#include "test_msgs/message_fixtures.hpp"
#include "rosbag2_storage_default_plugins/sqlite/sqlite_storage.hpp"
#include "rosbag2_test_common/subscription_manager.hpp"
Expand Down Expand Up @@ -58,31 +58,31 @@ class PlayEndToEndTestFixture : public Test
};

TEST_F(PlayEndToEndTestFixture, play_end_to_end_test) {
sub_->add_subscription<test_msgs::msg::StaticArrayPrimitives>("/array_topic", 2);
sub_->add_subscription<test_msgs::msg::Primitives>("/test_topic", 3);
sub_->add_subscription<test_msgs::msg::Arrays>("/array_topic", 2);
sub_->add_subscription<test_msgs::msg::BasicTypes>("/test_topic", 3);

auto subscription_future = sub_->spin_subscriptions();

auto exit_code = execute_and_wait_until_completion("ros2 bag play cdr_test", database_path_);

subscription_future.get();

auto primitive_messages = sub_->get_received_messages<test_msgs::msg::Primitives>("/test_topic");
auto array_messages = sub_->get_received_messages<test_msgs::msg::StaticArrayPrimitives>(
auto primitive_messages = sub_->get_received_messages<test_msgs::msg::BasicTypes>("/test_topic");
auto array_messages = sub_->get_received_messages<test_msgs::msg::Arrays>(
"/array_topic");

EXPECT_THAT(exit_code, Eq(EXIT_SUCCESS));

EXPECT_THAT(primitive_messages, SizeIs(Ge(3u)));
EXPECT_THAT(primitive_messages,
Each(Pointee(Field(&test_msgs::msg::Primitives::string_value, "test"))));
Each(Pointee(Field(&test_msgs::msg::BasicTypes::string_value, "test"))));

EXPECT_THAT(array_messages, SizeIs(Ge(2u)));
EXPECT_THAT(array_messages,
Each(Pointee(Field(&test_msgs::msg::StaticArrayPrimitives::bool_values,
Each(Pointee(Field(&test_msgs::msg::Arrays::bool_values,
ElementsAre(true, false, true)))));
EXPECT_THAT(array_messages,
Each(Pointee(Field(&test_msgs::msg::StaticArrayPrimitives::string_values,
Each(Pointee(Field(&test_msgs::msg::Arrays::string_values,
ElementsAre("Complex Hello1", "Complex Hello2", "Complex Hello3")))));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,11 +22,11 @@
#include "rosbag2_storage/metadata_io.hpp"

TEST_F(RecordFixture, record_end_to_end_test) {
auto message = get_messages_primitives()[0];
auto message = get_messages_basic_types()[0];
message->string_value = "test";
size_t expected_test_messages = 3;

auto wrong_message = get_messages_primitives()[0];
auto wrong_message = get_messages_basic_types()[0];
wrong_message->string_value = "wrong_content";

auto process_handle = start_execution("ros2 bag record --output " + bag_path_ + " /test_topic");
Expand Down Expand Up @@ -58,13 +58,13 @@ TEST_F(RecordFixture, record_end_to_end_test) {
metadata_io.write_metadata(bag_path_, metadata);
#endif

auto test_topic_messages = get_messages_for_topic<test_msgs::msg::Primitives>("/test_topic");
auto test_topic_messages = get_messages_for_topic<test_msgs::msg::BasicTypes>("/test_topic");
EXPECT_THAT(test_topic_messages, SizeIs(Ge(expected_test_messages)));
EXPECT_THAT(test_topic_messages,
Each(Pointee(Field(&test_msgs::msg::Primitives::string_value, "test"))));
Each(Pointee(Field(&test_msgs::msg::BasicTypes::string_value, "test"))));
EXPECT_THAT(get_rwm_format_for_topic("/test_topic", db), Eq(rmw_get_serialization_format()));

auto wrong_topic_messages = get_messages_for_topic<test_msgs::msg::Primitives>("/wrong_topic");
auto wrong_topic_messages = get_messages_for_topic<test_msgs::msg::BasicTypes>("/wrong_topic");
EXPECT_THAT(wrong_topic_messages, IsEmpty());
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ GenericPublisher::GenericPublisher(
void GenericPublisher::publish(std::shared_ptr<rmw_serialized_message_t> message)
{
auto return_code = rcl_publish_serialized_message(
get_publisher_handle(), message.get());
get_publisher_handle(), message.get(), NULL);

if (return_code != RCL_RET_OK) {
rclcpp::exceptions::throw_from_rcl_error(return_code, "failed to publish serialized message");
Expand Down
24 changes: 12 additions & 12 deletions rosbag2_transport/test/rosbag2_transport/test_play.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,8 @@

#include "rclcpp/rclcpp.hpp"
#include "rosbag2_transport/rosbag2_transport.hpp"
#include "test_msgs/msg/primitives.hpp"
#include "test_msgs/msg/static_array_primitives.hpp"
#include "test_msgs/msg/arrays.hpp"
#include "test_msgs/msg/basic_types.hpp"
#include "test_msgs/message_fixtures.hpp"

#include "rosbag2_transport_test_fixture.hpp"
Expand Down Expand Up @@ -54,16 +54,16 @@ class RosBag2PlayTestFixture : public Rosbag2TransportTestFixture

TEST_F(RosBag2PlayTestFixture, recorded_messages_are_played_for_all_topics)
{
auto primitive_message1 = get_messages_primitives()[0];
auto primitive_message1 = get_messages_basic_types()[0];
primitive_message1->string_value = "Hello World";

auto complex_message1 = get_messages_static_array_primitives()[0];
complex_message1->string_values = {{"Complex Hello1", "Complex Hello2", "Complex Hello3"}};
complex_message1->bool_values = {{true, false, true}};

auto topic_types = std::vector<rosbag2::TopicMetadata>{
{"topic1", "test_msgs/Primitives", ""},
{"topic2", "test_msgs/StaticArrayPrimitives", ""},
{"topic1", "test_msgs/BasicTypes", ""},
{"topic2", "test_msgs/Arrays", ""},
};

std::vector<std::shared_ptr<rosbag2::SerializedBagMessage>> messages =
Expand All @@ -78,8 +78,8 @@ TEST_F(RosBag2PlayTestFixture, recorded_messages_are_played_for_all_topics)

// Due to a problem related to the subscriber, we play many (3) messages but make the subscriber
// node spin only until 2 have arrived. Hence the 2 as `launch_subscriber()` argument.
sub_->add_subscription<test_msgs::msg::Primitives>("/topic1", 2);
sub_->add_subscription<test_msgs::msg::StaticArrayPrimitives>(
sub_->add_subscription<test_msgs::msg::BasicTypes>("/topic1", 2);
sub_->add_subscription<test_msgs::msg::Arrays>(
"/topic2", 2);

auto await_received_messages = sub_->spin_subscriptions();
Expand All @@ -89,19 +89,19 @@ TEST_F(RosBag2PlayTestFixture, recorded_messages_are_played_for_all_topics)

await_received_messages.get();

auto replayed_test_primitives = sub_->get_received_messages<test_msgs::msg::Primitives>(
auto replayed_test_primitives = sub_->get_received_messages<test_msgs::msg::BasicTypes>(
"/topic1");
EXPECT_THAT(replayed_test_primitives, SizeIs(Ge(2u)));
EXPECT_THAT(replayed_test_primitives,
Each(Pointee(Field(&test_msgs::msg::Primitives::string_value, "Hello World"))));
Each(Pointee(Field(&test_msgs::msg::BasicTypes::string_value, "Hello World"))));

auto replayed_test_arrays = sub_->get_received_messages<test_msgs::msg::StaticArrayPrimitives>(
auto replayed_test_arrays = sub_->get_received_messages<test_msgs::msg::Arrays>(
"/topic2");
EXPECT_THAT(replayed_test_arrays, SizeIs(Ge(2u)));
EXPECT_THAT(replayed_test_arrays,
Each(Pointee(Field(&test_msgs::msg::StaticArrayPrimitives::bool_values,
Each(Pointee(Field(&test_msgs::msg::Arrays::bool_values,
ElementsAre(true, false, true)))));
EXPECT_THAT(replayed_test_arrays,
Each(Pointee(Field(&test_msgs::msg::StaticArrayPrimitives::string_values,
Each(Pointee(Field(&test_msgs::msg::Arrays::string_values,
ElementsAre("Complex Hello1", "Complex Hello2", "Complex Hello3")))));
}
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include "rclcpp/rclcpp.hpp"
#include "rosbag2_transport/rosbag2_transport.hpp"
#include "rosbag2_transport_test_fixture.hpp"
#include "test_msgs/msg/primitives.hpp"
#include "test_msgs/msg/basic_types.hpp"
#include "test_msgs/message_fixtures.hpp"

using namespace ::testing; // NOLINT
Expand All @@ -31,15 +31,15 @@ using namespace rosbag2_transport; // NOLINT
TEST_F(Rosbag2TransportTestFixture, playing_respects_relative_timing_of_stored_messages)
{
rclcpp::init(0, nullptr);
auto primitive_message1 = get_messages_primitives()[0];
auto primitive_message1 = get_messages_basic_types()[0];
primitive_message1->string_value = "Hello World 1";

auto primitive_message2 = get_messages_primitives()[0];
auto primitive_message2 = get_messages_basic_types()[0];
primitive_message2->string_value = "Hello World 2";

auto message_time_difference = std::chrono::seconds(1);
auto topics_and_types =
std::vector<rosbag2::TopicMetadata>{{"topic1", "test_msgs/Primitives", ""}};
std::vector<rosbag2::TopicMetadata>{{"topic1", "test_msgs/BasicTypes", ""}};
std::vector<std::shared_ptr<rosbag2::SerializedBagMessage>> messages =
{serialize_test_message("topic1", 0, primitive_message1),
serialize_test_message("topic1", 0, primitive_message2)};
Expand Down
Loading