-
Notifications
You must be signed in to change notification settings - Fork 120
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
Avoid allocations #211
Avoid allocations #211
Changes from all commits
af48c30
91b0118
b570839
d4f1dd8
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -420,8 +420,11 @@ size_t next_field_align( | |
std::vector<T> & data = *reinterpret_cast<std::vector<T> *>(field); | ||
current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding); | ||
current_alignment += padding; | ||
current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, item_size); | ||
current_alignment += item_size * data.size(); | ||
auto num_elems = data.size(); | ||
if (num_elems > 0) { | ||
current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, item_size); | ||
current_alignment += item_size * data.size(); | ||
} | ||
} | ||
return current_alignment; | ||
} | ||
|
@@ -437,7 +440,7 @@ size_t next_field_align<std::string>( | |
if (!member->is_array_) { | ||
current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding); | ||
current_alignment += padding; | ||
auto str = *static_cast<std::string *>(field); | ||
auto & str = *static_cast<std::string *>(field); | ||
current_alignment += str.size() + 1; | ||
} else if (member->array_size_ && !member->is_upper_bound_) { | ||
auto str_arr = static_cast<std::string *>(field); | ||
|
@@ -935,7 +938,7 @@ size_t TypeSupport<MembersType>::getEstimatedSerializedSize( | |
size_t ret_val = 4; | ||
|
||
if (members_->member_count_ != 0) { | ||
ret_val += TypeSupport::getEstimatedSerializedSize(members_, ros_message, ret_val); | ||
ret_val += TypeSupport::getEstimatedSerializedSize(members_, ros_message, 0); | ||
} else { | ||
ret_val += 1; | ||
} | ||
|
@@ -994,13 +997,28 @@ bool TypeSupport<MembersType>::serialize( | |
assert(data); | ||
assert(payload); | ||
|
||
auto ser = static_cast<eprosima::fastcdr::Cdr *>(data); | ||
if (payload->max_size >= ser->getSerializedDataLength()) { | ||
payload->length = static_cast<uint32_t>(ser->getSerializedDataLength()); | ||
payload->encapsulation = ser->endianness() == | ||
eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; | ||
memcpy(payload->data, ser->getBufferPointer(), ser->getSerializedDataLength()); | ||
return true; | ||
auto ser_data = static_cast<SerializedData *>(data); | ||
if (ser_data->is_cdr_buffer) { | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I am a little bit confused. Why would you call There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This is the case when the call comes from rmw_publish_serialized_message. The serialize method is called internally by code inside Fast-RTPS publisher. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. so right now, there is no call to serialize. The raw data will simply be wrapped in There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. When you say 'right now', do you mean on the code currently on master, or on this PR. Whenever data is sent, the serialize function of TypeSupport class is called. In the code currently on master it just copies an externally serialized buffer into the SerializedPayload (that points) to the internal history record buffer. The code on this PR does that on some cases (namely rmw_publish_serialized) and performs serialization directly on others (rmw_publish). On the latter case we save the allocation of a temporary buffer. |
||
auto ser = static_cast<eprosima::fastcdr::Cdr *>(ser_data->data); | ||
if (payload->max_size >= ser->getSerializedDataLength()) { | ||
payload->length = static_cast<uint32_t>(ser->getSerializedDataLength()); | ||
payload->encapsulation = ser->endianness() == | ||
eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; | ||
memcpy(payload->data, ser->getBufferPointer(), ser->getSerializedDataLength()); | ||
return true; | ||
} | ||
} else { | ||
eprosima::fastcdr::FastBuffer fastbuffer( | ||
reinterpret_cast<char *>(payload->data), | ||
payload->max_size); // Object that manages the raw buffer. | ||
eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, | ||
eprosima::fastcdr::Cdr::DDS_CDR); // Object that serializes the data. | ||
if (this->serializeROSmessage(ser_data->data, ser)) { | ||
payload->encapsulation = ser.endianness() == | ||
eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; | ||
payload->length = (uint32_t)ser.getSerializedDataLength(); | ||
return true; | ||
} | ||
} | ||
|
||
return false; | ||
|
@@ -1014,21 +1032,41 @@ bool TypeSupport<MembersType>::deserialize( | |
assert(data); | ||
assert(payload); | ||
|
||
auto buffer = static_cast<eprosima::fastcdr::FastBuffer *>(data); | ||
if (!buffer->reserve(payload->length)) { | ||
return false; | ||
auto ser_data = static_cast<SerializedData *>(data); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. i think this function also could be strongly typed. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Not possible, as it is the implementation of Fast-RTPS TopicDataType interface, declared in this line |
||
if (ser_data->is_cdr_buffer) { | ||
auto buffer = static_cast<eprosima::fastcdr::FastBuffer *>(ser_data->data); | ||
if (!buffer->reserve(payload->length)) { | ||
return false; | ||
} | ||
memcpy(buffer->getBuffer(), payload->data, payload->length); | ||
return true; | ||
} | ||
memcpy(buffer->getBuffer(), payload->data, payload->length); | ||
return true; | ||
|
||
eprosima::fastcdr::FastBuffer fastbuffer( | ||
reinterpret_cast<char *>(payload->data), | ||
payload->length); | ||
eprosima::fastcdr::Cdr deser( | ||
fastbuffer, | ||
eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, | ||
eprosima::fastcdr::Cdr::DDS_CDR); | ||
return deserializeROSmessage(deser, ser_data->data); | ||
} | ||
|
||
template<typename MembersType> | ||
std::function<uint32_t()> TypeSupport<MembersType>::getSerializedSizeProvider(void * data) | ||
{ | ||
assert(data); | ||
|
||
auto ser = static_cast<eprosima::fastcdr::Cdr *>(data); | ||
return [ser]() -> uint32_t {return static_cast<uint32_t>(ser->getSerializedDataLength());}; | ||
auto ser_data = static_cast<SerializedData *>(data); | ||
auto ser_size = [this, ser_data]() -> uint32_t | ||
{ | ||
if (ser_data->is_cdr_buffer) { | ||
auto ser = static_cast<eprosima::fastcdr::Cdr *>(ser_data->data); | ||
return static_cast<uint32_t>(ser->getSerializedDataLength()); | ||
} | ||
return static_cast<uint32_t>(this->getEstimatedSerializedSize(ser_data->data)); | ||
}; | ||
return ser_size; | ||
} | ||
|
||
} // namespace rmw_fastrtps_cpp | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -22,6 +22,7 @@ | |
#include "rmw_fastrtps_cpp/custom_publisher_info.hpp" | ||
#include "rmw_fastrtps_cpp/identifier.hpp" | ||
#include "rmw_fastrtps_cpp/macros.hpp" | ||
#include "rmw_fastrtps_cpp/TypeSupport.hpp" | ||
|
||
#include "./ros_message_serialization.hpp" | ||
|
||
|
@@ -45,17 +46,10 @@ rmw_publish(const rmw_publisher_t * publisher, const void * ros_message) | |
RCUTILS_CHECK_FOR_NULL_WITH_MSG( | ||
info, "publisher info pointer is null", return RMW_RET_ERROR, error_allocator); | ||
|
||
eprosima::fastcdr::FastBuffer buffer; | ||
eprosima::fastcdr::Cdr ser(buffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, | ||
eprosima::fastcdr::Cdr::DDS_CDR); | ||
|
||
if (!_serialize_ros_message(ros_message, buffer, ser, info->type_support_, | ||
info->typesupport_identifier_)) | ||
{ | ||
RMW_SET_ERROR_MSG("cannot serialize data"); | ||
return RMW_RET_ERROR; | ||
} | ||
if (!info->publisher_->write(&ser)) { | ||
rmw_fastrtps_cpp::SerializedData data; | ||
data.is_cdr_buffer = false; | ||
data.data = const_cast<void *>(ros_message); | ||
if (!info->publisher_->write(&data)) { | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. shouldn't this be There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. As stated in this comment, it is not. The write method is provided with a pointer to a SerializedData struct, that will in turn be passed on to the serialize method on TypeSupport_impl. |
||
RMW_SET_ERROR_MSG("cannot publish data"); | ||
return RMW_RET_ERROR; | ||
} | ||
|
@@ -92,7 +86,10 @@ rmw_publish_serialized_message( | |
return RMW_RET_ERROR; | ||
} | ||
|
||
if (!info->publisher_->write(&ser)) { | ||
rmw_fastrtps_cpp::SerializedData data; | ||
data.is_cdr_buffer = true; | ||
data.data = &ser; | ||
if (!info->publisher_->write(&data)) { | ||
RMW_SET_ERROR_MSG("cannot publish data"); | ||
return RMW_RET_ERROR; | ||
} | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
The function could be strongly typed then, right? So this cast could go.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Not possible, as it is the implementation of Fast-RTPS TopicDataType interface, declared in this line