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

rename rosidl_generator_c namespace to rosidl_runtime_c #367

Merged
merged 1 commit into from
Apr 11, 2020
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
4 changes: 2 additions & 2 deletions rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/TypeSupport.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#ifndef RMW_FASTRTPS_CPP__TYPESUPPORT_HPP_
#define RMW_FASTRTPS_CPP__TYPESUPPORT_HPP_

#include <rosidl_generator_c/string.h>
#include <rosidl_generator_c/string_functions.h>
#include <rosidl_runtime_c/string.h>
#include <rosidl_runtime_c/string_functions.h>

#include <fastrtps/TopicDataType.h>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#ifndef RMW_FASTRTPS_DYNAMIC_CPP__TYPESUPPORT_HPP_
#define RMW_FASTRTPS_DYNAMIC_CPP__TYPESUPPORT_HPP_

#include <rosidl_generator_c/string.h>
#include <rosidl_generator_c/string_functions.h>
#include <rosidl_runtime_c/string.h>
#include <rosidl_runtime_c/string_functions.h>

#include <fastrtps/TopicDataType.h>

Expand Down Expand Up @@ -54,15 +54,15 @@ struct StringHelper;
template<>
struct StringHelper<rosidl_typesupport_introspection_c__MessageMembers>
{
using type = rosidl_generator_c__String;
using type = rosidl_runtime_c__String;

static size_t next_field_align(void * data, size_t current_alignment)
{
auto c_string = static_cast<rosidl_generator_c__String *>(data);
auto c_string = static_cast<rosidl_runtime_c__String *>(data);
if (!c_string) {
RCUTILS_LOG_ERROR_NAMED(
"rmw_fastrtps_dynamic_cpp",
"Failed to cast data as rosidl_generator_c__String");
"Failed to cast data as rosidl_runtime_c__String");
return current_alignment;
}
if (!c_string->data) {
Expand All @@ -79,11 +79,11 @@ struct StringHelper<rosidl_typesupport_introspection_c__MessageMembers>

static std::string convert_to_std_string(void * data)
{
auto c_string = static_cast<rosidl_generator_c__String *>(data);
auto c_string = static_cast<rosidl_runtime_c__String *>(data);
if (!c_string) {
RCUTILS_LOG_ERROR_NAMED(
"rmw_fastrtps_dynamic_cpp",
"Failed to cast data as rosidl_generator_c__String");
"Failed to cast data as rosidl_runtime_c__String");
return "";
}
if (!c_string->data) {
Expand All @@ -95,7 +95,7 @@ struct StringHelper<rosidl_typesupport_introspection_c__MessageMembers>
return std::string(c_string->data);
}

static std::string convert_to_std_string(rosidl_generator_c__String & data)
static std::string convert_to_std_string(rosidl_runtime_c__String & data)
{
return std::string(data.data);
}
Expand All @@ -104,8 +104,8 @@ struct StringHelper<rosidl_typesupport_introspection_c__MessageMembers>
{
std::string str;
deser >> str;
rosidl_generator_c__String * c_str = static_cast<rosidl_generator_c__String *>(field);
rosidl_generator_c__String__assign(c_str, str.c_str());
rosidl_runtime_c__String * c_str = static_cast<rosidl_runtime_c__String *>(field);
rosidl_runtime_c__String__assign(c_str, str.c_str());
}
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,8 @@
#include "rosidl_typesupport_introspection_c/message_introspection.h"
#include "rosidl_typesupport_introspection_c/service_introspection.h"

#include "rosidl_generator_c/primitives_sequence_functions.h"
#include "rosidl_generator_c/u16string_functions.h"
#include "rosidl_runtime_c/primitives_sequence_functions.h"
#include "rosidl_runtime_c/u16string_functions.h"

namespace rmw_fastrtps_dynamic_cpp
{
Expand All @@ -55,19 +55,19 @@ SPECIALIZE_GENERIC_C_SEQUENCE(uint32, uint32_t)
SPECIALIZE_GENERIC_C_SEQUENCE(int64, int64_t)
SPECIALIZE_GENERIC_C_SEQUENCE(uint64, uint64_t)

typedef struct rosidl_generator_c__void__Sequence
typedef struct rosidl_runtime_c__void__Sequence
{
void * data;
/// The number of valid items in data
size_t size;
/// The number of allocated items in data
size_t capacity;
} rosidl_generator_c__void__Sequence;
} rosidl_runtime_c__void__Sequence;

inline
bool
rosidl_generator_c__void__Sequence__init(
rosidl_generator_c__void__Sequence * sequence, size_t size, size_t member_size)
rosidl_runtime_c__void__Sequence__init(
rosidl_runtime_c__void__Sequence * sequence, size_t size, size_t member_size)
{
if (!sequence) {
return false;
Expand All @@ -87,7 +87,7 @@ rosidl_generator_c__void__Sequence__init(

inline
void
rosidl_generator_c__void__Sequence__fini(rosidl_generator_c__void__Sequence * sequence)
rosidl_runtime_c__void__Sequence__fini(rosidl_runtime_c__void__Sequence * sequence)
{
if (!sequence) {
return;
Expand Down Expand Up @@ -177,7 +177,7 @@ static size_t calculateMaxAlign(const MembersType * members)
if (std::is_same<MembersType,
rosidl_typesupport_introspection_c__MessageMembers>::value)
{
alignment = alignof(rosidl_generator_c__String);
alignment = alignof(rosidl_runtime_c__String);
} else {
alignment = alignof(std::string);
}
Expand All @@ -186,7 +186,7 @@ static size_t calculateMaxAlign(const MembersType * members)
if (std::is_same<MembersType,
rosidl_typesupport_introspection_c__MessageMembers>::value)
{
alignment = alignof(rosidl_generator_c__U16String);
alignment = alignof(rosidl_runtime_c__U16String);
} else {
alignment = alignof(std::u16string);
}
Expand Down Expand Up @@ -293,14 +293,14 @@ void serialize_field<std::string>(
// tmpstring is defined here and not below to avoid
// memory allocation in every iteration of the for loop
std::string tmpstring;
auto string_field = static_cast<rosidl_generator_c__String *>(field);
auto string_field = static_cast<rosidl_runtime_c__String *>(field);
for (size_t i = 0; i < member->array_size_; ++i) {
tmpstring = string_field[i].data;
ser.serialize(tmpstring);
}
} else {
auto & string_sequence_field =
*reinterpret_cast<rosidl_generator_c__String__Sequence *>(field);
*reinterpret_cast<rosidl_runtime_c__String__Sequence *>(field);
std::vector<std::string> cpp_string_vector;
for (size_t i = 0; i < string_sequence_field.size; ++i) {
cpp_string_vector.push_back(
Expand All @@ -320,17 +320,17 @@ void serialize_field<std::wstring>(
{
std::wstring wstr;
if (!member->is_array_) {
auto u16str = static_cast<rosidl_generator_c__U16String *>(field);
auto u16str = static_cast<rosidl_runtime_c__U16String *>(field);
rosidl_typesupport_fastrtps_c::u16string_to_wstring(*u16str, wstr);
ser << wstr;
} else if (member->array_size_ && !member->is_upper_bound_) {
auto array = static_cast<rosidl_generator_c__U16String *>(field);
auto array = static_cast<rosidl_runtime_c__U16String *>(field);
for (size_t i = 0; i < member->array_size_; ++i) {
rosidl_typesupport_fastrtps_c::u16string_to_wstring(array[i], wstr);
ser << wstr;
}
} else {
auto sequence = static_cast<rosidl_generator_c__U16String__Sequence *>(field);
auto sequence = static_cast<rosidl_runtime_c__U16String__Sequence *>(field);
ser << static_cast<uint32_t>(sequence->size);
for (size_t i = 0; i < sequence->size; ++i) {
rosidl_typesupport_fastrtps_c::u16string_to_wstring(sequence->data[i], wstr);
Expand Down Expand Up @@ -363,7 +363,7 @@ size_t get_array_size_and_assign_field(
void * & subros_message,
size_t, size_t)
{
auto tmpsequence = static_cast<rosidl_generator_c__void__Sequence *>(field);
auto tmpsequence = static_cast<rosidl_runtime_c__void__Sequence *>(field);
if (member->is_upper_bound_ && tmpsequence->size > member->array_size_) {
throw std::runtime_error("vector overcomes the maximum length");
}
Expand Down Expand Up @@ -575,7 +575,7 @@ size_t next_field_align_string<std::string>(
current_alignment = CStringHelper::next_field_align(field, current_alignment);
} else {
if (member->array_size_ && !member->is_upper_bound_) {
auto string_field = static_cast<rosidl_generator_c__String *>(field);
auto string_field = static_cast<rosidl_runtime_c__String *>(field);
for (size_t i = 0; i < member->array_size_; ++i) {
current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
current_alignment += padding;
Expand All @@ -585,7 +585,7 @@ size_t next_field_align_string<std::string>(
current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
current_alignment += padding;
auto & string_sequence_field =
*reinterpret_cast<rosidl_generator_c__String__Sequence *>(field);
*reinterpret_cast<rosidl_runtime_c__String__Sequence *>(field);
for (size_t i = 0; i < string_sequence_field.size; ++i) {
current_alignment = CStringHelper::next_field_align(
&(string_sequence_field.data[i]), current_alignment);
Expand All @@ -604,13 +604,13 @@ size_t next_field_align_string<std::wstring>(
{
const size_t padding = 4;
if (!member->is_array_) {
auto u16str = static_cast<rosidl_generator_c__U16String *>(field);
auto u16str = static_cast<rosidl_runtime_c__U16String *>(field);
current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
current_alignment += padding;
current_alignment += 4 * (u16str->size + 1);
} else {
if (member->array_size_ && !member->is_upper_bound_) {
auto string_field = static_cast<rosidl_generator_c__U16String *>(field);
auto string_field = static_cast<rosidl_runtime_c__U16String *>(field);
for (size_t i = 0; i < member->array_size_; ++i) {
current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
current_alignment += padding;
Expand All @@ -620,7 +620,7 @@ size_t next_field_align_string<std::wstring>(
current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
current_alignment += padding;
auto & string_sequence_field =
*reinterpret_cast<rosidl_generator_c__U16String__Sequence *>(field);
*reinterpret_cast<rosidl_runtime_c__U16String__Sequence *>(field);
for (size_t i = 0; i < string_sequence_field.size; ++i) {
current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
current_alignment += padding;
Expand Down Expand Up @@ -842,35 +842,35 @@ inline void deserialize_field<std::string>(
CStringHelper::assign(deser, field, call_new);
} else {
if (member->array_size_ && !member->is_upper_bound_) {
auto deser_field = static_cast<rosidl_generator_c__String *>(field);
auto deser_field = static_cast<rosidl_runtime_c__String *>(field);
// tmpstring is defined here and not below to avoid
// memory allocation in every iteration of the for loop
std::string tmpstring;
for (size_t i = 0; i < member->array_size_; ++i) {
deser.deserialize(tmpstring);
if (!rosidl_generator_c__String__assign(&deser_field[i], tmpstring.c_str())) {
throw std::runtime_error("unable to assign rosidl_generator_c__String");
if (!rosidl_runtime_c__String__assign(&deser_field[i], tmpstring.c_str())) {
throw std::runtime_error("unable to assign rosidl_runtime_c__String");
}
}
} else {
std::vector<std::string> cpp_string_vector;
deser >> cpp_string_vector;

auto & string_sequence_field =
*reinterpret_cast<rosidl_generator_c__String__Sequence *>(field);
*reinterpret_cast<rosidl_runtime_c__String__Sequence *>(field);
if (
!rosidl_generator_c__String__Sequence__init(
!rosidl_runtime_c__String__Sequence__init(
&string_sequence_field, cpp_string_vector.size()))
{
throw std::runtime_error("unable to initialize rosidl_generator_c__String array");
throw std::runtime_error("unable to initialize rosidl_runtime_c__String array");
}

for (size_t i = 0; i < cpp_string_vector.size(); ++i) {
if (
!rosidl_generator_c__String__assign(
!rosidl_runtime_c__String__assign(
&string_sequence_field.data[i], cpp_string_vector[i].c_str()))
{
throw std::runtime_error("unable to assign rosidl_generator_c__String");
throw std::runtime_error("unable to assign rosidl_runtime_c__String");
}
}
}
Expand All @@ -889,19 +889,19 @@ inline void deserialize_field<std::wstring>(
if (!member->is_array_) {
deser >> wstr;
rosidl_typesupport_fastrtps_c::wstring_to_u16string(
wstr, *static_cast<rosidl_generator_c__U16String *>(field));
wstr, *static_cast<rosidl_runtime_c__U16String *>(field));
} else if (member->array_size_ && !member->is_upper_bound_) {
auto array = static_cast<rosidl_generator_c__U16String *>(field);
auto array = static_cast<rosidl_runtime_c__U16String *>(field);
for (size_t i = 0; i < member->array_size_; ++i) {
deser >> wstr;
rosidl_typesupport_fastrtps_c::wstring_to_u16string(wstr, array[i]);
}
} else {
uint32_t size;
deser >> size;
auto sequence = static_cast<rosidl_generator_c__U16String__Sequence *>(field);
if (!rosidl_generator_c__U16String__Sequence__init(sequence, size)) {
throw std::runtime_error("unable to initialize rosidl_generator_c__U16String sequence");
auto sequence = static_cast<rosidl_runtime_c__U16String__Sequence *>(field);
if (!rosidl_runtime_c__U16String__Sequence__init(sequence, size)) {
throw std::runtime_error("unable to initialize rosidl_runtime_c__U16String sequence");
}
for (size_t i = 0; i < sequence->size; ++i) {
deser >> wstr;
Expand Down Expand Up @@ -946,8 +946,8 @@ inline size_t get_submessage_array_deserialize(
// Deserialize length
uint32_t vsize = 0;
deser >> vsize;
auto tmpsequence = static_cast<rosidl_generator_c__void__Sequence *>(field);
rosidl_generator_c__void__Sequence__init(tmpsequence, vsize, sub_members_size);
auto tmpsequence = static_cast<rosidl_runtime_c__void__Sequence *>(field);
rosidl_runtime_c__void__Sequence__init(tmpsequence, vsize, sub_members_size);
subros_message = reinterpret_cast<void *>(tmpsequence->data);
return vsize;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,14 +22,14 @@
template<> \
struct GenericCSequence<C_TYPE> \
{ \
using type = rosidl_generator_c__ ## C_NAME ## __Sequence; \
using type = rosidl_runtime_c__ ## C_NAME ## __Sequence; \
\
static void fini(type * array) { \
rosidl_generator_c__ ## C_NAME ## __Sequence__fini(array); \
rosidl_runtime_c__ ## C_NAME ## __Sequence__fini(array); \
} \
\
static bool init(type * array, size_t size) { \
return rosidl_generator_c__ ## C_NAME ## __Sequence__init(array, size); \
return rosidl_runtime_c__ ## C_NAME ## __Sequence__init(array, size); \
} \
};

Expand Down