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

Large message pub sub revision #51

Merged
merged 5 commits into from
Aug 27, 2016
Merged
Show file tree
Hide file tree
Changes from all commits
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
Original file line number Diff line number Diff line change
Expand Up @@ -32,16 +32,16 @@ MessageTypeSupport<MembersType>::MessageTypeSupport(const MembersType *members)
assert(members);
this->members_ = members;

if(strcmp(members->package_name_, "rcl_interfaces") == 0 && strcmp(members->message_name_, "ParameterEvent") == 0)
this->typeTooLarge_ = true;

std::string name = std::string(members->package_name_) + "::msg::dds_::" + members->message_name_ + "_";
this->setName(name.c_str());

// TODO(wjwwood): this could be more intelligent, setting m_typeSize to the
// maximum serialized size of the message, when the message is a bonded one.
if(members->member_count_ != 0)
this->m_typeSize = static_cast<uint32_t>(this->calculateMaxSerializedSize(members, 0));
else
this->m_typeSize = 1;
this->m_typeSize = 4;
}


#endif // _RMW_FASTRTPS_CPP_MESSAGETYPESUPPORT_IMPL_H_
Original file line number Diff line number Diff line change
Expand Up @@ -35,17 +35,13 @@ RequestTypeSupport<ServiceMembersType, MessageMembersType>::RequestTypeSupport(c
assert(members);
this->members_ = members->request_members_;

if(strcmp(members->package_name_, "rcl_interfaces") == 0 && (strcmp(members->service_name_, "SetParameters") == 0 ||
strcmp(members->service_name_, "SetParametersAtomically") == 0))
this->typeTooLarge_ = true;

std::string name = std::string(members->package_name_) + "::srv::dds_::" + members->service_name_ + "_Request_";
this->setName(name.c_str());

if(this->members_->member_count_ != 0)
this->m_typeSize = static_cast<uint32_t>(this->calculateMaxSerializedSize(this->members_, 0));
else
this->m_typeSize = 1;
this->m_typeSize = 4;
}

template <typename ServiceMembersType, typename MessageMembersType>
Expand All @@ -60,7 +56,7 @@ ResponseTypeSupport<ServiceMembersType, MessageMembersType>::ResponseTypeSupport
if(this->members_->member_count_ != 0)
this->m_typeSize = static_cast<uint32_t>(this->calculateMaxSerializedSize(this->members_, 0));
else
this->m_typeSize = 1;
this->m_typeSize = 4;
}

#endif // _RMW_FASTRTPS_CPP_SERVICETYPESUPPORT_IMPL_H_
16 changes: 4 additions & 12 deletions rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/TypeSupport.h
Original file line number Diff line number Diff line change
Expand Up @@ -93,25 +93,21 @@ namespace rmw_fastrtps_cpp
}
};

typedef struct Buffer
{
uint32_t length;
char *pointer;
} Buffer;

template <typename MembersType>
class TypeSupport : public eprosima::fastrtps::TopicDataType
{
public:

bool serializeROSmessage(const void *ros_message, Buffer *data);
bool serializeROSmessage(const void *ros_message, eprosima::fastcdr::Cdr& ser);

bool deserializeROSmessage(const Buffer* data, void *ros_message);
bool deserializeROSmessage(eprosima::fastcdr::FastBuffer *data, void *ros_message);

bool serialize(void *data, SerializedPayload_t *payload);

bool deserialize(SerializedPayload_t *payload, void *data);

std::function<uint32_t()> getSerializedSizeProvider(void* data);

void* createData();

void deleteData(void* data);
Expand All @@ -124,15 +120,11 @@ namespace rmw_fastrtps_cpp

const MembersType *members_;

bool typeTooLarge_;

private:

bool serializeROSmessage(eprosima::fastcdr::Cdr &ser, const MembersType *members, const void *ros_message);

bool deserializeROSmessage(eprosima::fastcdr::Cdr &deser, const MembersType *members, void *ros_message, bool call_new);

bool typeByDefaultLarge() { return typeTooLarge_; }
};
}

Expand Down
104 changes: 44 additions & 60 deletions rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/TypeSupport_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ SPECIALIZE_GENERIC_C_ARRAY(uint64, uint64_t)


template <typename MembersType>
TypeSupport<MembersType>::TypeSupport() : typeTooLarge_(false)
TypeSupport<MembersType>::TypeSupport()
{
m_isGetKeyDefined = false;
}
Expand All @@ -60,7 +60,7 @@ template <typename MembersType>
void TypeSupport<MembersType>::deleteData(void* data)
{
assert(data);
free(data);
delete static_cast<eprosima::fastcdr::FastBuffer *>(data);
}

static inline void*
Expand Down Expand Up @@ -228,17 +228,12 @@ template<typename T>
void serialize_array(
const rosidl_typesupport_introspection_cpp::MessageMember * member,
void * field,
eprosima::fastcdr::Cdr &ser,
bool typeTooLarge)
eprosima::fastcdr::Cdr &ser)
{
if (member->array_size_ && !member->is_upper_bound_) {
ser.serializeArray((T*)field, member->array_size_);
} else {
std::vector<T> & data = *reinterpret_cast<std::vector<T> *>(field);
if(data.size() > (member->is_upper_bound_ ? member->array_size_ : (typeTooLarge ? 30 : 101))) {
printf("vector overcomes the maximum length\n");
throw std::runtime_error("vector overcomes the maximum length");
}
ser << data;
}
}
Expand All @@ -248,17 +243,12 @@ template<typename T>
void serialize_array(
const rosidl_typesupport_introspection_c__MessageMember * member,
void * field,
eprosima::fastcdr::Cdr &ser,
bool typeTooLarge)
eprosima::fastcdr::Cdr &ser)
{
if (member->array_size_ && !member->is_upper_bound_) {
ser.serializeArray((T*)field, member->array_size_);
} else {
auto & data = *reinterpret_cast<typename GenericCArray<T>::type *>(field);
if(data.size > (member->is_upper_bound_ ? member->array_size_ : (typeTooLarge ? 30 : 101))) {
printf("vector overcomes the maximum length\n");
throw std::runtime_error("vector overcomes the maximum length");
}
ser.serializeArray((T*)data.data, data.size);
}
}
Expand All @@ -267,8 +257,7 @@ template<>
void serialize_array<std::string>(
const rosidl_typesupport_introspection_c__MessageMember * member,
void * field,
eprosima::fastcdr::Cdr &ser,
bool typeTooLarge)
eprosima::fastcdr::Cdr &ser)
{
using CStringHelper = StringHelper<rosidl_typesupport_introspection_c__MessageMembers>;
// First, cast field to rosidl_generator_c
Expand All @@ -278,11 +267,6 @@ void serialize_array<std::string>(
ser.serializeArray(string_field->data, member->array_size_);
} else {
auto & string_array_field = *reinterpret_cast<rosidl_generator_c__String__Array *>(field);
if(
string_array_field.size > (member->is_upper_bound_ ? member->array_size_ : (typeTooLarge ? 30 : 101))) {
printf("vector overcomes the maximum length\n");
throw std::runtime_error("vector overcomes the maximum length");
}
std::vector<std::string> cpp_string_vector;
for (size_t i = 0; i < string_array_field.size; ++i) {
cpp_string_vector.push_back(CStringHelper::convert_to_std_string(string_array_field.data[i]));
Expand Down Expand Up @@ -408,42 +392,42 @@ bool TypeSupport<MembersType>::serializeROSmessage(
switch(member->type_id_)
{
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BOOL:
serialize_array<bool>(member, field, ser, typeByDefaultLarge());
serialize_array<bool>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BYTE:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT8:
serialize_array<uint8_t>(member, field, ser, typeByDefaultLarge());
serialize_array<uint8_t>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_CHAR:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT8:
serialize_array<char>(member, field, ser, typeByDefaultLarge());
serialize_array<char>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT32:
serialize_array<float>(member, field, ser, typeByDefaultLarge());
serialize_array<float>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT64:
serialize_array<double>(member, field, ser, typeByDefaultLarge());
serialize_array<double>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT16:
serialize_array<int16_t>(member, field, ser, typeByDefaultLarge());
serialize_array<int16_t>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT16:
serialize_array<uint16_t>(member, field, ser, typeByDefaultLarge());
serialize_array<uint16_t>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT32:
serialize_array<int32_t>(member, field, ser, typeByDefaultLarge());
serialize_array<int32_t>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT32:
serialize_array<uint32_t>(member, field, ser, typeByDefaultLarge());
serialize_array<uint32_t>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT64:
serialize_array<int64_t>(member, field, ser, typeByDefaultLarge());
serialize_array<int64_t>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT64:
serialize_array<uint64_t>(member, field, ser, typeByDefaultLarge());
serialize_array<uint64_t>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_STRING:
serialize_array<std::string>(member, field, ser, typeByDefaultLarge());
serialize_array<std::string>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE:
{
Expand Down Expand Up @@ -781,7 +765,7 @@ size_t TypeSupport<MembersType>::calculateMaxSerializedSize(
{
current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4);

if(array_size == 0) typeByDefaultLarge() ? array_size = 30 : array_size = 101;
if(array_size == 0) array_size = 101;
}

switch(member->type_id_)
Expand Down Expand Up @@ -832,32 +816,26 @@ size_t TypeSupport<MembersType>::calculateMaxSerializedSize(

template <typename MembersType>
bool TypeSupport<MembersType>::serializeROSmessage(
const void *ros_message, Buffer *buffer)
const void *ros_message, eprosima::fastcdr::Cdr& ser)
{
assert(buffer);
assert(ros_message);

eprosima::fastcdr::FastBuffer fastbuffer(buffer->pointer, m_typeSize);
eprosima::fastcdr::Cdr ser(fastbuffer);

if(members_->member_count_ != 0)
TypeSupport::serializeROSmessage(ser, members_, ros_message);
else
ser << (uint8_t)0;

buffer->length = (uint32_t)ser.getSerializedDataLength();
return true;
}

template <typename MembersType>
bool TypeSupport<MembersType>::deserializeROSmessage(
const Buffer* buffer, void *ros_message)
eprosima::fastcdr::FastBuffer* buffer, void *ros_message)
{
assert(buffer);
assert(ros_message);

eprosima::fastcdr::FastBuffer fastbuffer(buffer->pointer, buffer->length);
eprosima::fastcdr::Cdr deser(fastbuffer);
eprosima::fastcdr::Cdr deser(*buffer);

if(members_->member_count_ != 0)
TypeSupport::deserializeROSmessage(deser, members_, ros_message, false);
Expand All @@ -874,15 +852,7 @@ bool TypeSupport<MembersType>::deserializeROSmessage(
template <typename MembersType>
void* TypeSupport<MembersType>::createData()
{
Buffer *buffer = static_cast<Buffer*>(malloc(sizeof(Buffer) + m_typeSize));

if(buffer)
{
buffer->length = 0;
buffer->pointer = (char*)(buffer + 1);
}

return buffer;
return new eprosima::fastcdr::FastBuffer();
}

template <typename MembersType>
Expand All @@ -892,11 +862,16 @@ bool TypeSupport<MembersType>::serialize(
assert(data);
assert(payload);

Buffer *buffer = static_cast<Buffer*>(data);
payload->length = buffer->length;
payload->encapsulation = CDR_LE;
memcpy(payload->data, buffer->pointer, buffer->length);
return true;
eprosima::fastcdr::Cdr *ser = static_cast<eprosima::fastcdr::Cdr*>(data);
if(payload->max_size >= ser->getSerializedDataLength())
{
payload->length = static_cast<uint32_t>(ser->getSerializedDataLength());
payload->encapsulation = CDR_LE;
memcpy(payload->data, ser->getBufferPointer(), ser->getSerializedDataLength());
return true;
}

return false;
}

template <typename MembersType>
Expand All @@ -905,10 +880,19 @@ bool TypeSupport<MembersType>::deserialize(SerializedPayload_t *payload, void *d
assert(data);
assert(payload);

Buffer *buffer = static_cast<Buffer*>(data);
buffer->length = payload->length;
memcpy(buffer->pointer, payload->data, payload->length);
eprosima::fastcdr::FastBuffer *buffer = static_cast<eprosima::fastcdr::FastBuffer*>(data);
buffer->resize(payload->length);
memcpy(buffer->getBuffer(), payload->data, payload->length);
return true;
}

template <typename MembersType>
std::function<uint32_t()> TypeSupport<MembersType>::getSerializedSizeProvider(void* data)
{
assert(data);

eprosima::fastcdr::Cdr *ser = static_cast<eprosima::fastcdr::Cdr*>(data);
return [ser]() -> uint32_t { return static_cast<uint32_t>(ser->getSerializedDataLength()); };
}

#endif // _RMW_FASTRTPS_CPP_TYPESUPPORT_IMPL_H_
Loading