Skip to content

Commit

Permalink
linters and disable wstring tests
Browse files Browse the repository at this point in the history
Signed-off-by: Knese Karsten <karsten.knese@us.bosch.com>
  • Loading branch information
Karsten1987 committed May 23, 2020
1 parent f674759 commit 6fca711
Show file tree
Hide file tree
Showing 6 changed files with 375 additions and 282 deletions.
46 changes: 33 additions & 13 deletions rmw_iceoryx_cpp/src/internal/iceoryx_deserialize_typesupport_c.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,9 @@ const char * deserialize_sequence(const char * serialized_msg, void * ros_messag
}

template<>
const char * deserialize_sequence<char, sizeof(char)>(const char * serialized_msg, void * ros_message_field)
const char * deserialize_sequence<char, sizeof(char)>(
const char * serialized_msg,
void * ros_message_field)
{
uint32_t array_size = 0;
std::tie(serialized_msg, array_size) = pop_sequence_size(serialized_msg);
Expand Down Expand Up @@ -144,38 +146,56 @@ const char * deserialize(
break;
case ::rosidl_typesupport_introspection_c__ROS_TYPE_BYTE:
case ::rosidl_typesupport_introspection_c__ROS_TYPE_UINT8:
serialized_msg = deserialize_message_field<uint8_t>(member, serialized_msg, ros_message_field);
serialized_msg = deserialize_message_field<uint8_t>(
member, serialized_msg,
ros_message_field);
break;
case ::rosidl_typesupport_introspection_c__ROS_TYPE_CHAR:
case ::rosidl_typesupport_introspection_c__ROS_TYPE_INT8:
serialized_msg = deserialize_message_field<char>(member, serialized_msg, ros_message_field);
break;
case ::rosidl_typesupport_introspection_c__ROS_TYPE_FLOAT32:
serialized_msg = deserialize_message_field<float>(member, serialized_msg, ros_message_field);
serialized_msg =
deserialize_message_field<float>(member, serialized_msg, ros_message_field);
break;
case ::rosidl_typesupport_introspection_c__ROS_TYPE_FLOAT64:
serialized_msg = deserialize_message_field<double>(member, serialized_msg, ros_message_field);
serialized_msg =
deserialize_message_field<double>(member, serialized_msg, ros_message_field);
break;
case ::rosidl_typesupport_introspection_c__ROS_TYPE_INT16:
serialized_msg = deserialize_message_field<int16_t>(member, serialized_msg, ros_message_field);
serialized_msg = deserialize_message_field<int16_t>(
member, serialized_msg,
ros_message_field);
break;
case ::rosidl_typesupport_introspection_c__ROS_TYPE_UINT16:
serialized_msg = deserialize_message_field<uint16_t>(member, serialized_msg, ros_message_field);
serialized_msg = deserialize_message_field<uint16_t>(
member, serialized_msg,
ros_message_field);
break;
case ::rosidl_typesupport_introspection_c__ROS_TYPE_INT32:
serialized_msg = deserialize_message_field<int32_t>(member, serialized_msg, ros_message_field);
serialized_msg = deserialize_message_field<int32_t>(
member, serialized_msg,
ros_message_field);
break;
case ::rosidl_typesupport_introspection_c__ROS_TYPE_UINT32:
serialized_msg = deserialize_message_field<uint32_t>(member, serialized_msg, ros_message_field);
serialized_msg = deserialize_message_field<uint32_t>(
member, serialized_msg,
ros_message_field);
break;
case ::rosidl_typesupport_introspection_c__ROS_TYPE_INT64:
serialized_msg = deserialize_message_field<int64_t>(member, serialized_msg, ros_message_field);
serialized_msg = deserialize_message_field<int64_t>(
member, serialized_msg,
ros_message_field);
break;
case ::rosidl_typesupport_introspection_c__ROS_TYPE_UINT64:
serialized_msg = deserialize_message_field<uint64_t>(member, serialized_msg, ros_message_field);
serialized_msg = deserialize_message_field<uint64_t>(
member, serialized_msg,
ros_message_field);
break;
case ::rosidl_typesupport_introspection_c__ROS_TYPE_STRING:
serialized_msg = deserialize_message_field<rosidl_runtime_c__String>(member, serialized_msg, ros_message_field);
serialized_msg = deserialize_message_field<rosidl_runtime_c__String>(
member, serialized_msg,
ros_message_field);
break;
case ::rosidl_typesupport_introspection_c__ROS_TYPE_MESSAGE:
{
Expand All @@ -199,8 +219,8 @@ const char * deserialize(

auto sequence =
const_cast<rosidl_runtime_c__char__Sequence *>(reinterpret_cast<const
rosidl_runtime_c__char__Sequence
*>(ros_message_field));
rosidl_runtime_c__char__Sequence
*>(ros_message_field));

subros_message = reinterpret_cast<void *>(sequence->data);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,9 @@ const char * deserialize_element<std::wstring, sizeof(std::wstring)>(
const char * serialized_msg,
void * ros_message_field)
{
return deserialize_sequence<wchar_t, sizeof(wchar_t), std::wstring>(serialized_msg, ros_message_field);
return deserialize_sequence<wchar_t, sizeof(wchar_t), std::wstring>(
serialized_msg,
ros_message_field);
}

template<
Expand Down Expand Up @@ -188,7 +190,9 @@ const char * deserialize_message_field(
if (!member->is_array_) {
return deserialize_element<T>(serialized_msg, ros_message_field);
} else if (member->array_size_ > 0 && !member->is_upper_bound_) {
return serialized_msg = deserialize_array<T>(serialized_msg, ros_message_field, member->array_size_);
return serialized_msg = deserialize_array<T>(
serialized_msg, ros_message_field,
member->array_size_);
} else {
return serialized_msg = deserialize_sequence<T>(serialized_msg, ros_message_field);
}
Expand All @@ -209,41 +213,61 @@ const char * deserialize(
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BYTE:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT8:
serialized_msg = deserialize_message_field<uint8_t>(member, serialized_msg, ros_message_field);
serialized_msg = deserialize_message_field<uint8_t>(
member, serialized_msg,
ros_message_field);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_CHAR:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT8:
serialized_msg = deserialize_message_field<char>(member, serialized_msg, ros_message_field);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT32:
serialized_msg = deserialize_message_field<float>(member, serialized_msg, ros_message_field);
serialized_msg =
deserialize_message_field<float>(member, serialized_msg, ros_message_field);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT64:
serialized_msg = deserialize_message_field<double>(member, serialized_msg, ros_message_field);
serialized_msg =
deserialize_message_field<double>(member, serialized_msg, ros_message_field);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT16:
serialized_msg = deserialize_message_field<int16_t>(member, serialized_msg, ros_message_field);
serialized_msg = deserialize_message_field<int16_t>(
member, serialized_msg,
ros_message_field);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT16:
serialized_msg = deserialize_message_field<uint16_t>(member, serialized_msg, ros_message_field);
serialized_msg = deserialize_message_field<uint16_t>(
member, serialized_msg,
ros_message_field);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT32:
serialized_msg = deserialize_message_field<int32_t>(member, serialized_msg, ros_message_field);
serialized_msg = deserialize_message_field<int32_t>(
member, serialized_msg,
ros_message_field);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT32:
serialized_msg = deserialize_message_field<uint32_t>(member, serialized_msg, ros_message_field);
serialized_msg = deserialize_message_field<uint32_t>(
member, serialized_msg,
ros_message_field);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT64:
serialized_msg = deserialize_message_field<int64_t>(member, serialized_msg, ros_message_field);
serialized_msg = deserialize_message_field<int64_t>(
member, serialized_msg,
ros_message_field);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT64:
serialized_msg = deserialize_message_field<uint64_t>(member, serialized_msg, ros_message_field);
serialized_msg = deserialize_message_field<uint64_t>(
member, serialized_msg,
ros_message_field);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_STRING:
serialized_msg = deserialize_message_field<std::string>(member, serialized_msg, ros_message_field);
serialized_msg = deserialize_message_field<std::string>(
member, serialized_msg,
ros_message_field);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_WSTRING:
serialized_msg = deserialize_message_field<std::wstring>(member, serialized_msg, ros_message_field);
serialized_msg = deserialize_message_field<std::wstring>(
member, serialized_msg,
ros_message_field);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE:
{
Expand Down
77 changes: 41 additions & 36 deletions rmw_iceoryx_cpp/src/internal/iceoryx_serialize_typesupport_c.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,8 @@ template<
>
void serialize_sequence(std::vector<char> & serialized_msg, const void * ros_message_field)
{
auto sequence = reinterpret_cast<const typename traits::sequence_type<T>::type *>(ros_message_field);
auto sequence =
reinterpret_cast<const typename traits::sequence_type<T>::type *>(ros_message_field);
uint32_t sequence_size = sequence->size;

push_sequence_size(serialized_msg, sequence_size);
Expand Down Expand Up @@ -152,46 +153,50 @@ void serialize(
serialize_message_field<uint64_t>(member, serialized_msg, ros_message_field);
break;
case ::rosidl_typesupport_introspection_c__ROS_TYPE_STRING:
serialize_message_field<rosidl_runtime_c__String>(member, serialized_msg, ros_message_field);
serialize_message_field<rosidl_runtime_c__String>(
member, serialized_msg,
ros_message_field);
break;
case ::rosidl_typesupport_introspection_c__ROS_TYPE_MESSAGE:
{
// Iterate recursively over the complex ROS messages
auto sub_members =
static_cast<const rosidl_typesupport_introspection_c__MessageMembers *>(member->members_->data);

const void * subros_message = nullptr;
size_t sequence_size = 0;
size_t sub_members_size = sub_members->size_of_;
// It's a single message
if (!member->is_array_) {
subros_message = ros_message_field;
sequence_size = 1;
// It's a fixed size array of messages
} else if (member->array_size_ > 0 && !member->is_upper_bound_) {
subros_message = ros_message_field;
sequence_size = member->array_size_;
// It's a dynamic sequence of messages
} else {
// Cast current ros_message_field ptr as vector "definition"
auto vector = reinterpret_cast<const rosidl_runtime_c__char__Sequence *>(ros_message_field);
// Vector size points to content of vector and returns number of bytes
// submembersize is the size of one element in the vector (it is provided by type support)
sequence_size = vector->size / sub_members_size;
if (member->is_upper_bound_ && sequence_size > member->array_size_) {
throw std::runtime_error("vector overcomes the maximum length");
// Iterate recursively over the complex ROS messages
auto sub_members =
static_cast<const rosidl_typesupport_introspection_c__MessageMembers *>(member->members_
->data);

const void * subros_message = nullptr;
size_t sequence_size = 0;
size_t sub_members_size = sub_members->size_of_;
// It's a single message
if (!member->is_array_) {
subros_message = ros_message_field;
sequence_size = 1;
// It's a fixed size array of messages
} else if (member->array_size_ > 0 && !member->is_upper_bound_) {
subros_message = ros_message_field;
sequence_size = member->array_size_;
// It's a dynamic sequence of messages
} else {
// Cast current ros_message_field ptr as vector "definition"
auto vector =
reinterpret_cast<const rosidl_runtime_c__char__Sequence *>(ros_message_field);
// Vector size points to content of vector and returns number of bytes
// submembersize is the size of one element in the vector (it is provided by type support)
sequence_size = vector->size / sub_members_size;
if (member->is_upper_bound_ && sequence_size > member->array_size_) {
throw std::runtime_error("vector overcomes the maximum length");
}
// create ptr to content of vector to enable recursion
subros_message = reinterpret_cast<const void *>(vector->data);
// store the number of elements
push_sequence_size(serialized_msg, sequence_size);
}
// create ptr to content of vector to enable recursion
subros_message = reinterpret_cast<const void *>(vector->data);
// store the number of elements
push_sequence_size(serialized_msg, sequence_size);
}

debug_log("serializing message field %s\n", member->name_);
for (auto index = 0u; index < sequence_size; ++index) {
serialize(subros_message, sub_members, serialized_msg);
subros_message = static_cast<const char *>(subros_message) + sub_members_size;
}
debug_log("serializing message field %s\n", member->name_);
for (auto index = 0u; index < sequence_size; ++index) {
serialize(subros_message, sub_members, serialized_msg);
subros_message = static_cast<const char *>(subros_message) + sub_members_size;
}
}
break;
default:
Expand Down
77 changes: 39 additions & 38 deletions rmw_iceoryx_cpp/src/internal/iceoryx_serialize_typesupport_cpp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,16 +76,16 @@ void serialize_element(

template<>
void serialize_element<std::string, sizeof(std::string)>(
std::vector<char> & serialized_msg,
const char * ros_message_field)
std::vector<char> & serialized_msg,
const char * ros_message_field)
{
serialize_sequence<char, sizeof(char), std::string>(serialized_msg, ros_message_field);
}

template<>
void serialize_element<std::wstring, sizeof(std::wstring)>(
std::vector<char> & serialized_msg,
const char * ros_message_field)
std::vector<char> & serialized_msg,
const char * ros_message_field)
{
serialize_sequence<wchar_t, sizeof(wchar_t), std::wstring>(serialized_msg, ros_message_field);
}
Expand Down Expand Up @@ -196,42 +196,43 @@ void serialize(
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE:
{
// Iterate recursively over the complex ROS messages
auto sub_members =
static_cast<const rosidl_typesupport_introspection_cpp::MessageMembers *>(member->members_->data);

const void * subros_message = nullptr;
size_t sequence_size = 0;
size_t sub_members_size = sub_members->size_of_;
// It's a single message
if (!member->is_array_) {
subros_message = ros_message_field;
sequence_size = 1;
// It's a fixed size array of messages
} else if (member->array_size_ > 0 && !member->is_upper_bound_) {
subros_message = ros_message_field;
sequence_size = member->array_size_;
// It's a dynamic sequence of messages
} else {
// Cast current ros_message_field ptr as vector "definition"
auto vector = reinterpret_cast<const std::vector<unsigned char> *>(ros_message_field);
// Vector size points to content of vector and returns number of bytes
// submembersize is the size of one element in the vector (it is provided by type support)
sequence_size = vector->size() / sub_members_size;
if (member->is_upper_bound_ && sequence_size > member->array_size_) {
throw std::runtime_error("vector overcomes the maximum length");
// Iterate recursively over the complex ROS messages
auto sub_members =
static_cast<const rosidl_typesupport_introspection_cpp::MessageMembers *>(member->
members_->data);

const void * subros_message = nullptr;
size_t sequence_size = 0;
size_t sub_members_size = sub_members->size_of_;
// It's a single message
if (!member->is_array_) {
subros_message = ros_message_field;
sequence_size = 1;
// It's a fixed size array of messages
} else if (member->array_size_ > 0 && !member->is_upper_bound_) {
subros_message = ros_message_field;
sequence_size = member->array_size_;
// It's a dynamic sequence of messages
} else {
// Cast current ros_message_field ptr as vector "definition"
auto vector = reinterpret_cast<const std::vector<unsigned char> *>(ros_message_field);
// Vector size points to content of vector and returns number of bytes
// submembersize is the size of one element in the vector (it is provided by type support)
sequence_size = vector->size() / sub_members_size;
if (member->is_upper_bound_ && sequence_size > member->array_size_) {
throw std::runtime_error("vector overcomes the maximum length");
}
// create ptr to content of vector to enable recursion
subros_message = reinterpret_cast<const void *>(vector->data());
// store the number of elements
push_sequence_size(serialized_msg, sequence_size);
}
// create ptr to content of vector to enable recursion
subros_message = reinterpret_cast<const void *>(vector->data());
// store the number of elements
push_sequence_size(serialized_msg, sequence_size);
}

debug_log("serializing message field %s\n", member->name_);
for (auto index = 0u; index < sequence_size; ++index) {
serialize(subros_message, sub_members, serialized_msg);
subros_message = static_cast<const char *>(subros_message) + sub_members_size;
}
debug_log("serializing message field %s\n", member->name_);
for (auto index = 0u; index < sequence_size; ++index) {
serialize(subros_message, sub_members, serialized_msg);
subros_message = static_cast<const char *>(subros_message) + sub_members_size;
}
}
break;
default:
Expand Down
Loading

0 comments on commit 6fca711

Please sign in to comment.