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

rosbag2_cpp Writer zero copy msg #1491

Closed
HRXWEB opened this issue Nov 7, 2023 · 8 comments
Closed

rosbag2_cpp Writer zero copy msg #1491

HRXWEB opened this issue Nov 7, 2023 · 8 comments
Labels
enhancement New feature or request

Comments

@HRXWEB
Copy link

HRXWEB commented Nov 7, 2023

Description

Hello, I would like to inquire whether the Writer in rosbag2_cpp supports creating a bag by reading files and if it also supports the LoanedMessage type of msg. I am interested in using the LoanedMessage type for my specific use case. Could you please provide information on the current support for this feature?

Thanks in advance

@HRXWEB HRXWEB added the enhancement New feature or request label Nov 7, 2023
@fujitatomoya
Copy link
Contributor

(just a note) for subscription (in case of rosbag2, recorder), LoanedMessage interface does not exist, that said if RMW supports loaned feature on subscription, subscription will try to loan the memory from RMW implementation w/o any setting. (it is likely that Plain Old Data is required to message type.)

(to answer your question) with quick code scan, i do not think LoanedMessages is supported in rosbag2 either writer or play.

CC: @MichaelOrlov

btw, there has been discussion about LoanedMessages unsafety behavior, you might want to see ros2/rcl#1110 and related issues.

@MichaelOrlov
Copy link
Contributor

@HRXWEB It doesn't make sense to have writer API with LoanedMessages because we will have to make a copy of the message eventually before we will store it in the storage file or database anyway.

The main advantages of using LoanedMessages are avoiding extra copies and enabling zero-copy like messages transfer over the shared memory. In the case of the data recording, we are operating with the rosbag2_storage::SerializedBagMessage which is defined as

namespace rosbag2_storage
{
struct SerializedBagMessage
{
  std::shared_ptr<rcutils_uint8_array_t> serialized_data;
  rcutils_time_point_value_t time_stamp;
  std::string topic_name;
};

We are getting from subscription callback the std::shared_ptr<const rclcpp::SerializedMessage> message and using remapping of the pointers to the original data in the newly created SerializedBagMessage on the rosbag2_cpp layer.

void Writer::write(
std::shared_ptr<const rclcpp::SerializedMessage> message,
const std::string & topic_name,
const std::string & type_name,
const rclcpp::Time & time)
{
auto serialized_bag_message = std::make_shared<rosbag2_storage::SerializedBagMessage>();
serialized_bag_message->topic_name = topic_name;
serialized_bag_message->time_stamp = time.nanoseconds();
// point to actual data and keep reference to original message to avoid premature releasing
serialized_bag_message->serialized_data = std::shared_ptr<rcutils_uint8_array_t>(
new rcutils_uint8_array_t(message->get_rcl_serialized_message()),
[message](rcutils_uint8_array_t * data) {
(void)message;
if (data != nullptr) {
data->buffer = nullptr;
delete data;
}
});
return write(serialized_bag_message, topic_name, type_name, rmw_get_serialization_format());
}

i.e. there are no actual data copies from the subscription to the further layers of the rosbag2 down until we need to really story serialized data to the file of database on the concrete rosbag2_storage_plugin implementation.

As you can see the data path in the rosbag2 is already optimized in such a way that there wouldn't be any differences if it would be LoanedMessage or regular shared_pointer to the rclcpp::SerializedMessage from a generic subscription.

Moreover, since we are getting std::shared_ptr<const rclcpp::SerializedMessage> we are essentially owning the time of liveliness of this shared pointer and can aggregate multiple message pointers in the cache mechanism with several gigabytes in total if needed.
However, with loaned messages, this approach may not work well since the memory in loaned messages belongs to the RMW or even DDS layer and that memory should be released as soon as we leave the subscription callback scope.
If people don't mindfully about this here is the trouble begins...
It would be impossible to use a cache for loaned messages. Writing messages one by one to the disk sequentially and synchronously in the "context" (in the same thread) of the subscription's callback is very inefficient.
To overcome such limitations and inefficiency we have separation of the transport and the storage layer via lock-free cache of shared pointers and running those two layers in separate threads. i.e. Hiccups on the storage layer will not have impact on the transport layer and vice versa and we can dump messages to the disk in batches.
Hence we would anyway have to make a full copy of the loaned message data as soon as it leaves the subscription's callback scope.

As regards the rosbag2 player. We do support publishing with loaned messages if publishers support loaned messages
See

explicit PlayerPublisher(
std::shared_ptr<rclcpp::GenericPublisher> pub,
bool disable_loan_message)
: publisher_(std::move(pub))
{
using std::placeholders::_1;
if (disable_loan_message || !publisher_->can_loan_messages()) {
publish_func_ = std::bind(&rclcpp::GenericPublisher::publish, publisher_, _1);
} else {
publish_func_ = std::bind(&rclcpp::GenericPublisher::publish_as_loaned_msg, publisher_, _1);
}
}

for reference.
However, there are some caveats there as well. We have to deserialize the message if we need to publish it with a loaned message interface. Contrary to it. In the regular flow, we can transfer serialized message data from storage directly up to the transport layer without deserialization.
Using loaned messages during playback may be beneficial if playing back on the same ECU as other consuming nodes and when messages will be delivered over shared memory transport.
And if there is more than one consumer on the topic. i.e. we will deserialize the message once in the rosbag2 player and consumers will get pointers to this data over the shared memory transport.

cc: @fujitatomoya

@HRXWEB
Copy link
Author

HRXWEB commented Nov 10, 2023

Thank you very much for your professional response. I understood some parts of what you mentioned, but I still have some confusion regarding the question I previously raised. I would like to provide a more detailed description of my requirements:

I want to create a ROS2 bag by reading from files. I understand that during play bag, there will be a GenericPublisher to play the topic. According to the code snippet you provided in player.cpp, there is a can_loan_messages() check. So, when writing this bag, can I ensure that the topic can be consumed by subscribers on the same ECU in a zero-copy manner?

Thank you for your assistance.

@MichaelOrlov
Copy link
Contributor

Hi @HRXWEB I am not sure that I correctly understand your question

So, when writing this bag, can I ensure that the topic can be consumed by subscribers on the same ECU in a zero-copy manner?

The GenericPublisher::can_loan_messages() is independent from the way how you would store messages.
It could be rmw and transport layer (DDS) implementation details in what cases the can_loan_messages() return true.
And this specific is unrelated to the rosbag2.
Another words, if transport layer allows publishing with loaned messages the rosbag2 will use the loaned messages API during playback. And this is a runtime check. For instance for CycloneDDS and iceoryx one of the requirements is that special shared memory manager RouDi shall be up and running on the system.

@sgf201
Copy link

sgf201 commented Nov 25, 2023

image
It is an api in genericPublisher which is used in ros2bag player, I think it is possible to play a bag in loaned message way. and it is mean something .like,it is faster in loaned way to replay bag,the copy time saved is as much as normol publisher.And,player and subscriber must be in the same DCU unit

@fujitatomoya
Copy link
Contributor

according to the current code, rosbag2 player can support LoanedMessage. (i did not know this, sorry for the confusion.)

as @MichaelOrlov pointed out,

https://github.com/ros2/rosbag2/blob/rolling/rosbag2_transport/src/rosbag2_transport/player.cpp#L222-L226

this will try to use LoanedMessage interface. (disable_loan_message is false in default)

about zero copy support, it just depends on the RMW implementation. after borrowing memory from the middleware, it is up to the middleware feature to support zero copy data sharing or not. (e.g https://fast-dds.docs.eprosima.com/en/latest/fastdds/transport/datasharing.html)

after all, that is beneficial in performance to use LoanedMessage since it can have one less copy for each publish call if rmw implementation supports it. but i would like to remind that ros2/rcl#1110 again, user needs to understand the circumstances.

note: ros2/ros2_documentation#4002

@sgf201
Copy link

sgf201 commented Nov 28, 2023

according to the current code, rosbag2 player can support LoanedMessage. (i did not know this, sorry for the confusion.)

as @MichaelOrlov pointed out,

https://github.com/ros2/rosbag2/blob/rolling/rosbag2_transport/src/rosbag2_transport/player.cpp#L222-L226

this will try to use LoanedMessage interface. (disable_loan_message is false in default)

about zero copy support, it just depends on the RMW implementation. after borrowing memory from the middleware, it is up to the middleware feature to support zero copy data sharing or not. (e.g https://fast-dds.docs.eprosima.com/en/latest/fastdds/transport/datasharing.html)

after all, that is beneficial in performance to use LoanedMessage since it can have one less copy for each publish call if rmw implementation supports it. but i would like to remind that ros2/rcl#1110 again, user needs to understand the circumstances.

note: ros2/ros2_documentation#4002

thanks so much, I get the important info
By default, Loaned Messages will try to borrow the memory from underlying middleware if it supports Loaned Messages.
The ROS_DISABLE_LOANED_MESSAGES environment variable can be used to disable Loaned Messages, and fallback to normal publisher behavior, without any code changes or middleware configuration.
You can set the environment variable with the following command:

.. tabs::

.. group-tab:: Linux

  .. code-block:: console
    export ROS_DISABLE_LOANED_MESSAGES=1
  To maintain this setting between shell sessions, you can add the command to your shell startup script:

  .. code-block:: console
    echo "export ROS_DISABLE_LOANED_MESSAGES=1" >> ~/.bashrc

and, about the ROS_DISABLE_LOANED_MESSAGES, Is it right that when it set , if I use the borrow_loaned_message api to fill data and send msg is allowed,and zero copy is worked well ?

and, about the sharedprt thing, I used to think the loaned_msg will be keeped by subscriber until the sharedptr distoryed.obviorsly,I am wrong. I will learn it in the future, thanks again

@MichaelOrlov
Copy link
Contributor

  • Closing as the question has been answered and no code changes are needed.
    Feel free to reopen if something is unclear yet.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
enhancement New feature or request
Projects
None yet
Development

No branches or pull requests

4 participants