Skip to content

Commit

Permalink
Renaming struct members for consistency (ros2#64)
Browse files Browse the repository at this point in the history
* ros2GH-118 Rename rosbag2_storage::TopicMetadata to TopicInformation and rosbag2_storage::TopicwithType to TopicMetadata

- The former TopicWithTye struct will be enlarged to contain also the rmw serialization format relative to the topic. This is why the name 'TopicMetadata' is now better suited for it.

* ros2GH-17 Rename timestamp to time_stamp for consistency in types

* Fix renaming of TopicWithType to TopicMetadata

* formatting

* pass by const ref
  • Loading branch information
Martin-Idel-SI authored and Karsten1987 committed Nov 26, 2018
1 parent cb28689 commit 149e85b
Show file tree
Hide file tree
Showing 32 changed files with 85 additions and 75 deletions.
2 changes: 1 addition & 1 deletion rosbag2/include/rosbag2/converter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ class ROSBAG2_PUBLIC Converter
Converter(
const std::string & input_format,
const std::string & output_format,
const std::vector<TopicWithType> & topics_and_types,
const std::vector<TopicMetadata> & topics_and_types,
std::shared_ptr<SerializationFormatConverterFactoryInterface> converter_factory =
std::make_shared<SerializationFormatConverterFactory>());

Expand Down
2 changes: 1 addition & 1 deletion rosbag2/include/rosbag2/sequential_reader.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ class ROSBAG2_PUBLIC SequentialReader
* \return vector of topics with topic name and type as std::string
* \throws runtime_error if the Reader is not open.
*/
virtual std::vector<TopicWithType> get_all_topics_and_types();
virtual std::vector<TopicMetadata> get_all_topics_and_types();

private:
std::unique_ptr<rosbag2_storage::StorageFactoryInterface> storage_factory_;
Expand Down
2 changes: 1 addition & 1 deletion rosbag2/include/rosbag2/types.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@ namespace rosbag2
{
using BagMetadata = rosbag2_storage::BagMetadata;
using SerializedBagMessage = rosbag2_storage::SerializedBagMessage;
using TopicInformation = rosbag2_storage::TopicInformation;
using TopicMetadata = rosbag2_storage::TopicMetadata;
using TopicWithType = rosbag2_storage::TopicWithType;
} // namespace rosbag2

#endif // ROSBAG2__TYPES_HPP_
2 changes: 1 addition & 1 deletion rosbag2/include/rosbag2/types/ros2_message.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ typedef struct rosbag2_ros2_message_t
{
void * message;
const char * topic_name;
rcutils_time_point_value_t timestamp;
rcutils_time_point_value_t time_stamp;
rcutils_allocator_t allocator;
} rosbag2_ros2_message_t;

Expand Down
2 changes: 1 addition & 1 deletion rosbag2/include/rosbag2/writer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ class ROSBAG2_PUBLIC Writer
* \param topic_with_type name and type identifier of topic to be created
* \throws runtime_error if the Writer is not open.
*/
virtual void create_topic(const TopicWithType & topic_with_type);
virtual void create_topic(const TopicMetadata & topic_with_type);

/**
* Write a message to a bagfile. The topic needs to have been created before writing is possible.
Expand Down
2 changes: 1 addition & 1 deletion rosbag2/src/rosbag2/converter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ namespace rosbag2
Converter::Converter(
const std::string & input_format,
const std::string & output_format,
const std::vector<TopicWithType> & topics_and_types,
const std::vector<TopicMetadata> & topics_and_types,
std::shared_ptr<rosbag2::SerializationFormatConverterFactoryInterface> converter_factory)
: converter_factory_(converter_factory)
{
Expand Down
2 changes: 1 addition & 1 deletion rosbag2/src/rosbag2/sequential_reader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ std::shared_ptr<SerializedBagMessage> SequentialReader::read_next()
throw std::runtime_error("Bag is not open. Call open() before reading.");
}

std::vector<TopicWithType> SequentialReader::get_all_topics_and_types()
std::vector<TopicMetadata> SequentialReader::get_all_topics_and_types()
{
if (storage_) {
return storage_->get_all_topics_and_types();
Expand Down
2 changes: 1 addition & 1 deletion rosbag2/src/rosbag2/writer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ void Writer::open(const StorageOptions & options)
uri_ = options.uri;
}

void Writer::create_topic(const TopicWithType & topic_with_type)
void Writer::create_topic(const TopicMetadata & topic_with_type)
{
if (!storage_) {
throw std::runtime_error("Bag is not open. Call open() before writing.");
Expand Down
4 changes: 2 additions & 2 deletions rosbag2/test/rosbag2/mock_storage.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,11 +30,11 @@ class MockStorage : public rosbag2_storage::storage_interfaces::ReadWriteInterfa
{
public:
MOCK_METHOD2(open, void(const std::string &, rosbag2_storage::storage_interfaces::IOFlag));
MOCK_METHOD1(create_topic, void(const rosbag2_storage::TopicWithType &));
MOCK_METHOD1(create_topic, void(const rosbag2_storage::TopicMetadata &));
MOCK_METHOD0(has_next, bool());
MOCK_METHOD0(read_next, std::shared_ptr<rosbag2_storage::SerializedBagMessage>());
MOCK_METHOD1(write, void(std::shared_ptr<const rosbag2_storage::SerializedBagMessage>));
MOCK_METHOD0(get_all_topics_and_types, std::vector<rosbag2_storage::TopicWithType>());
MOCK_METHOD0(get_all_topics_and_types, std::vector<rosbag2_storage::TopicMetadata>());
MOCK_METHOD0(get_metadata, rosbag2_storage::BagMetadata());
};

Expand Down
4 changes: 2 additions & 2 deletions rosbag2/test/rosbag2/test_info.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,14 +76,14 @@ TEST_F(TemporaryDirectoryFixture, read_metadata_makes_appropriate_call_to_metada
EXPECT_THAT(read_metadata.topics_with_message_count,
SizeIs(2u));
auto actual_first_topic = read_metadata.topics_with_message_count[0];
rosbag2_storage::TopicMetadata expected_first_topic = {{"topic1", "type1"}, 100};
rosbag2_storage::TopicInformation expected_first_topic = {{"topic1", "type1"}, 100};
EXPECT_THAT(actual_first_topic.topic_with_type.name,
Eq(expected_first_topic.topic_with_type.name));
EXPECT_THAT(actual_first_topic.topic_with_type.type,
Eq(expected_first_topic.topic_with_type.type));
EXPECT_THAT(actual_first_topic.message_count, Eq(expected_first_topic.message_count));
auto actual_second_topic = read_metadata.topics_with_message_count[1];
rosbag2_storage::TopicMetadata expected_second_topic = {{"topic2", "type2"}, 200};
rosbag2_storage::TopicInformation expected_second_topic = {{"topic2", "type2"}, 200};
EXPECT_THAT(actual_second_topic.topic_with_type.name,
Eq(expected_second_topic.topic_with_type.name));
EXPECT_THAT(actual_second_topic.topic_with_type.type,
Expand Down
4 changes: 2 additions & 2 deletions rosbag2/test/rosbag2/test_sequential_reader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,10 @@ class SequentialReaderTest : public Test
storage_ = std::make_shared<NiceMock<MockStorage>>();
converter_factory_ = std::make_shared<StrictMock<MockConverterFactory>>();

rosbag2_storage::TopicWithType topic_with_type;
rosbag2_storage::TopicMetadata topic_with_type;
topic_with_type.name = "topic";
topic_with_type.type = "test_msgs/Primitives";
auto topics_and_types = std::vector<rosbag2_storage::TopicWithType>{topic_with_type};
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
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ void CdrConverter::deserialize(
std::shared_ptr<rosbag2_ros2_message_t> ros_message)
{
ros_message->topic_name = serialized_message->topic_name.c_str();
ros_message->timestamp = serialized_message->time_stamp;
ros_message->time_stamp = serialized_message->time_stamp;

printf("this should be a call to FASTRTPS\n");
auto ret =
Expand All @@ -115,7 +115,7 @@ void CdrConverter::serialize(
std::shared_ptr<rosbag2::SerializedBagMessage> serialized_message)
{
serialized_message->topic_name = std::string(ros_message->topic_name);
serialized_message->time_stamp = ros_message->timestamp;
serialized_message->time_stamp = ros_message->time_stamp;

auto ret = serialize_fcn_(
ros_message->message, type_support, serialized_message->serialized_data.get());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ class CdrConverterTestFixture : public Test
const std::string & topic_name = "")
{
auto ros_message = std::make_shared<rosbag2_ros2_message_t>();
ros_message->timestamp = 0;
ros_message->time_stamp = 0;
ros_message->message = nullptr;
ros_message->allocator = allocator_;

Expand Down Expand Up @@ -81,13 +81,13 @@ TEST_F(CdrConverterTestFixture, deserialize_converts_cdr_into_ros_message_for_pr

auto cast_message = static_cast<test_msgs::msg::Primitives *>(ros_message->message);
EXPECT_THAT(*cast_message, Eq(*message));
EXPECT_THAT(ros_message->timestamp, Eq(serialized_message->time_stamp));
EXPECT_THAT(ros_message->time_stamp, Eq(serialized_message->time_stamp));
EXPECT_THAT(ros_message->topic_name, StrEq(serialized_message->topic_name));
}

TEST_F(CdrConverterTestFixture, serialize_converts_ros_message_into_cdr_for_primitives) {
auto ros_message = make_shared_ros_message(topic_name_);
ros_message->timestamp = 1;
ros_message->time_stamp = 1;
auto message = get_messages_primitives()[0];
message->string_value = "test_serialize";
message->float64_value = 102.34;
Expand All @@ -104,7 +104,7 @@ TEST_F(CdrConverterTestFixture, serialize_converts_ros_message_into_cdr_for_prim
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->timestamp));
EXPECT_THAT(serialized_message->time_stamp, Eq(ros_message->time_stamp));
}

TEST_F(CdrConverterTestFixture, deserialize_converts_cdr_into_ros_message_for_static_array) {
Expand All @@ -128,13 +128,13 @@ TEST_F(CdrConverterTestFixture, deserialize_converts_cdr_into_ros_message_for_st

auto cast_message = static_cast<test_msgs::msg::StaticArrayPrimitives *>(ros_message->message);
EXPECT_THAT(*cast_message, Eq(*message));
EXPECT_THAT(ros_message->timestamp, Eq(serialized_message->time_stamp));
EXPECT_THAT(ros_message->time_stamp, Eq(serialized_message->time_stamp));
EXPECT_THAT(ros_message->topic_name, StrEq(serialized_message->topic_name));
}

TEST_F(CdrConverterTestFixture, serialize_converts_ros_message_into_cdr_for_static_array) {
auto ros_message = make_shared_ros_message(topic_name_);
ros_message->timestamp = 1;
ros_message->time_stamp = 1;
auto message = get_messages_static_array_primitives()[0];
message->string_values = {{"test_deserialize", "another string", "the third one"}};
message->float64_values = {{102.34, 1.9, 1236.011}};
Expand All @@ -152,7 +152,7 @@ TEST_F(CdrConverterTestFixture, serialize_converts_ros_message_into_cdr_for_stat
deserialize_message<test_msgs::msg::StaticArrayPrimitives>(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->timestamp));
EXPECT_THAT(serialized_message->time_stamp, Eq(ros_message->time_stamp));
}

TEST_F(CdrConverterTestFixture, deserialize_converts_cdr_into_ros_message_for_dynamic_array_nest) {
Expand Down Expand Up @@ -181,13 +181,13 @@ TEST_F(CdrConverterTestFixture, deserialize_converts_cdr_into_ros_message_for_dy

auto cast_message = static_cast<test_msgs::msg::DynamicArrayNested *>(ros_message->message);
EXPECT_THAT(*cast_message, Eq(*message));
EXPECT_THAT(ros_message->timestamp, Eq(serialized_message->time_stamp));
EXPECT_THAT(ros_message->time_stamp, Eq(serialized_message->time_stamp));
EXPECT_THAT(ros_message->topic_name, StrEq(serialized_message->topic_name));
}

TEST_F(CdrConverterTestFixture, serialize_converts_ros_message_into_cdr_for_dynamic_array_nest) {
auto ros_message = make_shared_ros_message(topic_name_);
ros_message->timestamp = 1;
ros_message->time_stamp = 1;
auto message = get_messages_dynamic_array_nested()[0];
test_msgs::msg::Primitives first_primitive_message;
first_primitive_message.string_value = "I am the first";
Expand All @@ -210,5 +210,5 @@ TEST_F(CdrConverterTestFixture, serialize_converts_ros_message_into_cdr_for_dyna
deserialize_message<test_msgs::msg::DynamicArrayNested>(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->timestamp));
EXPECT_THAT(serialized_message->time_stamp, Eq(ros_message->time_stamp));
}
6 changes: 3 additions & 3 deletions rosbag2_storage/include/rosbag2_storage/bag_metadata.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,9 +26,9 @@
namespace rosbag2_storage
{

struct TopicMetadata
struct TopicInformation
{
TopicWithType topic_with_type;
TopicMetadata topic_with_type;
size_t message_count;
};

Expand All @@ -42,7 +42,7 @@ struct BagMetadata
std::chrono::nanoseconds duration;
std::chrono::time_point<std::chrono::high_resolution_clock> starting_time;
size_t message_count;
std::vector<TopicMetadata> topics_with_message_count;
std::vector<TopicInformation> topics_with_message_count;
};

} // namespace rosbag2_storage
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ class ROSBAG2_STORAGE_PUBLIC BaseReadInterface

virtual std::shared_ptr<SerializedBagMessage> read_next() = 0;

virtual std::vector<TopicWithType> get_all_topics_and_types() = 0;
virtual std::vector<TopicMetadata> get_all_topics_and_types() = 0;
};

} // namespace storage_interfaces
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class ROSBAG2_STORAGE_PUBLIC BaseWriteInterface

virtual void write(std::shared_ptr<const SerializedBagMessage> msg) = 0;

virtual void create_topic(const TopicWithType & topic) = 0;
virtual void create_topic(const TopicMetadata & topic) = 0;
};

} // namespace storage_interfaces
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
namespace rosbag2_storage
{

struct TopicWithType
struct TopicMetadata
{
std::string name;
std::string type;
Expand Down
16 changes: 8 additions & 8 deletions rosbag2_storage/src/rosbag2_storage/metadata_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,17 +36,17 @@
namespace YAML
{
template<>
struct convert<rosbag2_storage::TopicWithType>
struct convert<rosbag2_storage::TopicMetadata>
{
static Node encode(const rosbag2_storage::TopicWithType & topic)
static Node encode(const rosbag2_storage::TopicMetadata & topic)
{
Node node;
node["name"] = topic.name;
node["type"] = topic.type;
return node;
}

static bool decode(const Node & node, rosbag2_storage::TopicWithType & topic)
static bool decode(const Node & node, rosbag2_storage::TopicMetadata & topic)
{
topic.name = node["name"].as<std::string>();
topic.type = node["type"].as<std::string>();
Expand All @@ -55,19 +55,19 @@ struct convert<rosbag2_storage::TopicWithType>
};

template<>
struct convert<rosbag2_storage::TopicMetadata>
struct convert<rosbag2_storage::TopicInformation>
{
static Node encode(const rosbag2_storage::TopicMetadata & metadata)
static Node encode(const rosbag2_storage::TopicInformation & metadata)
{
Node node;
node["topic_and_type"] = metadata.topic_with_type;
node["message_count"] = metadata.message_count;
return node;
}

static bool decode(const Node & node, rosbag2_storage::TopicMetadata & metadata)
static bool decode(const Node & node, rosbag2_storage::TopicInformation & metadata)
{
metadata.topic_with_type = node["topic_and_type"].as<rosbag2_storage::TopicWithType>();
metadata.topic_with_type = node["topic_and_type"].as<rosbag2_storage::TopicMetadata>();
metadata.message_count = node["message_count"].as<size_t>();
return true;
}
Expand Down Expand Up @@ -137,7 +137,7 @@ struct convert<rosbag2_storage::BagMetadata>
.as<std::chrono::time_point<std::chrono::high_resolution_clock>>();
metadata.message_count = node["message_count"].as<size_t>();
metadata.topics_with_message_count =
node["topics_with_message_count"].as<std::vector<rosbag2_storage::TopicMetadata>>();
node["topics_with_message_count"].as<std::vector<rosbag2_storage::TopicInformation>>();
return true;
}
};
Expand Down
6 changes: 3 additions & 3 deletions rosbag2_storage/test/rosbag2_storage/test_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ std::shared_ptr<rosbag2_storage::SerializedBagMessage> TestPlugin::read_next()
return std::shared_ptr<rosbag2_storage::SerializedBagMessage>();
}

void TestPlugin::create_topic(const rosbag2_storage::TopicWithType & topic)
void TestPlugin::create_topic(const rosbag2_storage::TopicMetadata & topic)
{
std::cout << "Created topic with name =" << topic.name << " and type =" << topic.type << ".\n";
}
Expand All @@ -63,10 +63,10 @@ void TestPlugin::write(const std::shared_ptr<const rosbag2_storage::SerializedBa
std::cout << "\nwriting\n";
}

std::vector<rosbag2_storage::TopicWithType> TestPlugin::get_all_topics_and_types()
std::vector<rosbag2_storage::TopicMetadata> TestPlugin::get_all_topics_and_types()
{
std::cout << "\nreading topics and types\n";
return std::vector<rosbag2_storage::TopicWithType>();
return std::vector<rosbag2_storage::TopicMetadata>();
}

rosbag2_storage::BagMetadata TestPlugin::get_metadata()
Expand Down
4 changes: 2 additions & 2 deletions rosbag2_storage/test/rosbag2_storage/test_plugin.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,15 +32,15 @@ class TestPlugin : public rosbag2_storage::storage_interfaces::ReadWriteInterfac

void open(const std::string & uri, rosbag2_storage::storage_interfaces::IOFlag flag) override;

void create_topic(const rosbag2_storage::TopicWithType & topic) override;
void create_topic(const rosbag2_storage::TopicMetadata & topic) override;

bool has_next() override;

std::shared_ptr<rosbag2_storage::SerializedBagMessage> read_next() override;

void write(std::shared_ptr<const rosbag2_storage::SerializedBagMessage> msg) override;

std::vector<rosbag2_storage::TopicWithType> get_all_topics_and_types() override;
std::vector<rosbag2_storage::TopicMetadata> get_all_topics_and_types() override;

rosbag2_storage::BagMetadata get_metadata() override;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,10 +49,10 @@ std::shared_ptr<rosbag2_storage::SerializedBagMessage> TestReadOnlyPlugin::read_
return std::shared_ptr<rosbag2_storage::SerializedBagMessage>();
}

std::vector<rosbag2_storage::TopicWithType> TestReadOnlyPlugin::get_all_topics_and_types()
std::vector<rosbag2_storage::TopicMetadata> TestReadOnlyPlugin::get_all_topics_and_types()
{
std::cout << "\nreading topics and types\n";
return std::vector<rosbag2_storage::TopicWithType>();
return std::vector<rosbag2_storage::TopicMetadata>();
}

rosbag2_storage::BagMetadata TestReadOnlyPlugin::get_metadata()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ class TestReadOnlyPlugin : public rosbag2_storage::storage_interfaces::ReadOnlyI

std::shared_ptr<rosbag2_storage::SerializedBagMessage> read_next() override;

std::vector<rosbag2_storage::TopicWithType> get_all_topics_and_types() override;
std::vector<rosbag2_storage::TopicMetadata> get_all_topics_and_types() override;

rosbag2_storage::BagMetadata get_metadata() override;
};
Expand Down
Loading

0 comments on commit 149e85b

Please sign in to comment.