update for Cyclone DDS changes and ROS2 changes

The changes in this commit make it compile with ROS2 Crystal Clemmys and
current Cyclone DDS.  The RMW interface of ROS2 was modified in some
ways and extended in some other ways since Bouncy Bolson; and similarly,
Cyclone now has a somewhat reasonable interface for custom sample
representations and serialization, but the code in this commit probably
contains mistakes in using it.

Therefore, the expectation should be that this doesn't actually work
just yet, though it probably is quite close.  As the old state wouldn't
build at all with any version of Cyclone DDS except the early commits,
this is significant progress already.
This commit is contained in:
Erik Boasson 2019-04-29 09:33:13 +02:00
parent 40a042c6dc
commit c9a23a9b8a
9 changed files with 1202 additions and 1079 deletions

View file

@ -52,12 +52,11 @@ include_directories(include)
add_library(rmw_cyclonedds_cpp
src/namespace_prefix.cpp
src/rmw_node.cpp
src/serdata.cpp
src/serdes.cpp
)
idlc_generate(rmw_cyclonedds_topic_lib src/rmw_cyclonedds_topic.idl)
target_link_libraries(rmw_cyclonedds_cpp
rmw_cyclonedds_topic_lib CycloneDDS::ddsc)
target_link_libraries(rmw_cyclonedds_cpp CycloneDDS::ddsc)
ament_target_dependencies(rmw_cyclonedds_cpp
"rcutils"
@ -72,7 +71,7 @@ configure_rmw_library(rmw_cyclonedds_cpp)
# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
target_compile_definitions(${PROJECT_NAME}
PRIVATE "RMW_CYCLONEDDS_CPP_BUILDING_LIBRARY")
PRIVATE "RMW_CYCLONEDDS_CPP_BUILDING_LIBRARY")
ament_export_include_directories(include)
ament_export_libraries(rmw_cyclonedds_cpp)

View file

@ -59,13 +59,13 @@ struct StringHelper<rosidl_typesupport_introspection_c__MessageMembers>
if (!c_string) {
RCUTILS_LOG_ERROR_NAMED(
"rmw_cyclonedds_cpp",
"Failed to cast data as rosidl_generator_c__String")
"Failed to cast data as rosidl_generator_c__String");
return "";
}
if (!c_string->data) {
RCUTILS_LOG_ERROR_NAMED(
"rmw_cyclonedds_cpp",
"rosidl_generator_c_String had invalid data")
"rosidl_generator_c_String had invalid data");
return "";
}
return std::string(c_string->data);

View file

@ -30,7 +30,7 @@
#include "rosidl_typesupport_introspection_c/message_introspection.h"
#include "rosidl_typesupport_introspection_c/service_introspection.h"
#include "rosidl_generator_c/primitives_array_functions.h"
#include "rosidl_generator_c/primitives_sequence_functions.h"
#include "serdes.hpp"
@ -38,37 +38,37 @@ namespace rmw_cyclonedds_cpp
{
template<typename T>
struct GenericCArray;
struct GenericCSequence;
// multiple definitions of ambiguous primitive types
SPECIALIZE_GENERIC_C_ARRAY(bool, bool)
SPECIALIZE_GENERIC_C_ARRAY(byte, uint8_t)
SPECIALIZE_GENERIC_C_ARRAY(char, char)
SPECIALIZE_GENERIC_C_ARRAY(float32, float)
SPECIALIZE_GENERIC_C_ARRAY(float64, double)
SPECIALIZE_GENERIC_C_ARRAY(int8, int8_t)
SPECIALIZE_GENERIC_C_ARRAY(int16, int16_t)
SPECIALIZE_GENERIC_C_ARRAY(uint16, uint16_t)
SPECIALIZE_GENERIC_C_ARRAY(int32, int32_t)
SPECIALIZE_GENERIC_C_ARRAY(uint32, uint32_t)
SPECIALIZE_GENERIC_C_ARRAY(int64, int64_t)
SPECIALIZE_GENERIC_C_ARRAY(uint64, uint64_t)
SPECIALIZE_GENERIC_C_SEQUENCE(bool, bool)
SPECIALIZE_GENERIC_C_SEQUENCE(byte, uint8_t)
SPECIALIZE_GENERIC_C_SEQUENCE(char, char)
SPECIALIZE_GENERIC_C_SEQUENCE(float32, float)
SPECIALIZE_GENERIC_C_SEQUENCE(float64, double)
SPECIALIZE_GENERIC_C_SEQUENCE(int8, int8_t)
SPECIALIZE_GENERIC_C_SEQUENCE(int16, int16_t)
SPECIALIZE_GENERIC_C_SEQUENCE(uint16, uint16_t)
SPECIALIZE_GENERIC_C_SEQUENCE(int32, int32_t)
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__Array
typedef struct rosidl_generator_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__Array;
} rosidl_generator_c__void__Sequence;
inline
bool
rosidl_generator_c__void__Array__init(
rosidl_generator_c__void__Array * array, size_t size, size_t member_size)
rosidl_generator_c__void__Sequence__init(
rosidl_generator_c__void__Sequence * sequence, size_t size, size_t member_size)
{
if (!array) {
if (!sequence) {
return false;
}
void * data = nullptr;
@ -78,31 +78,31 @@ rosidl_generator_c__void__Array__init(
return false;
}
}
array->data = data;
array->size = size;
array->capacity = size;
sequence->data = data;
sequence->size = size;
sequence->capacity = size;
return true;
}
inline
void
rosidl_generator_c__void__Array__fini(rosidl_generator_c__void__Array * array)
rosidl_generator_c__void__Sequence__fini(rosidl_generator_c__void__Sequence * sequence)
{
if (!array) {
if (!sequence) {
return;
}
if (array->data) {
if (sequence->data) {
// ensure that data and capacity values are consistent
assert(array->capacity > 0);
// finalize all array elements
free(array->data);
array->data = nullptr;
array->size = 0;
array->capacity = 0;
assert(sequence->capacity > 0);
// finalize all sequence elements
free(sequence->data);
sequence->data = nullptr;
sequence->size = 0;
sequence->capacity = 0;
} else {
// ensure that data, size, and capacity values are consistent
assert(0 == array->size);
assert(0 == array->capacity);
assert(0 == sequence->size);
assert(0 == sequence->capacity);
}
}
@ -231,7 +231,7 @@ void serialize_field(
} else if (member->array_size_ && !member->is_upper_bound_) {
ser.serializeA(static_cast<T *>(field), member->array_size_);
} else {
auto & data = *reinterpret_cast<typename GenericCArray<T>::type *>(field);
auto & data = *reinterpret_cast<typename GenericCSequence<T>::type *>(field);
ser.serializeS(reinterpret_cast<T *>(data.data), data.size);
}
}
@ -264,7 +264,7 @@ void serialize_field<std::string>(
ser.serialize(tmpstring);
}
} else {
auto & string_array_field = *reinterpret_cast<rosidl_generator_c__String__Array *>(field);
auto & string_array_field = *reinterpret_cast<rosidl_generator_c__String__Sequence *>(field);
std::vector<std::string> cpp_string_vector;
for (size_t i = 0; i < string_array_field.size; ++i) {
cpp_string_vector.push_back(
@ -300,12 +300,12 @@ size_t get_array_size_and_assign_field(
void * & subros_message,
size_t, size_t)
{
auto tmparray = static_cast<rosidl_generator_c__void__Array *>(field);
if (member->is_upper_bound_ && tmparray->size > member->array_size_) {
auto tmpsequence = static_cast<rosidl_generator_c__void__Sequence *>(field);
if (member->is_upper_bound_ && tmpsequence->size > member->array_size_) {
throw std::runtime_error("vector overcomes the maximum length");
}
subros_message = reinterpret_cast<void *>(tmparray->data);
return tmparray->size;
subros_message = reinterpret_cast<void *>(tmpsequence->data);
return tmpsequence->size;
}
template<typename MembersType>
@ -434,10 +434,10 @@ void deserialize_field(
} else if (member->array_size_ && !member->is_upper_bound_) {
deser.deserializeA(static_cast<T *>(field), member->array_size_);
} else {
auto & data = *reinterpret_cast<typename GenericCArray<T>::type *>(field);
auto & data = *reinterpret_cast<typename GenericCSequence<T>::type *>(field);
int32_t dsize = 0;
deser >> dsize;
GenericCArray<T>::init(&data, dsize);
GenericCSequence<T>::init(&data, dsize);
deser.deserializeA(reinterpret_cast<T *>(data.data), dsize);
}
}
@ -469,8 +469,8 @@ inline void deserialize_field<std::string>(
std::vector<std::string> cpp_string_vector;
deser >> cpp_string_vector;
auto & string_array_field = *reinterpret_cast<rosidl_generator_c__String__Array *>(field);
if (!rosidl_generator_c__String__Array__init(&string_array_field, cpp_string_vector.size())) {
auto & string_array_field = *reinterpret_cast<rosidl_generator_c__String__Sequence *>(field);
if (!rosidl_generator_c__String__Sequence__init(&string_array_field, cpp_string_vector.size())) {
throw std::runtime_error("unable to initialize rosidl_generator_c__String array");
}
@ -521,8 +521,8 @@ inline size_t get_submessage_array_deserialize(
// Deserialize length
uint32_t vsize = 0;
deser >> vsize;
auto tmparray = static_cast<rosidl_generator_c__void__Array *>(field);
rosidl_generator_c__void__Array__init(tmparray, vsize, sub_members_size);
auto tmparray = static_cast<rosidl_generator_c__void__Sequence *>(field);
rosidl_generator_c__void__Sequence__init(tmparray, vsize, sub_members_size);
subros_message = reinterpret_cast<void *>(tmparray->data);
return vsize;
}

View file

@ -18,18 +18,18 @@
#include <limits>
#include <string>
#define SPECIALIZE_GENERIC_C_ARRAY(C_NAME, C_TYPE) \
#define SPECIALIZE_GENERIC_C_SEQUENCE(C_NAME, C_TYPE) \
template<> \
struct GenericCArray<C_TYPE> \
struct GenericCSequence<C_TYPE> \
{ \
using type = rosidl_generator_c__ ## C_NAME ## __Array; \
using type = rosidl_generator_c__ ## C_NAME ## __Sequence; \
\
static void fini(type * array) { \
rosidl_generator_c__ ## C_NAME ## __Array__fini(array); \
rosidl_generator_c__ ## C_NAME ## __Sequence__fini(array); \
} \
\
static bool init(type * array, size_t size) { \
return rosidl_generator_c__ ## C_NAME ## __Array__init(array, size); \
return rosidl_generator_c__ ## C_NAME ## __Sequence__init(array, size); \
} \
};

View file

@ -0,0 +1,55 @@
// Copyright 2019 ADLINK Technology
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef SERDATA_HPP
#define SERDATA_HPP
#include "dds/ddsi/ddsi_sertopic.h"
#include "dds/ddsi/ddsi_serdata.h"
struct CddsTypeSupport {
void *type_support_;
const char *typesupport_identifier_;
};
struct sertopic_rmw : ddsi_sertopic {
CddsTypeSupport type_support;
bool is_request_header;
std::string cpp_name;
std::string cpp_type_name;
std::string cpp_name_type_name;
};
struct serdata_rmw : ddsi_serdata {
/* first two bytes of data is CDR encoding
second two bytes are encoding options */
std::vector<unsigned char> data;
};
typedef struct cdds_request_header {
uint64_t guid;
int64_t seq;
} cdds_request_header_t;
typedef struct cdds_request_wrapper {
cdds_request_header_t header;
void *data;
} cdds_request_wrapper_t;
void *create_message_type_support (const void *untyped_members, const char *typesupport_identifier);
void *create_request_type_support (const void *untyped_members, const char *typesupport_identifier);
void *create_response_type_support (const void *untyped_members, const char *typesupport_identifier);
struct sertopic_rmw *create_sertopic (const char *topicname, const char *type_support_identifier, void *type_support, bool is_request_header);
#endif

View file

@ -20,235 +20,217 @@
#include <vector>
#include <type_traits>
#include "ddsc/dds.h"
extern "C" {
struct serstate;
struct serdata;
struct sertopic;
struct serdata *ddsi_serdata_ref(struct serdata *serdata);
void ddsi_serdata_unref(struct serdata *serdata);
struct serstate *ddsi_serstate_new(const struct sertopic *topic);
struct serdata *ddsi_serstate_fix(struct serstate *st);
void ddsi_serstate_release(struct serstate *st);
void *ddsi_serstate_append(struct serstate *st, size_t n);
void *ddsi_serstate_append_align(struct serstate *st, size_t a);
void *ddsi_serstate_append_aligned(struct serstate *st, size_t n, size_t a);
void ddsi_serdata_getblob(void **raw, size_t *sz, struct serdata *serdata);
}
template<class T>
struct simpletype : std::integral_constant< bool, std::is_arithmetic<T>::value && !std::is_same<bool, T>::value > {};
template<class T>
struct complextype : std::integral_constant< bool, !(std::is_arithmetic<T>::value && !std::is_same<bool, T>::value) > {};
template<unsigned N> struct rank : rank<N-1> {};
template<> struct rank<0> {};
class cycser {
public:
cycser(struct sertopic *topic);
cycser() = delete;
~cycser();
cycser& fix();
cycser& ref();
void unref();
struct serdata *data();
cycser (std::vector<unsigned char>& dst_);
cycser () = delete;
inline cycser& operator<<(bool x) { serialize(x); return *this; }
inline cycser& operator<<(char x) { serialize(x); return *this; }
inline cycser& operator<<(uint8_t x) { serialize(x); return *this; }
inline cycser& operator<<(int16_t x) { serialize(x); return *this; }
inline cycser& operator<<(uint16_t x) { serialize(x); return *this; }
inline cycser& operator<<(int32_t x) { serialize(x); return *this; }
inline cycser& operator<<(uint32_t x) { serialize(x); return *this; }
inline cycser& operator<<(int64_t x) { serialize(x); return *this; }
inline cycser& operator<<(uint64_t x) { serialize(x); return *this; }
inline cycser& operator<<(float x) { serialize(x); return *this; }
inline cycser& operator<<(double x) { serialize(x); return *this; }
inline cycser& operator<<(const char *x) { serialize(x); return *this; }
inline cycser& operator<<(const std::string& x) { serialize(x); return *this; }
template<class T> inline cycser& operator<<(const std::vector<T>& x) { serialize(x); return *this; }
template<class T, size_t S> inline cycser& operator<<(const std::array<T, S>& x) { serialize(x); return *this; }
inline cycser& operator<< (bool x) { serialize (x); return *this; }
inline cycser& operator<< (char x) { serialize (x); return *this; }
inline cycser& operator<< (uint8_t x) { serialize (x); return *this; }
inline cycser& operator<< (int16_t x) { serialize (x); return *this; }
inline cycser& operator<< (uint16_t x) { serialize (x); return *this; }
inline cycser& operator<< (int32_t x) { serialize (x); return *this; }
inline cycser& operator<< (uint32_t x) { serialize (x); return *this; }
inline cycser& operator<< (int64_t x) { serialize (x); return *this; }
inline cycser& operator<< (uint64_t x) { serialize (x); return *this; }
inline cycser& operator<< (float x) { serialize (x); return *this; }
inline cycser& operator<< (double x) { serialize (x); return *this; }
inline cycser& operator<< (const char *x) { serialize (x); return *this; }
inline cycser& operator<< (const std::string& x) { serialize (x); return *this; }
template<class T> inline cycser& operator<< (const std::vector<T>& x) { serialize (x); return *this; }
template<class T, size_t S> inline cycser& operator<< (const std::array<T, S>& x) { serialize (x); return *this; }
#define SIMPLE(T) inline void serialize(T x) { \
T *p = (T *)ddsi_serstate_append_aligned(st, sizeof(T), sizeof(T)); \
*p = x; \
}
SIMPLE(char);
SIMPLE(unsigned char);
SIMPLE(int16_t);
SIMPLE(uint16_t);
SIMPLE(int32_t);
SIMPLE(uint32_t);
SIMPLE(int64_t);
SIMPLE(uint64_t);
SIMPLE(float);
SIMPLE(double);
#define SIMPLE(T) inline void serialize (T x) { \
if ((off % sizeof (T)) != 0) { \
off += sizeof (T) - (off % sizeof (T)); \
} \
reserve (off + sizeof (T)); \
*(T *) (data () + off) = x; \
off += sizeof (T); \
}
SIMPLE (char);
SIMPLE (unsigned char);
SIMPLE (int16_t);
SIMPLE (uint16_t);
SIMPLE (int32_t);
SIMPLE (uint32_t);
SIMPLE (int64_t);
SIMPLE (uint64_t);
SIMPLE (float);
SIMPLE (double);
#undef SIMPLE
inline void serialize(bool x) {
serialize(static_cast<unsigned char>(x));
}
inline void serialize(const char *x)
{
size_t sz = strlen(x) + 1;
serialize(static_cast<uint32_t>(sz));
char *p = (char *)ddsi_serstate_append(st, sz);
memcpy(p, x, sz);
}
inline void serialize(const std::string& x)
{
size_t sz = x.size();
serialize(static_cast<uint32_t>(sz+1));
char *p = (char *)ddsi_serstate_append(st, sz+1);
memcpy(p, x.data(), sz);
p[sz] = 0;
}
inline void serialize (bool x) {
serialize (static_cast<unsigned char> (x));
}
inline void serialize (const char *x)
{
size_t sz = strlen (x) + 1;
serialize (static_cast<uint32_t> (sz));
reserve (off + sz);
memcpy (data () + off, x, sz);
off += sz;
}
inline void serialize (const std::string& x)
{
size_t sz = x.size () + 1;
serialize (static_cast<uint32_t> (sz));
reserve (off + sz);
memcpy (data () + off, x.data (), sz - 1);
*(data () + off + sz - 1) = 0;
}
#define SIMPLEA(T) inline void serializeA(const T *x, size_t cnt) { \
void *p = (void *)ddsi_serstate_append_aligned(st, (cnt) * sizeof(T), sizeof(T)); \
memcpy(p, (void *)x, (cnt) * sizeof(T)); \
}
SIMPLEA(char);
SIMPLEA(unsigned char);
SIMPLEA(int16_t);
SIMPLEA(uint16_t);
SIMPLEA(int32_t);
SIMPLEA(uint32_t);
SIMPLEA(int64_t);
SIMPLEA(uint64_t);
SIMPLEA(float);
SIMPLEA(double);
#define SIMPLEA(T) inline void serializeA (const T *x, size_t cnt) { \
if ((off % sizeof (T)) != 0) { \
off += sizeof (T) - (off % sizeof (T)); \
} \
reserve (off + cnt * sizeof (T)); \
memcpy (data () + off, (void *) x, cnt * sizeof (T)); \
off += cnt * sizeof (T); \
}
SIMPLEA (char);
SIMPLEA (unsigned char);
SIMPLEA (int16_t);
SIMPLEA (uint16_t);
SIMPLEA (int32_t);
SIMPLEA (uint32_t);
SIMPLEA (int64_t);
SIMPLEA (uint64_t);
SIMPLEA (float);
SIMPLEA (double);
#undef SIMPLEA
template<class T> inline void serializeA(const T *x, size_t cnt) {
for (size_t i = 0; i < cnt; i++) serialize(x[i]);
}
template<class T> inline void serializeA (const T *x, size_t cnt) {
for (size_t i = 0; i < cnt; i++) serialize (x[i]);
}
template<class T> inline void serialize(const std::vector<T>& x)
{
serialize(static_cast<uint32_t>(x.size()));
if (x.size() > 0) serializeA(x.data(), x.size());
}
inline void serialize(const std::vector<bool>& x) {
serialize(static_cast<uint32_t>(x.size()));
for (auto&& i : x) serialize(i);
}
template<class T> inline void serialize (const std::vector<T>& x)
{
serialize (static_cast<uint32_t> (x.size ()));
if (x.size () > 0) serializeA (x.data (), x.size ());
}
inline void serialize (const std::vector<bool>& x) {
serialize (static_cast<uint32_t> (x.size ()));
for (auto&& i : x) serialize (i);
}
template<class T> inline void serializeS(const T *x, size_t cnt)
{
serialize(static_cast<uint32_t>(cnt));
if (cnt > 0) serializeA(x, cnt);
}
template<class T> inline void serializeS (const T *x, size_t cnt)
{
serialize (static_cast<uint32_t> (cnt));
if (cnt > 0) serializeA (x, cnt);
}
private:
struct serstate *st;
struct serdata *sd;
inline void reserve (size_t n) { dst.reserve (n + 4); }
inline unsigned char *data () { return dst.data () + 4; }
std::vector<unsigned char>& dst;
size_t off;
};
class cycdeser {
public:
// FIXME: byteswapping
cycdeser(const void *data, size_t size);
cycdeser() = delete;
~cycdeser();
// FIXME: byteswapping
cycdeser (const void *data, size_t size);
cycdeser () = delete;
inline cycdeser& operator>>(bool& x) { deserialize(x); return *this; }
inline cycdeser& operator>>(char& x) { deserialize(x); return *this; }
inline cycdeser& operator>>(uint8_t& x) { deserialize(x); return *this; }
inline cycdeser& operator>>(int16_t& x) { deserialize(x); return *this; }
inline cycdeser& operator>>(uint16_t& x) { deserialize(x); return *this; }
inline cycdeser& operator>>(int32_t& x) { deserialize(x); return *this; }
inline cycdeser& operator>>(uint32_t& x) { deserialize(x); return *this; }
inline cycdeser& operator>>(int64_t& x) { deserialize(x); return *this; }
inline cycdeser& operator>>(uint64_t& x) { deserialize(x); return *this; }
inline cycdeser& operator>>(float& x) { deserialize(x); return *this; }
inline cycdeser& operator>>(double& x) { deserialize(x); return *this; }
inline cycdeser& operator>>(char *& x) { deserialize(x); return *this; }
inline cycdeser& operator>>(std::string& x) { deserialize(x); return *this; }
template<class T> inline cycdeser& operator>>(std::vector<T>& x) { deserialize(x); return *this; }
template<class T, size_t S> inline cycdeser& operator>>(std::array<T, S>& x) { deserialize(x); return *this; }
inline cycdeser& operator>> (bool& x) { deserialize (x); return *this; }
inline cycdeser& operator>> (char& x) { deserialize (x); return *this; }
inline cycdeser& operator>> (uint8_t& x) { deserialize (x); return *this; }
inline cycdeser& operator>> (int16_t& x) { deserialize (x); return *this; }
inline cycdeser& operator>> (uint16_t& x) { deserialize (x); return *this; }
inline cycdeser& operator>> (int32_t& x) { deserialize (x); return *this; }
inline cycdeser& operator>> (uint32_t& x) { deserialize (x); return *this; }
inline cycdeser& operator>> (int64_t& x) { deserialize (x); return *this; }
inline cycdeser& operator>> (uint64_t& x) { deserialize (x); return *this; }
inline cycdeser& operator>> (float& x) { deserialize (x); return *this; }
inline cycdeser& operator>> (double& x) { deserialize (x); return *this; }
inline cycdeser& operator>> (char *& x) { deserialize (x); return *this; }
inline cycdeser& operator>> (std::string& x) { deserialize (x); return *this; }
template<class T> inline cycdeser& operator>> (std::vector<T>& x) { deserialize (x); return *this; }
template<class T, size_t S> inline cycdeser& operator>> (std::array<T, S>& x) { deserialize (x); return *this; }
#define SIMPLE(T) inline void deserialize(T& x) { \
align(sizeof(x)); \
x = *reinterpret_cast<const T *>(data); \
data += sizeof(x); \
}
SIMPLE(char);
SIMPLE(unsigned char);
SIMPLE(int16_t);
SIMPLE(uint16_t);
SIMPLE(int32_t);
SIMPLE(uint32_t);
SIMPLE(int64_t);
SIMPLE(uint64_t);
SIMPLE(float);
SIMPLE(double);
#define SIMPLE(T) inline void deserialize (T& x) { \
align (sizeof (x)); \
x = *reinterpret_cast<const T *> (data + pos); \
pos += sizeof (x); \
}
SIMPLE (char);
SIMPLE (unsigned char);
SIMPLE (int16_t);
SIMPLE (uint16_t);
SIMPLE (int32_t);
SIMPLE (uint32_t);
SIMPLE (int64_t);
SIMPLE (uint64_t);
SIMPLE (float);
SIMPLE (double);
#undef SIMPLE
inline void deserialize(bool& x) {
unsigned char z; deserialize(z); x = (z != 0);
}
inline uint32_t deserialize32() {
uint32_t sz; deserialize(sz); return sz;
}
inline void deserialize(char *& x) {
const uint32_t sz = deserialize32(); x = (char *)malloc(sz); memcpy(x, data, sz); data += sz;
}
inline void deserialize(std::string& x) {
const uint32_t sz = deserialize32(); x = std::string(data, sz-1); data += sz;
}
inline void deserialize (bool& x) {
unsigned char z; deserialize (z); x = (z != 0);
}
inline uint32_t deserialize32 () {
uint32_t sz; deserialize (sz); return sz;
}
inline void deserialize (char *& x) {
const uint32_t sz = deserialize32 ();
x = (char *) malloc (sz);
memcpy (x, data + pos, sz);
pos += sz;
}
inline void deserialize (std::string& x) {
const uint32_t sz = deserialize32 ();
x = std::string (data + pos, sz-1);
pos += sz;
}
#define SIMPLEA(T) inline void deserializeA(T *x, size_t cnt) { \
align(sizeof(T)); \
memcpy((void *)x, (void *)data, (cnt) * sizeof(T)); \
data += (cnt) * sizeof(T); \
}
SIMPLEA(char);
SIMPLEA(unsigned char);
SIMPLEA(int16_t);
SIMPLEA(uint16_t);
SIMPLEA(int32_t);
SIMPLEA(uint32_t);
SIMPLEA(int64_t);
SIMPLEA(uint64_t);
SIMPLEA(float);
SIMPLEA(double);
#define SIMPLEA(T) inline void deserializeA (T *x, size_t cnt) { \
align (sizeof (T)); \
memcpy ((void *) x, (void *) (data + pos), (cnt) * sizeof (T)); \
pos += (cnt) * sizeof (T); \
}
SIMPLEA (char);
SIMPLEA (unsigned char);
SIMPLEA (int16_t);
SIMPLEA (uint16_t);
SIMPLEA (int32_t);
SIMPLEA (uint32_t);
SIMPLEA (int64_t);
SIMPLEA (uint64_t);
SIMPLEA (float);
SIMPLEA (double);
#undef SIMPLEA
template<class T> inline void deserializeA(T *x, size_t cnt) {
for (size_t i = 0; i < cnt; i++) deserialize(x[i]);
}
template<class T> inline void deserializeA (T *x, size_t cnt) {
for (size_t i = 0; i < cnt; i++) deserialize (x[i]);
}
template<class T> inline void deserialize(std::vector<T>& x) {
const uint32_t sz = deserialize32();
x.resize(sz);
deserializeA(x.data(), sz);
}
inline void deserialize(std::vector<bool>& x) {
const uint32_t sz = deserialize32();
x.resize(sz);
for (auto&& i : x) i = (data[i] != 0);
data += sz;
}
template<class T, size_t S> inline void deserialize(std::array<T, S>& x) {
deserializeA(x.data(), x.size());
}
template<class T> inline void deserialize (std::vector<T>& x) {
const uint32_t sz = deserialize32 ();
x.resize (sz);
deserializeA (x.data (), sz);
}
inline void deserialize (std::vector<bool>& x) {
const uint32_t sz = deserialize32 ();
x.resize (sz);
for (auto&& i : x) i = ((data + pos)[i] != 0);
pos += sz;
}
template<class T, size_t S> inline void deserialize (std::array<T, S>& x) {
deserializeA (x.data (), x.size ());
}
private:
inline void align(size_t a)
{
const uintptr_t x = reinterpret_cast<uintptr_t>(data);
if ((x % a) != 0) {
const uintptr_t pad = a - (x % a);
data = reinterpret_cast<const char *>(x + pad);
inline void align (size_t a)
{
if ((pos % a) != 0) {
pos += a - (pos % a);
}
}
}
const char *data;
size_t pos;
size_t lim; // ignored for now ... better provide correct input
const char *data;
size_t pos;
size_t lim; // ignored for now ... better provide correct input
};
#endif

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,306 @@
// Copyright 2019 ADLINK Technology
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <vector>
#include "rmw/error_handling.h"
#include "rmw_cyclonedds_cpp/MessageTypeSupport.hpp"
#include "rmw_cyclonedds_cpp/ServiceTypeSupport.hpp"
#include "rmw_cyclonedds_cpp/serdes.hpp"
#include "rmw_cyclonedds_cpp/serdata.hpp"
#include "dds/ddsi/ddsi_iid.h"
#include "dds/ddsi/q_radmin.h"
using MessageTypeSupport_c = rmw_cyclonedds_cpp::MessageTypeSupport<rosidl_typesupport_introspection_c__MessageMembers>;
using MessageTypeSupport_cpp = rmw_cyclonedds_cpp::MessageTypeSupport<rosidl_typesupport_introspection_cpp::MessageMembers>;
using RequestTypeSupport_c = rmw_cyclonedds_cpp::RequestTypeSupport<rosidl_typesupport_introspection_c__ServiceMembers, rosidl_typesupport_introspection_c__MessageMembers>;
using RequestTypeSupport_cpp = rmw_cyclonedds_cpp::RequestTypeSupport<rosidl_typesupport_introspection_cpp::ServiceMembers, rosidl_typesupport_introspection_cpp::MessageMembers>;
using ResponseTypeSupport_c = rmw_cyclonedds_cpp::ResponseTypeSupport<rosidl_typesupport_introspection_c__ServiceMembers, rosidl_typesupport_introspection_c__MessageMembers>;
using ResponseTypeSupport_cpp = rmw_cyclonedds_cpp::ResponseTypeSupport<rosidl_typesupport_introspection_cpp::ServiceMembers, rosidl_typesupport_introspection_cpp::MessageMembers>;
static bool using_introspection_c_typesupport (const char *typesupport_identifier)
{
return typesupport_identifier == rosidl_typesupport_introspection_c__identifier;
}
static bool using_introspection_cpp_typesupport (const char *typesupport_identifier)
{
return typesupport_identifier == rosidl_typesupport_introspection_cpp::typesupport_identifier;
}
void *create_message_type_support (const void *untyped_members, const char *typesupport_identifier)
{
if (using_introspection_c_typesupport (typesupport_identifier)) {
auto members = static_cast<const rosidl_typesupport_introspection_c__MessageMembers *> (untyped_members);
return new MessageTypeSupport_c (members);
} else if (using_introspection_cpp_typesupport (typesupport_identifier)) {
auto members = static_cast<const rosidl_typesupport_introspection_cpp::MessageMembers *> (untyped_members);
return new MessageTypeSupport_cpp (members);
}
RMW_SET_ERROR_MSG ("Unknown typesupport identifier");
return nullptr;
}
void *create_request_type_support (const void *untyped_members, const char *typesupport_identifier)
{
if (using_introspection_c_typesupport (typesupport_identifier)) {
auto members = static_cast<const rosidl_typesupport_introspection_c__ServiceMembers *> (untyped_members);
return new RequestTypeSupport_c (members);
} else if (using_introspection_cpp_typesupport (typesupport_identifier)) {
auto members = static_cast<const rosidl_typesupport_introspection_cpp::ServiceMembers *> (untyped_members);
return new RequestTypeSupport_cpp (members);
}
RMW_SET_ERROR_MSG ("Unknown typesupport identifier");
return nullptr;
}
void *create_response_type_support (const void *untyped_members, const char *typesupport_identifier)
{
if (using_introspection_c_typesupport (typesupport_identifier)) {
auto members = static_cast<const rosidl_typesupport_introspection_c__ServiceMembers *> (untyped_members);
return new ResponseTypeSupport_c (members);
} else if (using_introspection_cpp_typesupport (typesupport_identifier)) {
auto members = static_cast<const rosidl_typesupport_introspection_cpp::ServiceMembers *> (untyped_members);
return new ResponseTypeSupport_cpp (members);
}
RMW_SET_ERROR_MSG ("Unknown typesupport identifier");
return nullptr;
}
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wc99-extensions"
static uint32_t serdata_rmw_size (const struct ddsi_serdata *dcmn)
{
const struct serdata_rmw *d = static_cast<const struct serdata_rmw *> (dcmn);
return d->data.size ();
}
static void serdata_rmw_free (struct ddsi_serdata *dcmn)
{
const struct serdata_rmw *d = static_cast<const struct serdata_rmw *> (dcmn);
delete d;
}
static struct serdata_rmw *new_serdata_rmw (const struct ddsi_sertopic *topic, enum ddsi_serdata_kind kind)
{
struct serdata_rmw *sd = new serdata_rmw;
ddsi_serdata_init (sd, topic, kind);
return sd;
}
static struct ddsi_serdata *serdata_rmw_from_ser (const struct ddsi_sertopic *topic, enum ddsi_serdata_kind kind, const struct nn_rdata *fragchain, size_t size)
{
struct serdata_rmw *d = new_serdata_rmw (topic, kind);
uint32_t off = 0;
assert (fragchain->min == 0);
assert (fragchain->maxp1 >= off); /* CDR header must be in first fragment */
d->data.reserve (size);
while (fragchain) {
if (fragchain->maxp1 > off) {
/* only copy if this fragment adds data */
const unsigned char *payload = NN_RMSG_PAYLOADOFF (fragchain->rmsg, NN_RDATA_PAYLOAD_OFF (fragchain));
d->data.insert (d->data.end (), payload + off - fragchain->min, payload + fragchain->maxp1 - fragchain->min);
off = fragchain->maxp1;
}
fragchain = fragchain->nextfrag;
}
return d;
}
static struct ddsi_serdata *serdata_rmw_from_keyhash (const struct ddsi_sertopic *topic, const struct nn_keyhash *keyhash __attribute__ ((unused)))
{
/* there is no key field, so from_keyhash is trivial */
return new_serdata_rmw (topic, SDK_KEY);
}
static struct ddsi_serdata *serdata_rmw_from_sample (const struct ddsi_sertopic *topiccmn, enum ddsi_serdata_kind kind, const void *sample)
{
const struct sertopic_rmw *topic = static_cast<const struct sertopic_rmw *> (topiccmn);
struct serdata_rmw *d = new_serdata_rmw (topic, kind);
if (kind != SDK_DATA) {
/* ROS2 doesn't do keys, so SDK_KEY is trivial */
} else if (!topic->is_request_header) {
cycser sd (d->data);
if (using_introspection_c_typesupport (topic->type_support.typesupport_identifier_)) {
auto typed_typesupport = static_cast<MessageTypeSupport_c *> (topic->type_support.type_support_);
(void) typed_typesupport->serializeROSmessage (sample, sd, nullptr);
} else if (using_introspection_cpp_typesupport (topic->type_support.typesupport_identifier_)) {
auto typed_typesupport = static_cast<MessageTypeSupport_cpp *> (topic->type_support.type_support_);
(void) typed_typesupport->serializeROSmessage (sample, sd, nullptr);
}
} else {
/* The "prefix" lambda is there to inject the service invocation header data into the CDR
stream -- I haven't checked how it is done in the official RMW implementations, so it is
probably incompatible. */
const cdds_request_wrapper_t *wrap = static_cast<const cdds_request_wrapper_t *> (sample);
auto prefix = [wrap](cycser& ser) { ser << wrap->header.guid; ser << wrap->header.seq; };
cycser sd (d->data);
if (using_introspection_c_typesupport (topic->type_support.typesupport_identifier_)) {
auto typed_typesupport = static_cast<MessageTypeSupport_c *> (topic->type_support.type_support_);
(void) typed_typesupport->serializeROSmessage (wrap->data, sd, prefix);
} else if (using_introspection_cpp_typesupport (topic->type_support.typesupport_identifier_)) {
auto typed_typesupport = static_cast<MessageTypeSupport_cpp *> (topic->type_support.type_support_);
(void) typed_typesupport->serializeROSmessage (wrap->data, sd, prefix);
}
}
return d;
}
static struct ddsi_serdata *serdata_rmw_to_topicless (const struct ddsi_serdata *dcmn)
{
const struct serdata_rmw *d = static_cast<const struct serdata_rmw *> (dcmn);
struct serdata_rmw *d1 = new_serdata_rmw (d->topic, SDK_KEY);
d1->topic = nullptr;
return d1;
}
static void serdata_rmw_to_ser (const struct ddsi_serdata *dcmn, size_t off, size_t sz, void *buf)
{
const struct serdata_rmw *d = static_cast<const struct serdata_rmw *> (dcmn);
memcpy (buf, (char *) d->data.data () + off, sz);
}
static struct ddsi_serdata *serdata_rmw_to_ser_ref (const struct ddsi_serdata *dcmn, size_t off, size_t sz, ddsrt_iovec_t *ref)
{
const struct serdata_rmw *d = static_cast<const struct serdata_rmw *> (dcmn);
ref->iov_base = (char *) d->data.data () + off;
ref->iov_len = (ddsrt_iov_len_t) sz;
return ddsi_serdata_ref (d);
}
static void serdata_rmw_to_ser_unref (struct ddsi_serdata *dcmn, const ddsrt_iovec_t *ref __attribute__ ((unused)))
{
struct serdata_rmw *d = static_cast<struct serdata_rmw *> (dcmn);
ddsi_serdata_unref (d);
}
static bool serdata_rmw_to_sample (const struct ddsi_serdata *dcmn, void *sample, void **bufptr __attribute__ ((unused)), void *buflim __attribute__ ((unused)))
{
const struct serdata_rmw *d = static_cast<const struct serdata_rmw *> (dcmn);
const struct sertopic_rmw *topic = static_cast<const struct sertopic_rmw *> (d->topic);
assert (bufptr == NULL);
assert (buflim == NULL);
if (d->kind != SDK_DATA) {
/* ROS2 doesn't do keys in a meaningful way yet */
} else if (!topic->is_request_header) {
cycdeser sd (static_cast<const void *> (d->data.data ()), d->data.size ());
if (using_introspection_c_typesupport (topic->type_support.typesupport_identifier_)) {
auto typed_typesupport = static_cast<MessageTypeSupport_c *> (topic->type_support.type_support_);
return typed_typesupport->deserializeROSmessage (sd, sample, nullptr);
} else if (using_introspection_cpp_typesupport (topic->type_support.typesupport_identifier_)) {
auto typed_typesupport = static_cast<MessageTypeSupport_cpp *> (topic->type_support.type_support_);
return typed_typesupport->deserializeROSmessage (sd, sample, nullptr);
}
} else {
/* The "prefix" lambda is there to inject the service invocation header data into the CDR
stream -- I haven't checked how it is done in the official RMW implementations, so it is
probably incompatible. */
cdds_request_wrapper_t * const wrap = static_cast<cdds_request_wrapper_t *> (sample);
auto prefix = [wrap](cycdeser& ser) { ser >> wrap->header.guid; ser >> wrap->header.seq; };
cycdeser sd (static_cast<const void *> (d->data.data ()), d->data.size ());
if (using_introspection_c_typesupport (topic->type_support.typesupport_identifier_)) {
auto typed_typesupport = static_cast<MessageTypeSupport_c *> (topic->type_support.type_support_);
return typed_typesupport->deserializeROSmessage (sd, wrap->data, prefix);
} else if (using_introspection_cpp_typesupport (topic->type_support.typesupport_identifier_)) {
auto typed_typesupport = static_cast<MessageTypeSupport_cpp *> (topic->type_support.type_support_);
return typed_typesupport->deserializeROSmessage (sd, wrap->data, prefix);
}
}
return false;
}
static bool serdata_rmw_topicless_to_sample (const struct ddsi_sertopic *topic __attribute__ ((unused)), const struct ddsi_serdata *dcmn __attribute__ ((unused)), void *sample __attribute__ ((unused)), void **bufptr __attribute__ ((unused)), void *buflim __attribute__ ((unused)))
{
/* ROS2 doesn't do keys in a meaningful way yet */
return true;
}
static bool serdata_rmw_eqkey (const struct ddsi_serdata *a __attribute__ ((unused)), const struct ddsi_serdata *b __attribute__ ((unused)))
{
/* ROS2 doesn't do keys in a meaningful way yet */
return true;
}
static const struct ddsi_serdata_ops serdata_rmw_ops = {
.eqkey = serdata_rmw_eqkey,
.get_size = serdata_rmw_size,
.from_ser = serdata_rmw_from_ser,
.from_keyhash = serdata_rmw_from_keyhash,
.from_sample = serdata_rmw_from_sample,
.to_ser = serdata_rmw_to_ser,
.to_ser_ref = serdata_rmw_to_ser_ref,
.to_ser_unref = serdata_rmw_to_ser_unref,
.to_sample = serdata_rmw_to_sample,
.to_topicless = serdata_rmw_to_topicless,
.topicless_to_sample = serdata_rmw_topicless_to_sample,
.free = serdata_rmw_free
};
static void sertopic_rmw_deinit (struct ddsi_sertopic *tpcmn)
{
struct sertopic_rmw *tp = static_cast<struct sertopic_rmw *> (tpcmn);
delete tp;
}
static void sertopic_rmw_zero_samples (const struct ddsi_sertopic *d __attribute__ ((unused)), void *samples __attribute__ ((unused)), size_t count __attribute__ ((unused)))
{
/* Not using code paths that rely on the samples getting zero'd out */
}
static void sertopic_rmw_realloc_samples (void **ptrs __attribute__ ((unused)), const struct ddsi_sertopic *d __attribute__ ((unused)), void *old __attribute__ ((unused)), size_t oldcount __attribute__ ((unused)), size_t count __attribute__ ((unused)))
{
/* Not using code paths that rely on this (loans, dispose, unregister with instance handle,
content filters) */
abort ();
}
static void sertopic_rmw_free_samples (const struct ddsi_sertopic *d __attribute__ ((unused)), void **ptrs __attribute__ ((unused)), size_t count __attribute__ ((unused)), dds_free_op_t op)
{
/* Not using code paths that rely on this (dispose, unregister with instance handle, content
filters) */
assert (!(op & DDS_FREE_ALL_BIT));
}
static const struct ddsi_sertopic_ops sertopic_rmw_ops = {
.deinit = sertopic_rmw_deinit,
.zero_samples = sertopic_rmw_zero_samples,
.realloc_samples = sertopic_rmw_realloc_samples,
.free_samples = sertopic_rmw_free_samples
};
struct sertopic_rmw *create_sertopic (const char *topicname, const char *type_support_identifier, void *type_support, bool is_request_header)
{
struct sertopic_rmw *st = new struct sertopic_rmw;
st->cpp_name = std::string (topicname);
st->cpp_type_name = std::string ("absent"); // FIXME: obviously a hack
st->cpp_name_type_name = st->cpp_name + std::string (";") + std::string (st->cpp_type_name);
st->ops = &sertopic_rmw_ops;
st->serdata_ops = &serdata_rmw_ops;
st->serdata_basehash = ddsi_sertopic_compute_serdata_basehash (st->serdata_ops);
st->name_type_name = const_cast<char *> (st->cpp_name_type_name.c_str ());
st->name = const_cast<char *> (st->cpp_name.c_str ());
st->type_name = const_cast<char *> (st->cpp_type_name.c_str ());
st->iid = ddsi_iid_gen ();
ddsrt_atomic_st32 (&st->refc, 1);
st->type_support.typesupport_identifier_ = type_support_identifier;
st->type_support.type_support_ = type_support;
st->is_request_header = is_request_header;
return st;
}
#pragma GCC diagnostic pop

View file

@ -1,53 +1,22 @@
#include "rmw_cyclonedds_cpp/serdes.hpp"
cycser::cycser(struct sertopic *topic)
cycser::cycser (std::vector<unsigned char>& dst_)
: dst (dst_)
, off (0)
{
st = ddsi_serstate_new(topic);
sd = nullptr;
dst.reserve (4);
unsigned char *magic = dst.data ();
/* FIXME: hard code to little endian ... and ignoring endianness in deser */
magic[0] = 0;
magic[1] = 3;
/* options: */
magic[2] = 0;
magic[3] = 0;
}
cycser::~cycser()
{
if (sd == nullptr) {
ddsi_serstate_release(st);
} else {
ddsi_serdata_unref(sd);
}
}
cycser& cycser::ref()
{
assert(sd != nullptr);
ddsi_serdata_ref(sd);
return *this;
}
void cycser::unref()
{
assert(sd != nullptr);
ddsi_serdata_unref(sd);
}
cycser& cycser::fix()
{
assert(sd == nullptr);
sd = ddsi_serstate_fix(st);
return *this;
}
struct serdata *cycser::data()
{
assert(sd != nullptr);
return sd;
}
cycdeser::cycdeser(const void *data_, size_t size_)
{
data = static_cast<const char *>(data_);
lim = size_;
pos = 0;
}
cycdeser::~cycdeser()
cycdeser::cycdeser (const void *data_, size_t size_)
: data (static_cast<const char *> (data_) + 4)
, pos (0)
, lim (size_ - 4)
{
}