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

Updates to build against foxy. #45

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
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
34 changes: 16 additions & 18 deletions rmw_dps_cpp/include/rmw_dps_cpp/TypeSupport.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,8 @@
#ifndef RMW_DPS_CPP__TYPESUPPORT_HPP_
#define RMW_DPS_CPP__TYPESUPPORT_HPP_

#include <rosidl_generator_c/string.h>
#include <rosidl_generator_c/string_functions.h>
#include <rosidl_generator_c/u16string.h>
#include <rosidl_generator_c/u16string_functions.h>
#include "rosidl_runtime_c/string_functions.h"
#include "rosidl_runtime_c/u16string_functions.h"

#include <cassert>
#include <string>
Expand Down Expand Up @@ -50,27 +48,27 @@ struct StringHelper;
template<>
struct StringHelper<rosidl_typesupport_introspection_c__MessageMembers>
{
using type = rosidl_generator_c__String;
using type = rosidl_runtime_c__String;

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_dps_cpp",
"Failed to cast data as rosidl_generator_c__String");
"Failed to cast data as rosidl_runtime_c__String");
return "";
}
if (!c_string->data) {
RCUTILS_LOG_ERROR_NAMED(
"rmw_dps_cpp",
"rosidl_generator_c_String had invalid data");
"rosidl_runtime_c_String had invalid data");
return "";
}
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 @@ -79,8 +77,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 Expand Up @@ -113,27 +111,27 @@ struct U16StringHelper;
template<>
struct U16StringHelper<rosidl_typesupport_introspection_c__MessageMembers>
{
using type = rosidl_generator_c__U16String;
using type = rosidl_runtime_c__U16String;

static std::u16string convert_to_std_u16string(void * data)
{
auto c_u16string = static_cast<rosidl_generator_c__U16String *>(data);
auto c_u16string = static_cast<rosidl_runtime_c__U16String *>(data);
if (!c_u16string) {
RCUTILS_LOG_ERROR_NAMED(
"rmw_dps_cpp",
"Failed to cast data as rosidl_generator_c__U16String");
"Failed to cast data as rosidl_runtime_c__U16String");
return u"";
}
if (!c_u16string->data) {
RCUTILS_LOG_ERROR_NAMED(
"rmw_dps_cpp",
"rosidl_generator_c_U16String had invalid data");
"rosidl_runtime_c_U16String had invalid data");
return u"";
}
return std::u16string(reinterpret_cast<char16_t *>(c_u16string->data));
}

static std::u16string convert_to_std_u16string(rosidl_generator_c__U16String & data)
static std::u16string convert_to_std_u16string(rosidl_runtime_c__U16String & data)
{
return std::u16string(reinterpret_cast<char16_t *>(data.data));
}
Expand All @@ -142,8 +140,8 @@ struct U16StringHelper<rosidl_typesupport_introspection_c__MessageMembers>
{
std::u16string str;
deser >> str;
rosidl_generator_c__U16String * c_str = static_cast<rosidl_generator_c__U16String *>(field);
rosidl_generator_c__U16String__assign(c_str, reinterpret_cast<const uint16_t *>(str.c_str()));
rosidl_runtime_c__U16String * c_str = static_cast<rosidl_runtime_c__U16String *>(field);
rosidl_runtime_c__U16String__assign(c_str, reinterpret_cast<const uint16_t *>(str.c_str()));
}
};

Expand Down
56 changes: 28 additions & 28 deletions rmw_dps_cpp/include/rmw_dps_cpp/TypeSupport_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include "rmw_dps_cpp/macros.hpp"

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

namespace rmw_dps_cpp
{
Expand All @@ -43,19 +43,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 @@ -75,7 +75,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 @@ -152,18 +152,18 @@ void serialize_field<std::string>(
}
ser << str;
} else {
// First, cast field to rosidl_generator_c
// First, cast field to rosidl_runtime_c
// Then convert to a std::string using StringHelper and serialize the std::string
std::vector<std::string> cpp_string_vector;
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) {
cpp_string_vector.push_back(
CStringHelper::convert_to_std_string(string_field[i]));
}
} else {
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) {
cpp_string_vector.push_back(
CStringHelper::convert_to_std_string(string_sequence_field.data[i]));
Expand All @@ -189,18 +189,18 @@ void serialize_field<std::u16string>(
}
ser << str;
} else {
// First, cast field to rosidl_generator_c
// First, cast field to rosidl_runtime_c
// Then convert to a std::u16string using U16StringHelper and serialize the std::u16string
std::vector<std::u16string> cpp_u16string_vector;
if (member->array_size_ && !member->is_upper_bound_) {
auto u16string_field = static_cast<rosidl_generator_c__U16String *>(field);
auto u16string_field = static_cast<rosidl_runtime_c__U16String *>(field);
for (size_t i = 0; i < member->array_size_; ++i) {
cpp_u16string_vector.push_back(
CU16StringHelper::convert_to_std_u16string(u16string_field[i]));
}
} else {
auto & u16string_sequence_field =
*reinterpret_cast<rosidl_generator_c__U16String__Sequence *>(field);
*reinterpret_cast<rosidl_runtime_c__U16String__Sequence *>(field);
for (size_t i = 0; i < u16string_sequence_field.size; ++i) {
cpp_u16string_vector.push_back(
CU16StringHelper::convert_to_std_u16string(u16string_sequence_field.data[i]));
Expand Down Expand Up @@ -396,27 +396,27 @@ void deserialize_field<std::string>(
deser >> cpp_string_vector;

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);
for (size_t i = 0; i < member->array_size_; ++i) {
if (!rosidl_generator_c__String__assign(&deser_field[i],
if (!rosidl_runtime_c__String__assign(&deser_field[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");
}
}
} else {
auto & string_sequence_field =
*reinterpret_cast<rosidl_generator_c__String__Sequence *>(field);
if (!rosidl_generator_c__String__Sequence__init(&string_sequence_field,
*reinterpret_cast<rosidl_runtime_c__String__Sequence *>(field);
if (!rosidl_runtime_c__String__Sequence__init(&string_sequence_field,
cpp_string_vector.size()))
{
throw std::runtime_error("unable to initialize rosidl_generator_c__String sequence");
throw std::runtime_error("unable to initialize rosidl_runtime_c__String sequence");
}
for (size_t i = 0; i < cpp_string_vector.size(); ++i) {
if (!rosidl_generator_c__String__assign(&string_sequence_field.data[i],
if (!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 @@ -439,27 +439,27 @@ void deserialize_field<std::u16string>(
deser >> cpp_u16string_vector;

if (member->array_size_ && !member->is_upper_bound_) {
auto deser_field = static_cast<rosidl_generator_c__U16String *>(field);
auto deser_field = static_cast<rosidl_runtime_c__U16String *>(field);
for (size_t i = 0; i < member->array_size_; ++i) {
if (!rosidl_generator_c__U16String__assign(&deser_field[i],
if (!rosidl_runtime_c__U16String__assign(&deser_field[i],
reinterpret_cast<const uint16_t *>(cpp_u16string_vector[i].c_str())))
{
throw std::runtime_error("unable to assign rosidl_generator_c__U16String");
throw std::runtime_error("unable to assign rosidl_runtime_c__U16String");
}
}
} else {
auto & u16string_sequence_field =
*reinterpret_cast<rosidl_generator_c__U16String__Sequence *>(field);
if (!rosidl_generator_c__U16String__Sequence__init(&u16string_sequence_field,
*reinterpret_cast<rosidl_runtime_c__U16String__Sequence *>(field);
if (!rosidl_runtime_c__U16String__Sequence__init(&u16string_sequence_field,
cpp_u16string_vector.size()))
{
throw std::runtime_error("unable to initialize rosidl_generator_c__U16String sequence");
throw std::runtime_error("unable to initialize rosidl_runtime_c__U16String sequence");
}
for (size_t i = 0; i < cpp_u16string_vector.size(); ++i) {
if (!rosidl_generator_c__U16String__assign(&u16string_sequence_field.data[i],
if (!rosidl_runtime_c__U16String__assign(&u16string_sequence_field.data[i],
reinterpret_cast<const uint16_t *>(cpp_u16string_vector[i].c_str())))
{
throw std::runtime_error("unable to assign rosidl_generator_c__U16String");
throw std::runtime_error("unable to assign rosidl_runtime_c__U16String");
}
}
}
Expand Down
6 changes: 3 additions & 3 deletions rmw_dps_cpp/include/rmw_dps_cpp/macros.hpp
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 * sequence) { \
rosidl_generator_c__ ## C_NAME ## __Sequence__fini(sequence); \
rosidl_runtime_c__ ## C_NAME ## __Sequence__fini(sequence); \
} \
\
static bool init(type * sequence, size_t size) { \
return rosidl_generator_c__ ## C_NAME ## __Sequence__init(sequence, size); \
return rosidl_runtime_c__ ## C_NAME ## __Sequence__init(sequence, size); \
} \
};

Expand Down
11 changes: 2 additions & 9 deletions rmw_dps_cpp/src/rmw_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -264,17 +264,14 @@ rmw_create_node(
const char * name,
const char * namespace_,
size_t domain_id,
const rmw_node_security_options_t * security_options,
bool localhost_only)
{
// TODO(malsbat): implement RMW_SECURITY_ENFORCEMENT_PERMISSIVE, ENFORCE
// TODO(malsbat): implement localhost_only
RCUTILS_LOG_DEBUG_NAMED(
"rmw_dps_cpp",
"%s(name=%s,namespace_=%s,domain_id=%zu,"
"security_options={enforce_security=%d,security_root_path=%s},localhost_only=%d)",
__FUNCTION__, name, namespace_, domain_id, security_options->enforce_security,
security_options->security_root_path, localhost_only);
"%s(name=%s,namespace_=%s,domain_id=%zu,localhost_only=%d)",
__FUNCTION__, name, namespace_, domain_id, localhost_only);

RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, nullptr);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
Expand All @@ -287,10 +284,6 @@ rmw_create_node(
RMW_SET_ERROR_MSG("name is null");
return nullptr;
}
if (!security_options) {
RMW_SET_ERROR_MSG("security_options is null");
return nullptr;
}

return create_node(context, name, namespace_, domain_id);
}
Expand Down
2 changes: 1 addition & 1 deletion rmw_dps_cpp/src/rmw_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ extern "C"
rmw_ret_t
rmw_init_publisher_allocation(
const rosidl_message_type_support_t * type_support,
const rosidl_message_bounds_t * message_bounds,
const rosidl_runtime_c__Sequence__bound * message_bounds,
rmw_publisher_allocation_t * allocation)
{
// Unused in current implementation.
Expand Down
12 changes: 6 additions & 6 deletions rmw_dps_cpp/src/rmw_request.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ rmw_send_request(
rmw_ret_t
rmw_take_request(
const rmw_service_t * service,
rmw_request_id_t * request_header,
rmw_service_info_t * request_header,
void * ros_request,
bool * taken)
{
Expand Down Expand Up @@ -108,16 +108,16 @@ rmw_take_request(
info->typesupport_identifier_);

// Get header
memset(request_header->writer_guid, 0, sizeof(request_header->writer_guid));
memset(request_header->request_id.writer_guid, 0, sizeof(request_header->request_id.writer_guid));
const DPS_UUID * uuid = DPS_PublicationGetUUID(pub.get());
if (uuid) {
memcpy(request_header->writer_guid, uuid, sizeof(DPS_UUID));
memcpy(request_header->request_id.writer_guid, uuid, sizeof(DPS_UUID));
}
request_header->sequence_number = DPS_PublicationGetSequenceNum(pub.get());

request_header->request_id.sequence_number = DPS_PublicationGetSequenceNum(pub.get());
*taken = true;

info->requests_.emplace(std::make_pair(*request_header, std::move(pub)));
info->requests_.emplace(std::make_pair(request_header->request_id, std::move(pub)));
}

return RMW_RET_OK;
Expand Down
8 changes: 4 additions & 4 deletions rmw_dps_cpp/src/rmw_response.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ extern "C"
rmw_ret_t
rmw_take_response(
const rmw_client_t * client,
rmw_request_id_t * request_header,
rmw_service_info_t * request_header,
void * ros_response,
bool * taken)
{
Expand Down Expand Up @@ -63,12 +63,12 @@ rmw_take_response(
info->typesupport_identifier_);

// Get header
memset(request_header->writer_guid, 0, sizeof(request_header->writer_guid));
memset(request_header->request_id.writer_guid, 0, sizeof(request_header->request_id.writer_guid));
const DPS_UUID * uuid = DPS_PublicationGetUUID(pub.get());
if (uuid) {
memcpy(request_header->writer_guid, uuid, sizeof(DPS_UUID));
memcpy(request_header->request_id.writer_guid, uuid, sizeof(DPS_UUID));
}
request_header->sequence_number = DPS_AckGetSequenceNum(pub.get());
request_header->request_id.sequence_number = DPS_AckGetSequenceNum(pub.get());

*taken = true;
}
Expand Down
2 changes: 1 addition & 1 deletion rmw_dps_cpp/src/rmw_serialize.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ rmw_deserialize(
rmw_ret_t
rmw_get_serialized_message_size(
const rosidl_message_type_support_t * /*type_support*/,
const rosidl_message_bounds_t * /*message_bounds*/,
const rosidl_runtime_c__Sequence__bound * /*message_bounds*/,
size_t * /*size*/)
{
RMW_SET_ERROR_MSG("unimplemented");
Expand Down
2 changes: 1 addition & 1 deletion rmw_dps_cpp/src/rmw_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ extern "C"
rmw_ret_t
rmw_init_subscription_allocation(
const rosidl_message_type_support_t * type_support,
const rosidl_message_bounds_t * message_bounds,
const rosidl_runtime_c__Sequence__bound * message_bounds,
rmw_subscription_allocation_t * allocation)
{
// Unused in current implementation.
Expand Down