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

Use serialized message directly #24

Merged
merged 21 commits into from
Sep 3, 2018

Conversation

Martin-Idel-SI
Copy link
Contributor

@Martin-Idel-SI Martin-Idel-SI commented Aug 24, 2018

This PR makes rosbag subscribe and publish directly to the underlying middleware implementation.

It contains:

  • Use rosbag2_storage::SerializedBagMessage and publish/subscribe directly to rcutils_char_array_t
  • The SQLite3 storage plugin now has a rather generic interface to deal with serialized messages (this is also a preparation to deal with other topics than string topics)
  • Subscribing and Publishing to std_msgs/String topic of predefined name
  • Builds on all supported platforms

It does not contain:

  • Subscribing to an arbitrary topic (will be done in a follow-up PR)

Note that the rosbag2_write_integration_test still sometimes fails for an unknown reason (see #25).

storage->create_topic();

if (storage) {
auto node = std::make_shared<rclcpp::Node>("rosbag_node");
auto subscription = node->create_subscription<std_msgs::msg::String>(
topic_name,
[&storage, after_write_action](std::shared_ptr<rmw_serialized_message_t> msg) {
[&storage, after_write_action](std::shared_ptr<rcutils_char_array_t> msg) {
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think we should continue to subscribe to rmw_serialized_message rather than rcutils_char_array_t. The two type are currently typedef'd, but that might change in the future.

@Martin-Idel-SI
Copy link
Contributor Author

Done.

// without the sleep_for() many messages are lost.
std::this_thread::sleep_for(std::chrono::milliseconds(500));
publisher->publish(string_message);
publisher->publish(message->serialized_data.get());
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

you can publish shared_ptr<rmw_serialized_message_t> now.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I know. We are currently rewriting the test and this will be improved as part of that effort if that's okay with you.

@@ -45,6 +45,7 @@ class RosBag2IntegrationTestFixture : public Rosbag2TestFixture
auto node = std::make_shared<rclcpp::Node>("subscriber_node");
auto subscription = node->create_subscription<std_msgs::msg::String>("string_topic",
[this, &messages](const std_msgs::msg::String::ConstSharedPtr message) {
std::cout << "\ndata = " << message->data << "\n";
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

nit: we normally use printf to be threadsafe.

Copy link
Contributor

@anhosi anhosi Aug 30, 2018

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In tests we prefer cout for readability. But we will remove this line as it is a debugging left-over.

namespace rosbag2_storage
{

std::shared_ptr<rcutils_char_array_t>
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

shouldn't this be a SerializedBagMessage essentially?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes and no. In the end, we want a SerializedBagMessage, but since this function only really fills the rcutils_char_array_t part, I think it's cleaner to just provide this.

std::shared_ptr<rcutils_char_array_t>
make_serialized_message(const void * data, size_t size)
{
auto rcutils_allocator = new rcutils_allocator_t;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this allocator is leaked. Nobody is cleaning this up.
The destructor should call delete on the allocator (rcutils_char_array_fini doesn't do it).

Copy link
Contributor Author

@Martin-Idel-SI Martin-Idel-SI Aug 30, 2018

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We saw this, too. This is fixed in #27, to simplify rebasing I'd just leave it here.

@@ -32,7 +32,7 @@ class TestPlugin : public rosbag2_storage::storage_interfaces::ReadWriteInterfac

rosbag2_storage::BagInfo info() override;

bool has_next() const override;
bool has_next() override;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why can't this function be const?

@@ -30,7 +30,7 @@ class ROSBAG2_STORAGE_PUBLIC BaseReadInterface
public:
virtual ~BaseReadInterface() = default;

virtual bool has_next() const = 0;
virtual bool has_next() = 0;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why is this change necessary?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We need to actually change the internal state of the storage to correctly ask whether there is a next entry. In the followup PR, we'll do this the following way (here, it's done as simple as possible):

  • We have a read_statement_ member which needs to be initialized somewhere. This is either done in read_next() or in has_next() if it is not already initialized. This read statement then gets reused for every read to allow fast reading. If we don't do this, has_next() would fail if read_next() has never been called, which is awkward.
  • In order to allow the function to be const this would imply we'd have to make the read_statement (and by transitivity a lot of the other state of the storage) mutable, which is also not very nice. So we thought changing to non-const here is simpler.

If you think the const is worth it to signify that it shouldn't matter how often this function is called, all other function calls will result in the same results (i.e. the state as it is visible to users of this class is unchanged), we can change it back and make the necessary changes to mutable state.
If it's okay, I'd want to do this in a follow-up PR to avoid rebase hell for the other PRs because there are a lot of changes to the implementation in the other open PRs.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Regarding the constness: I agree that having const might improve the interface from a users point of view (for the sqlite implementation it probably would not be too hard to do so). However, this imposes a big limitation on the internal implementation of all future storage plugins (basically a lot of member need to be mutable).
One could also argue that the information whether more data is available might be expensive to obtain and thus should be considered an important part of the internal state.

Also if has_next() is const what about read_next? The arguments for/ against constness are pretty much the same.

To distinguish between read and write access we have the ReadOnlyInterface and ReadWriteInterface.

Martin-Idel-SI and others added 21 commits August 30, 2018 09:29
- Remove virtual on methods as this was added only for unit tests. We
  decided to use only integration tests for the sqlite plugins.
- Changes semantics of SqliteStatement: represents always a prepared
  statement if not null.
- Ensures that a SqliteStatementWrapper cannot be copied and does not
  publicly expose its sqlite_stmt as this would cause memory corruption.
- Uses a std::tuple for row data
- Exposes an iterator interface for the query result
This is not storage plugin specific but will be needed by most (if
not all) plugins.
@Martin-Idel-SI Martin-Idel-SI force-pushed the feature/use_rmw_directly branch from 98976b7 to 45f1508 Compare August 30, 2018 08:33
@Karsten1987 Karsten1987 merged commit 3f77b33 into ros2:master Sep 3, 2018
@Karsten1987
Copy link
Collaborator

sorry for being late on this. Hope the rebasing is not becoming too crazy :)

@Martin-Idel-SI Martin-Idel-SI deleted the feature/use_rmw_directly branch September 4, 2018 08:37
james-rms pushed a commit to james-rms/rosbag2 that referenced this pull request Nov 17, 2022
Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>
james-rms pushed a commit to james-rms/rosbag2 that referenced this pull request Nov 17, 2022
Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>
Signed-off-by: James Smith <james@foxglove.dev>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants