Uncrustify and fix issues reported by cpplint

Signed-off-by: Erik Boasson <eb@ilities.com>
This commit is contained in:
Erik Boasson 2019-08-17 15:18:57 +02:00 committed by eboasson
parent 130d6ea10e
commit 5e137205f2
7 changed files with 2664 additions and 2204 deletions

View file

@ -111,8 +111,12 @@ template<typename MembersType>
class TypeSupport class TypeSupport
{ {
public: public:
bool serializeROSmessage(const void * ros_message, cycser & ser, std::function<void(cycser&)> prefix = nullptr); bool serializeROSmessage(
bool deserializeROSmessage(cycdeser & deser, void * ros_message, std::function<void(cycdeser&)> prefix = nullptr); const void * ros_message, cycser & ser,
std::function<void(cycser &)> prefix = nullptr);
bool deserializeROSmessage(
cycdeser & deser, void * ros_message,
std::function<void(cycdeser &)> prefix = nullptr);
std::string getName(); std::string getName();
protected: protected:
@ -125,7 +129,9 @@ protected:
private: private:
bool serializeROSmessage(cycser & ser, const MembersType * members, const void * ros_message); bool serializeROSmessage(cycser & ser, const MembersType * members, const void * ros_message);
bool deserializeROSmessage(cycdeser & deser, const MembersType * members, void * ros_message, bool call_new); bool deserializeROSmessage(
cycdeser & deser, const MembersType * members, void * ros_message,
bool call_new);
}; };
} // namespace rmw_cyclonedds_cpp } // namespace rmw_cyclonedds_cpp

View file

@ -502,7 +502,9 @@ inline void deserialize_field<std::string>(
deser >> cpp_string_vector; deser >> cpp_string_vector;
auto & string_array_field = *reinterpret_cast<rosidl_generator_c__String__Sequence *>(field); 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())) { 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"); throw std::runtime_error("unable to initialize rosidl_generator_c__String array");
} }

View file

@ -11,18 +11,23 @@
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and // See the License for the specific language governing permissions and
// limitations under the License. // limitations under the License.
#ifndef SERDATA_HPP #ifndef RMW_CYCLONEDDS_CPP__SERDATA_HPP_
#define SERDATA_HPP #define RMW_CYCLONEDDS_CPP__SERDATA_HPP_
#include <string>
#include <vector>
#include "dds/ddsi/ddsi_sertopic.h" #include "dds/ddsi/ddsi_sertopic.h"
#include "dds/ddsi/ddsi_serdata.h" #include "dds/ddsi/ddsi_serdata.h"
struct CddsTypeSupport { struct CddsTypeSupport
{
void * type_support_; void * type_support_;
const char * typesupport_identifier_; const char * typesupport_identifier_;
}; };
struct sertopic_rmw : ddsi_sertopic { struct sertopic_rmw : ddsi_sertopic
{
CddsTypeSupport type_support; CddsTypeSupport type_support;
bool is_request_header; bool is_request_header;
std::string cpp_name; std::string cpp_name;
@ -30,28 +35,41 @@ struct sertopic_rmw : ddsi_sertopic {
std::string cpp_name_type_name; std::string cpp_name_type_name;
}; };
struct serdata_rmw : ddsi_serdata { struct serdata_rmw : ddsi_serdata
{
/* first two bytes of data is CDR encoding /* first two bytes of data is CDR encoding
second two bytes are encoding options */ second two bytes are encoding options */
std::vector<unsigned char> data; std::vector<unsigned char> data;
}; };
typedef struct cdds_request_header { typedef struct cdds_request_header
{
uint64_t guid; uint64_t guid;
int64_t seq; int64_t seq;
} cdds_request_header_t; } cdds_request_header_t;
typedef struct cdds_request_wrapper { typedef struct cdds_request_wrapper
{
cdds_request_header_t header; cdds_request_header_t header;
void * data; void * data;
} cdds_request_wrapper_t; } cdds_request_wrapper_t;
void *create_message_type_support (const void *untyped_members, const char *typesupport_identifier); void * create_message_type_support(
void *create_request_type_support (const void *untyped_members, const char *typesupport_identifier); const void * untyped_members,
void *create_response_type_support (const void *untyped_members, const char *typesupport_identifier); 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); struct sertopic_rmw * create_sertopic(
const char * topicname, const char * type_support_identifier,
void * type_support, bool is_request_header);
struct ddsi_serdata *serdata_rmw_from_serialized_message (const struct ddsi_sertopic *topiccmn, const void *raw, size_t size); struct ddsi_serdata * serdata_rmw_from_serialized_message(
const struct ddsi_sertopic * topiccmn,
const void * raw, size_t size);
#endif #endif // RMW_CYCLONEDDS_CPP__SERDATA_HPP_

View file

@ -1,4 +1,4 @@
// Copyright 2018 ADLINK Technology // Copyright 2018 to 2019 ADLINK Technology
// //
// Licensed under the Apache License, Version 2.0 (the "License"); // Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License. // you may not use this file except in compliance with the License.
@ -12,18 +12,20 @@
// See the License for the specific language governing permissions and // See the License for the specific language governing permissions and
// limitations under the License. // limitations under the License.
#ifndef SERDES_HPP #ifndef RMW_CYCLONEDDS_CPP__SERDES_HPP_
#define SERDES_HPP #define RMW_CYCLONEDDS_CPP__SERDES_HPP_
#include <string.h>
#include <array> #include <array>
#include <string> #include <string>
#include <vector> #include <vector>
#include <string.h>
#include <type_traits> #include <type_traits>
class cycser { class cycser
{
public: public:
cycser (std::vector<unsigned char>& dst_); explicit cycser(std::vector<unsigned char> & dst_);
cycser() = delete; cycser() = delete;
inline cycser & operator<<(bool x) {serialize(x); return *this;} inline cycser & operator<<(bool x) {serialize(x); return *this;}
@ -40,15 +42,17 @@ public:
inline cycser & operator<<(double 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 char * x) {serialize(x); return *this;}
inline cycser & operator<<(const std::string & 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>
template<class T, size_t S> inline cycser& operator<< (const std::array<T, S>& x) { serialize (x); return *this; } 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) { \ #define SIMPLE(T) inline void serialize(T x) { \
if ((off % sizeof(T)) != 0) { \ if ((off % sizeof(T)) != 0) { \
off += sizeof(T) - (off % sizeof(T)); \ off += sizeof(T) - (off % sizeof(T)); \
} \ } \
resize(off + sizeof(T)); \ resize(off + sizeof(T)); \
*(T *) (data () + off) = x; \ *(reinterpret_cast<T *>(data() + off)) = x; \
off += sizeof(T); \ off += sizeof(T); \
} }
SIMPLE(char); SIMPLE(char);
@ -64,7 +68,8 @@ public:
SIMPLE(double); SIMPLE(double);
#undef SIMPLE #undef SIMPLE
inline void serialize (bool x) { inline void serialize(bool x)
{
serialize(static_cast<unsigned char>(x)); serialize(static_cast<unsigned char>(x));
} }
inline void serialize(const char * x) inline void serialize(const char * x)
@ -90,7 +95,7 @@ public:
off += sizeof(T) - (off % sizeof(T)); \ off += sizeof(T) - (off % sizeof(T)); \
} \ } \
resize(off + cnt * sizeof(T)); \ resize(off + cnt * sizeof(T)); \
memcpy (data () + off, (void *) x, cnt * sizeof (T)); \ memcpy(data() + off, reinterpret_cast<const void *>(x), cnt * sizeof(T)); \
off += cnt * sizeof(T); \ off += cnt * sizeof(T); \
} \ } \
} }
@ -106,21 +111,26 @@ public:
SIMPLEA(float); SIMPLEA(float);
SIMPLEA(double); SIMPLEA(double);
#undef SIMPLEA #undef SIMPLEA
template<class T> inline void serializeA (const T *x, size_t cnt) { template<class T>
for (size_t i = 0; i < cnt; i++) serialize (x[i]); 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) template<class T>
inline void serialize(const std::vector<T> & x)
{ {
serialize(static_cast<uint32_t>(x.size())); serialize(static_cast<uint32_t>(x.size()));
serializeA(x.data(), x.size()); serializeA(x.data(), x.size());
} }
inline void serialize (const std::vector<bool>& x) { inline void serialize(const std::vector<bool> & x)
{
serialize(static_cast<uint32_t>(x.size())); serialize(static_cast<uint32_t>(x.size()));
for (auto&& i : x) serialize (i); for (auto && i : x) {serialize(i);}
} }
template<class T> inline void serializeS (const T *x, size_t cnt) template<class T>
inline void serializeS(const T * x, size_t cnt)
{ {
serialize(static_cast<uint32_t>(cnt)); serialize(static_cast<uint32_t>(cnt));
serializeA(x, cnt); serializeA(x, cnt);
@ -134,7 +144,8 @@ private:
size_t off; size_t off;
}; };
class cycdeser { class cycdeser
{
public: public:
// FIXME: byteswapping // FIXME: byteswapping
cycdeser(const void * data, size_t size); cycdeser(const void * data, size_t size);
@ -154,8 +165,10 @@ public:
inline cycdeser & operator>>(double & 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>>(char * & x) {deserialize(x); return *this;}
inline cycdeser & operator>>(std::string & 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>
template<class T, size_t S> inline cycdeser& operator>> (std::array<T, S>& x) { deserialize (x); return *this; } 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) { \ #define SIMPLE(T) inline void deserialize(T & x) { \
align(sizeof(x)); \ align(sizeof(x)); \
@ -175,19 +188,23 @@ public:
SIMPLE(double); SIMPLE(double);
#undef SIMPLE #undef SIMPLE
inline void deserialize (bool& x) { inline void deserialize(bool & x)
{
unsigned char z; deserialize(z); x = (z != 0); unsigned char z; deserialize(z); x = (z != 0);
} }
inline uint32_t deserialize32 () { inline uint32_t deserialize32()
{
uint32_t sz; deserialize(sz); return sz; uint32_t sz; deserialize(sz); return sz;
} }
inline void deserialize (char *& x) { inline void deserialize(char * & x)
{
const uint32_t sz = deserialize32(); const uint32_t sz = deserialize32();
x = (char *) malloc (sz); x = reinterpret_cast<char *>(malloc(sz));
memcpy(x, data + pos, sz); memcpy(x, data + pos, sz);
pos += sz; pos += sz;
} }
inline void deserialize (std::string& x) { inline void deserialize(std::string & x)
{
const uint32_t sz = deserialize32(); const uint32_t sz = deserialize32();
x = std::string(data + pos, sz - 1); x = std::string(data + pos, sz - 1);
pos += sz; pos += sz;
@ -196,7 +213,8 @@ public:
#define SIMPLEA(T) inline void deserializeA(T * x, size_t cnt) { \ #define SIMPLEA(T) inline void deserializeA(T * x, size_t cnt) { \
if (cnt > 0) { \ if (cnt > 0) { \
align(sizeof(T)); \ align(sizeof(T)); \
memcpy ((void *) x, (void *) (data + pos), (cnt) * sizeof (T)); \ memcpy(reinterpret_cast<void *>(x), reinterpret_cast<const void *>(data + pos), \
(cnt) * sizeof(T)); \
pos += (cnt) * sizeof(T); \ pos += (cnt) * sizeof(T); \
} \ } \
} }
@ -212,16 +230,21 @@ public:
SIMPLEA(float); SIMPLEA(float);
SIMPLEA(double); SIMPLEA(double);
#undef SIMPLEA #undef SIMPLEA
template<class T> inline void deserializeA (T *x, size_t cnt) { template<class T>
for (size_t i = 0; i < cnt; i++) deserialize (x[i]); 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) { template<class T>
inline void deserialize(std::vector<T> & x)
{
const uint32_t sz = deserialize32(); const uint32_t sz = deserialize32();
x.resize(sz); x.resize(sz);
deserializeA(x.data(), sz); deserializeA(x.data(), sz);
} }
inline void deserialize (std::vector<bool>& x) { inline void deserialize(std::vector<bool> & x)
{
const uint32_t sz = deserialize32(); const uint32_t sz = deserialize32();
x.resize(sz); x.resize(sz);
for (size_t i = 0; i < sz; i++) { for (size_t i = 0; i < sz; i++) {
@ -229,7 +252,9 @@ public:
} }
pos += sz; pos += sz;
} }
template<class T, size_t S> inline void deserialize (std::array<T, S>& x) { template<class T, size_t S>
inline void deserialize(std::array<T, S> & x)
{
deserializeA(x.data(), x.size()); deserializeA(x.data(), x.size());
} }
@ -246,4 +271,4 @@ private:
size_t lim; // ignored for now ... better provide correct input size_t lim; // ignored for now ... better provide correct input
}; };
#endif #endif // RMW_CYCLONEDDS_CPP__SERDES_HPP_

File diff suppressed because it is too large Load diff

View file

@ -11,9 +11,12 @@
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and // See the License for the specific language governing permissions and
// limitations under the License. // limitations under the License.
#include <string.h>
#include <vector> #include <vector>
#include <regex> #include <regex>
#include <sstream> #include <sstream>
#include <string>
#include "rmw/error_handling.h" #include "rmw/error_handling.h"
@ -26,12 +29,22 @@
#include "dds/ddsi/ddsi_iid.h" #include "dds/ddsi/ddsi_iid.h"
#include "dds/ddsi/q_radmin.h" #include "dds/ddsi/q_radmin.h"
using MessageTypeSupport_c = rmw_cyclonedds_cpp::MessageTypeSupport<rosidl_typesupport_introspection_c__MessageMembers>; using MessageTypeSupport_c =
using MessageTypeSupport_cpp = rmw_cyclonedds_cpp::MessageTypeSupport<rosidl_typesupport_introspection_cpp::MessageMembers>; rmw_cyclonedds_cpp::MessageTypeSupport<rosidl_typesupport_introspection_c__MessageMembers>;
using RequestTypeSupport_c = rmw_cyclonedds_cpp::RequestTypeSupport<rosidl_typesupport_introspection_c__ServiceMembers, rosidl_typesupport_introspection_c__MessageMembers>; using MessageTypeSupport_cpp =
using RequestTypeSupport_cpp = rmw_cyclonedds_cpp::RequestTypeSupport<rosidl_typesupport_introspection_cpp::ServiceMembers, rosidl_typesupport_introspection_cpp::MessageMembers>; rmw_cyclonedds_cpp::MessageTypeSupport<rosidl_typesupport_introspection_cpp::MessageMembers>;
using ResponseTypeSupport_c = rmw_cyclonedds_cpp::ResponseTypeSupport<rosidl_typesupport_introspection_c__ServiceMembers, rosidl_typesupport_introspection_c__MessageMembers>; using RequestTypeSupport_c = rmw_cyclonedds_cpp::RequestTypeSupport<
using ResponseTypeSupport_cpp = rmw_cyclonedds_cpp::ResponseTypeSupport<rosidl_typesupport_introspection_cpp::ServiceMembers, rosidl_typesupport_introspection_cpp::MessageMembers>; 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) static bool using_introspection_c_typesupport(const char * typesupport_identifier)
{ {
@ -43,39 +56,51 @@ static bool using_introspection_cpp_typesupport (const char *typesupport_identif
return typesupport_identifier == rosidl_typesupport_introspection_cpp::typesupport_identifier; return typesupport_identifier == rosidl_typesupport_introspection_cpp::typesupport_identifier;
} }
void *create_message_type_support (const void *untyped_members, const char *typesupport_identifier) void * create_message_type_support(
const void * untyped_members,
const char * typesupport_identifier)
{ {
if (using_introspection_c_typesupport(typesupport_identifier)) { if (using_introspection_c_typesupport(typesupport_identifier)) {
auto members = static_cast<const rosidl_typesupport_introspection_c__MessageMembers *> (untyped_members); auto members =
static_cast<const rosidl_typesupport_introspection_c__MessageMembers *>(untyped_members);
return new MessageTypeSupport_c(members); return new MessageTypeSupport_c(members);
} else if (using_introspection_cpp_typesupport(typesupport_identifier)) { } else if (using_introspection_cpp_typesupport(typesupport_identifier)) {
auto members = static_cast<const rosidl_typesupport_introspection_cpp::MessageMembers *> (untyped_members); auto members =
static_cast<const rosidl_typesupport_introspection_cpp::MessageMembers *>(untyped_members);
return new MessageTypeSupport_cpp(members); return new MessageTypeSupport_cpp(members);
} }
RMW_SET_ERROR_MSG("Unknown typesupport identifier"); RMW_SET_ERROR_MSG("Unknown typesupport identifier");
return nullptr; return nullptr;
} }
void *create_request_type_support (const void *untyped_members, const char *typesupport_identifier) void * create_request_type_support(
const void * untyped_members,
const char * typesupport_identifier)
{ {
if (using_introspection_c_typesupport(typesupport_identifier)) { if (using_introspection_c_typesupport(typesupport_identifier)) {
auto members = static_cast<const rosidl_typesupport_introspection_c__ServiceMembers *> (untyped_members); auto members =
static_cast<const rosidl_typesupport_introspection_c__ServiceMembers *>(untyped_members);
return new RequestTypeSupport_c(members); return new RequestTypeSupport_c(members);
} else if (using_introspection_cpp_typesupport(typesupport_identifier)) { } else if (using_introspection_cpp_typesupport(typesupport_identifier)) {
auto members = static_cast<const rosidl_typesupport_introspection_cpp::ServiceMembers *> (untyped_members); auto members =
static_cast<const rosidl_typesupport_introspection_cpp::ServiceMembers *>(untyped_members);
return new RequestTypeSupport_cpp(members); return new RequestTypeSupport_cpp(members);
} }
RMW_SET_ERROR_MSG("Unknown typesupport identifier"); RMW_SET_ERROR_MSG("Unknown typesupport identifier");
return nullptr; return nullptr;
} }
void *create_response_type_support (const void *untyped_members, const char *typesupport_identifier) void * create_response_type_support(
const void * untyped_members,
const char * typesupport_identifier)
{ {
if (using_introspection_c_typesupport(typesupport_identifier)) { if (using_introspection_c_typesupport(typesupport_identifier)) {
auto members = static_cast<const rosidl_typesupport_introspection_c__ServiceMembers *> (untyped_members); auto members =
static_cast<const rosidl_typesupport_introspection_c__ServiceMembers *>(untyped_members);
return new ResponseTypeSupport_c(members); return new ResponseTypeSupport_c(members);
} else if (using_introspection_cpp_typesupport(typesupport_identifier)) { } else if (using_introspection_cpp_typesupport(typesupport_identifier)) {
auto members = static_cast<const rosidl_typesupport_introspection_cpp::ServiceMembers *> (untyped_members); auto members =
static_cast<const rosidl_typesupport_introspection_cpp::ServiceMembers *>(untyped_members);
return new ResponseTypeSupport_cpp(members); return new ResponseTypeSupport_cpp(members);
} }
RMW_SET_ERROR_MSG("Unknown typesupport identifier"); RMW_SET_ERROR_MSG("Unknown typesupport identifier");
@ -94,14 +119,19 @@ static void serdata_rmw_free (struct ddsi_serdata *dcmn)
delete d; delete d;
} }
static struct serdata_rmw *rmw_serdata_new (const struct ddsi_sertopic *topic, enum ddsi_serdata_kind kind) static struct serdata_rmw * rmw_serdata_new(
const struct ddsi_sertopic * topic,
enum ddsi_serdata_kind kind)
{ {
struct serdata_rmw * sd = new serdata_rmw; struct serdata_rmw * sd = new serdata_rmw;
ddsi_serdata_init(sd, topic, kind); ddsi_serdata_init(sd, topic, kind);
return sd; 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) 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 = rmw_serdata_new(topic, kind); struct serdata_rmw * d = rmw_serdata_new(topic, kind);
uint32_t off = 0; uint32_t off = 0;
@ -111,8 +141,10 @@ static struct ddsi_serdata *serdata_rmw_from_ser (const struct ddsi_sertopic *to
while (fragchain) { while (fragchain) {
if (fragchain->maxp1 > off) { if (fragchain->maxp1 > off) {
/* only copy if this fragment adds data */ /* only copy if this fragment adds data */
const unsigned char *payload = NN_RMSG_PAYLOADOFF (fragchain->rmsg, NN_RDATA_PAYLOAD_OFF (fragchain)); const unsigned char * payload =
d->data.insert (d->data.end (), payload + off - fragchain->min, payload + fragchain->maxp1 - fragchain->min); 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; off = fragchain->maxp1;
} }
fragchain = fragchain->nextfrag; fragchain = fragchain->nextfrag;
@ -120,14 +152,19 @@ static struct ddsi_serdata *serdata_rmw_from_ser (const struct ddsi_sertopic *to
return d; return d;
} }
static struct ddsi_serdata *serdata_rmw_from_keyhash (const struct ddsi_sertopic *topic, const struct nn_keyhash *keyhash) static struct ddsi_serdata * serdata_rmw_from_keyhash(
const struct ddsi_sertopic * topic,
const struct nn_keyhash * keyhash)
{ {
static_cast<void>(keyhash); // unused static_cast<void>(keyhash); // unused
/* there is no key field, so from_keyhash is trivial */ /* there is no key field, so from_keyhash is trivial */
return rmw_serdata_new(topic, SDK_KEY); return rmw_serdata_new(topic, SDK_KEY);
} }
static struct ddsi_serdata *serdata_rmw_from_sample (const struct ddsi_sertopic *topiccmn, enum ddsi_serdata_kind kind, const void *sample) 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); const struct sertopic_rmw * topic = static_cast<const struct sertopic_rmw *>(topiccmn);
struct serdata_rmw * d = rmw_serdata_new(topic, kind); struct serdata_rmw * d = rmw_serdata_new(topic, kind);
@ -136,10 +173,12 @@ static struct ddsi_serdata *serdata_rmw_from_sample (const struct ddsi_sertopic
} else if (!topic->is_request_header) { } else if (!topic->is_request_header) {
cycser sd(d->data); cycser sd(d->data);
if (using_introspection_c_typesupport(topic->type_support.typesupport_identifier_)) { if (using_introspection_c_typesupport(topic->type_support.typesupport_identifier_)) {
auto typed_typesupport = static_cast<MessageTypeSupport_c *> (topic->type_support.type_support_); auto typed_typesupport =
static_cast<MessageTypeSupport_c *>(topic->type_support.type_support_);
(void) typed_typesupport->serializeROSmessage(sample, sd, nullptr); (void) typed_typesupport->serializeROSmessage(sample, sd, nullptr);
} else if (using_introspection_cpp_typesupport(topic->type_support.typesupport_identifier_)) { } else if (using_introspection_cpp_typesupport(topic->type_support.typesupport_identifier_)) {
auto typed_typesupport = static_cast<MessageTypeSupport_cpp *> (topic->type_support.type_support_); auto typed_typesupport =
static_cast<MessageTypeSupport_cpp *>(topic->type_support.type_support_);
(void) typed_typesupport->serializeROSmessage(sample, sd, nullptr); (void) typed_typesupport->serializeROSmessage(sample, sd, nullptr);
} }
} else { } else {
@ -150,10 +189,12 @@ static struct ddsi_serdata *serdata_rmw_from_sample (const struct ddsi_sertopic
auto prefix = [wrap](cycser & ser) {ser << wrap->header.guid; ser << wrap->header.seq;}; auto prefix = [wrap](cycser & ser) {ser << wrap->header.guid; ser << wrap->header.seq;};
cycser sd(d->data); cycser sd(d->data);
if (using_introspection_c_typesupport(topic->type_support.typesupport_identifier_)) { if (using_introspection_c_typesupport(topic->type_support.typesupport_identifier_)) {
auto typed_typesupport = static_cast<MessageTypeSupport_c *> (topic->type_support.type_support_); auto typed_typesupport =
static_cast<MessageTypeSupport_c *>(topic->type_support.type_support_);
(void) typed_typesupport->serializeROSmessage(wrap->data, sd, prefix); (void) typed_typesupport->serializeROSmessage(wrap->data, sd, prefix);
} else if (using_introspection_cpp_typesupport(topic->type_support.typesupport_identifier_)) { } else if (using_introspection_cpp_typesupport(topic->type_support.typesupport_identifier_)) {
auto typed_typesupport = static_cast<MessageTypeSupport_cpp *> (topic->type_support.type_support_); auto typed_typesupport =
static_cast<MessageTypeSupport_cpp *>(topic->type_support.type_support_);
(void) typed_typesupport->serializeROSmessage(wrap->data, sd, prefix); (void) typed_typesupport->serializeROSmessage(wrap->data, sd, prefix);
} }
} }
@ -165,7 +206,9 @@ static struct ddsi_serdata *serdata_rmw_from_sample (const struct ddsi_sertopic
return d; return d;
} }
struct ddsi_serdata *serdata_rmw_from_serialized_message (const struct ddsi_sertopic *topiccmn, const void *raw, size_t size) struct ddsi_serdata * serdata_rmw_from_serialized_message(
const struct ddsi_sertopic * topiccmn,
const void * raw, size_t size)
{ {
const struct sertopic_rmw * topic = static_cast<const struct sertopic_rmw *>(topiccmn); const struct sertopic_rmw * topic = static_cast<const struct sertopic_rmw *>(topiccmn);
struct serdata_rmw * d = rmw_serdata_new(topic, SDK_DATA); struct serdata_rmw * d = rmw_serdata_new(topic, SDK_DATA);
@ -190,13 +233,15 @@ static struct ddsi_serdata *serdata_rmw_to_topicless (const struct ddsi_serdata
static void serdata_rmw_to_ser(const struct ddsi_serdata * dcmn, size_t off, size_t sz, void * buf) 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); const struct serdata_rmw * d = static_cast<const struct serdata_rmw *>(dcmn);
memcpy (buf, (char *) d->data.data () + off, sz); memcpy(buf, reinterpret_cast<const 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) 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); const struct serdata_rmw * d = static_cast<const struct serdata_rmw *>(dcmn);
ref->iov_base = (char *) d->data.data () + off; ref->iov_base = const_cast<char *>(reinterpret_cast<const char *>(d->data.data())) + off;
ref->iov_len = (ddsrt_iov_len_t) sz; ref->iov_len = (ddsrt_iov_len_t) sz;
return ddsi_serdata_ref(d); return ddsi_serdata_ref(d);
} }
@ -208,7 +253,9 @@ static void serdata_rmw_to_ser_unref (struct ddsi_serdata *dcmn, const ddsrt_iov
ddsi_serdata_unref(d); ddsi_serdata_unref(d);
} }
static bool serdata_rmw_to_sample (const struct ddsi_serdata *dcmn, void *sample, void **bufptr, void *buflim) static bool serdata_rmw_to_sample(
const struct ddsi_serdata * dcmn, void * sample, void ** bufptr,
void * buflim)
{ {
static_cast<void>(bufptr); // unused static_cast<void>(bufptr); // unused
static_cast<void>(buflim); // unused static_cast<void>(buflim); // unused
@ -221,10 +268,12 @@ static bool serdata_rmw_to_sample (const struct ddsi_serdata *dcmn, void *sample
} else if (!topic->is_request_header) { } else if (!topic->is_request_header) {
cycdeser sd(static_cast<const void *>(d->data.data()), d->data.size()); cycdeser sd(static_cast<const void *>(d->data.data()), d->data.size());
if (using_introspection_c_typesupport(topic->type_support.typesupport_identifier_)) { if (using_introspection_c_typesupport(topic->type_support.typesupport_identifier_)) {
auto typed_typesupport = static_cast<MessageTypeSupport_c *> (topic->type_support.type_support_); auto typed_typesupport =
static_cast<MessageTypeSupport_c *>(topic->type_support.type_support_);
return typed_typesupport->deserializeROSmessage(sd, sample, nullptr); return typed_typesupport->deserializeROSmessage(sd, sample, nullptr);
} else if (using_introspection_cpp_typesupport(topic->type_support.typesupport_identifier_)) { } else if (using_introspection_cpp_typesupport(topic->type_support.typesupport_identifier_)) {
auto typed_typesupport = static_cast<MessageTypeSupport_cpp *> (topic->type_support.type_support_); auto typed_typesupport =
static_cast<MessageTypeSupport_cpp *>(topic->type_support.type_support_);
return typed_typesupport->deserializeROSmessage(sd, sample, nullptr); return typed_typesupport->deserializeROSmessage(sd, sample, nullptr);
} }
} else { } else {
@ -235,17 +284,22 @@ static bool serdata_rmw_to_sample (const struct ddsi_serdata *dcmn, void *sample
auto prefix = [wrap](cycdeser & ser) {ser >> wrap->header.guid; ser >> wrap->header.seq;}; 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()); cycdeser sd(static_cast<const void *>(d->data.data()), d->data.size());
if (using_introspection_c_typesupport(topic->type_support.typesupport_identifier_)) { if (using_introspection_c_typesupport(topic->type_support.typesupport_identifier_)) {
auto typed_typesupport = static_cast<MessageTypeSupport_c *> (topic->type_support.type_support_); auto typed_typesupport =
static_cast<MessageTypeSupport_c *>(topic->type_support.type_support_);
return typed_typesupport->deserializeROSmessage(sd, wrap->data, prefix); return typed_typesupport->deserializeROSmessage(sd, wrap->data, prefix);
} else if (using_introspection_cpp_typesupport(topic->type_support.typesupport_identifier_)) { } else if (using_introspection_cpp_typesupport(topic->type_support.typesupport_identifier_)) {
auto typed_typesupport = static_cast<MessageTypeSupport_cpp *> (topic->type_support.type_support_); auto typed_typesupport =
static_cast<MessageTypeSupport_cpp *>(topic->type_support.type_support_);
return typed_typesupport->deserializeROSmessage(sd, wrap->data, prefix); return typed_typesupport->deserializeROSmessage(sd, wrap->data, prefix);
} }
} }
return false; return false;
} }
static bool serdata_rmw_topicless_to_sample (const struct ddsi_sertopic *topic, const struct ddsi_serdata *dcmn, void *sample, void **bufptr, void *buflim) static bool serdata_rmw_topicless_to_sample(
const struct ddsi_sertopic * topic,
const struct ddsi_serdata * dcmn, void * sample,
void ** bufptr, void * buflim)
{ {
static_cast<void>(topic); static_cast<void>(topic);
static_cast<void>(dcmn); static_cast<void>(dcmn);
@ -293,7 +347,9 @@ static void sertopic_rmw_zero_samples (const struct ddsi_sertopic *d, void *samp
/* Not using code paths that rely on the samples getting zero'd out */ /* Not using code paths that rely on the samples getting zero'd out */
} }
static void sertopic_rmw_realloc_samples (void **ptrs, const struct ddsi_sertopic *d, void *old, size_t oldcount, size_t count) static void sertopic_rmw_realloc_samples(
void ** ptrs, const struct ddsi_sertopic * d, void * old,
size_t oldcount, size_t count)
{ {
static_cast<void>(ptrs); static_cast<void>(ptrs);
static_cast<void>(d); static_cast<void>(d);
@ -305,7 +361,9 @@ static void sertopic_rmw_realloc_samples (void **ptrs, const struct ddsi_sertopi
abort(); abort();
} }
static void sertopic_rmw_free_samples (const struct ddsi_sertopic *d, void **ptrs, size_t count, dds_free_op_t op) static void sertopic_rmw_free_samples(
const struct ddsi_sertopic * d, void ** ptrs, size_t count,
dds_free_op_t op)
{ {
static_cast<void>(d); // unused static_cast<void>(d); // unused
static_cast<void>(ptrs); // unused static_cast<void>(ptrs); // unused
@ -358,7 +416,9 @@ static std::string get_type_name (const char *type_support_identifier, void *typ
} }
} }
struct sertopic_rmw *create_sertopic (const char *topicname, const char *type_support_identifier, void *type_support, bool is_request_header) 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; struct sertopic_rmw * st = new struct sertopic_rmw;
memset(st, 0, sizeof(struct ddsi_sertopic)); memset(st, 0, sizeof(struct ddsi_sertopic));

View file

@ -1,8 +1,23 @@
// Copyright 2018 to 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_cyclonedds_cpp/serdes.hpp" #include "rmw_cyclonedds_cpp/serdes.hpp"
cycser::cycser(std::vector<unsigned char> & dst_) cycser::cycser(std::vector<unsigned char> & dst_)
: dst (dst_) : dst(dst_),
, off (0) off(0)
{ {
dst.reserve(4); dst.reserve(4);
/* FIXME: hard code to little endian ... and ignoring endianness in deser */ /* FIXME: hard code to little endian ... and ignoring endianness in deser */
@ -14,8 +29,8 @@ cycser::cycser (std::vector<unsigned char>& dst_)
} }
cycdeser::cycdeser(const void * data_, size_t size_) cycdeser::cycdeser(const void * data_, size_t size_)
: data (static_cast<const char *> (data_) + 4) : data(static_cast<const char *>(data_) + 4),
, pos (0) pos(0),
, lim (size_ - 4) lim(size_ - 4)
{ {
} }