initial commit

This commit is contained in:
Erik Boasson 2018-07-09 13:22:25 +02:00
commit 01ef31359a
23 changed files with 3650 additions and 0 deletions

View file

@ -0,0 +1,103 @@
# Copyright 2018 ADLINK Technology Limited.
#
# 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.
cmake_minimum_required(VERSION 3.5)
project(rmw_cyclonedds_cpp)
link_directories(/usr/local/lib)
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
find_package(ament_cmake_ros REQUIRED)
find_package(rcutils REQUIRED)
find_package(cyclonedds_cmake_module REQUIRED)
find_package(fastcdr REQUIRED CONFIG)
find_package(CycloneDDS REQUIRED CONFIG)
find_package(rmw REQUIRED)
find_package(rosidl_generator_c REQUIRED)
find_package(rosidl_typesupport_introspection_c REQUIRED)
find_package(rosidl_typesupport_introspection_cpp REQUIRED)
ament_export_dependencies(rcutils)
ament_export_dependencies(rmw)
ament_export_dependencies(rosidl_generator_c)
ament_export_dependencies(rosidl_typesupport_introspection_c)
ament_export_dependencies(rosidl_typesupport_introspection_cpp)
include_directories(include)
###??
add_library(rmw_cyclonedds_cpp
src/namespace_prefix.cpp
src/rmw_node.cpp
)
idlc_generate(rmw_cyclonedds_topic_lib src/rmw_cyclonedds_topic.idl)
target_link_libraries(rmw_cyclonedds_cpp
fastcdr rmw_cyclonedds_topic_lib CycloneDDS::ddsc)
ament_target_dependencies(rmw_cyclonedds_cpp
"rcutils"
"rosidl_typesupport_introspection_c"
"rosidl_typesupport_introspection_cpp"
"rmw"
"rosidl_generator_c"
)
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")
ament_export_include_directories(include)
ament_export_libraries(rmw_cyclonedds_cpp)
register_rmw_implementation(
"c:rosidl_typesupport_c:rosidl_typesupport_introspection_c"
"cpp:rosidl_typesupport_cpp:rosidl_typesupport_introspection_cpp")
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()
ament_package(
CONFIG_EXTRAS "rmw_cyclonedds_cpp-extras.cmake"
)
install(
DIRECTORY include/
DESTINATION include
)
install(
TARGETS rmw_cyclonedds_cpp
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

View file

@ -0,0 +1,42 @@
// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima).
//
// 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 RMW_CYCLONEDDS_CPP__MESSAGETYPESUPPORT_HPP_
#define RMW_CYCLONEDDS_CPP__MESSAGETYPESUPPORT_HPP_
#include <fastcdr/FastBuffer.h>
#include <fastcdr/Cdr.h>
#include <cassert>
#include <memory>
#include "TypeSupport.hpp"
#include "rosidl_typesupport_introspection_cpp/message_introspection.hpp"
#include "rosidl_typesupport_introspection_cpp/field_types.hpp"
namespace rmw_cyclonedds_cpp
{
template<typename MembersType>
class MessageTypeSupport : public TypeSupport<MembersType>
{
public:
explicit MessageTypeSupport(const MembersType * members);
};
} // namespace rmw_cyclonedds_cpp
#include "MessageTypeSupport_impl.hpp"
#endif // RMW_CYCLONEDDS_CPP__MESSAGETYPESUPPORT_HPP_

View file

@ -0,0 +1,52 @@
// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima).
//
// 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 RMW_CYCLONEDDS_CPP__MESSAGETYPESUPPORT_IMPL_HPP_
#define RMW_CYCLONEDDS_CPP__MESSAGETYPESUPPORT_IMPL_HPP_
#include <fastcdr/FastBuffer.h>
#include <fastcdr/Cdr.h>
#include <cassert>
#include <memory>
#include <string>
#include "rmw_cyclonedds_cpp/MessageTypeSupport.hpp"
#include "rosidl_typesupport_introspection_cpp/field_types.hpp"
namespace rmw_cyclonedds_cpp
{
template<typename MembersType>
MessageTypeSupport<MembersType>::MessageTypeSupport(const MembersType * members)
{
assert(members);
this->members_ = members;
std::string name = std::string(members->package_name_) + "::msg::dds_::" +
members->message_name_ + "_";
this->setName(name.c_str());
// TODO(wjwwood): this could be more intelligent, setting m_typeSize to the
// maximum serialized size of the message, when the message is a bounded one.
if (members->member_count_ != 0) {
this->m_typeSize = static_cast<uint32_t>(this->calculateMaxSerializedSize(members, 0));
} else {
this->m_typeSize = 4;
}
}
} // namespace rmw_cyclonedds_cpp
#endif // RMW_CYCLONEDDS_CPP__MESSAGETYPESUPPORT_IMPL_HPP_

View file

@ -0,0 +1,55 @@
// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima).
//
// 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 RMW_CYCLONEDDS_CPP__SERVICETYPESUPPORT_HPP_
#define RMW_CYCLONEDDS_CPP__SERVICETYPESUPPORT_HPP_
#include <fastcdr/FastBuffer.h>
#include <fastcdr/Cdr.h>
#include <cassert>
#include "TypeSupport.hpp"
#include "rosidl_typesupport_introspection_cpp/field_types.hpp"
struct CustomServiceInfo;
namespace rmw_cyclonedds_cpp
{
template<typename MembersType>
class ServiceTypeSupport : public TypeSupport<MembersType>
{
protected:
ServiceTypeSupport();
};
template<typename ServiceMembersType, typename MessageMembersType>
class RequestTypeSupport : public ServiceTypeSupport<MessageMembersType>
{
public:
explicit RequestTypeSupport(const ServiceMembersType * members);
};
template<typename ServiceMembersType, typename MessageMembersType>
class ResponseTypeSupport : public ServiceTypeSupport<MessageMembersType>
{
public:
explicit ResponseTypeSupport(const ServiceMembersType * members);
};
} // namespace rmw_cyclonedds_cpp
#include "ServiceTypeSupport_impl.hpp"
#endif // RMW_CYCLONEDDS_CPP__SERVICETYPESUPPORT_HPP_

View file

@ -0,0 +1,76 @@
// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima).
//
// 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 RMW_CYCLONEDDS_CPP__SERVICETYPESUPPORT_IMPL_HPP_
#define RMW_CYCLONEDDS_CPP__SERVICETYPESUPPORT_IMPL_HPP_
#include <fastcdr/FastBuffer.h>
#include <fastcdr/Cdr.h>
#include <cassert>
#include <string>
#include "rmw_cyclonedds_cpp/ServiceTypeSupport.hpp"
#include "rosidl_typesupport_introspection_cpp/field_types.hpp"
namespace rmw_cyclonedds_cpp
{
template<typename MembersType>
ServiceTypeSupport<MembersType>::ServiceTypeSupport()
{
}
template<typename ServiceMembersType, typename MessageMembersType>
RequestTypeSupport<ServiceMembersType, MessageMembersType>::RequestTypeSupport(
const ServiceMembersType * members)
{
assert(members);
this->members_ = members->request_members_;
std::string name = std::string(members->package_name_) + "::srv::dds_::" +
members->service_name_ + "_Request_";
this->setName(name.c_str());
// TODO(wjwwood): this could be more intelligent, setting m_typeSize to the
// maximum serialized size of the message, when the message is a bounded one.
if (this->members_->member_count_ != 0) {
this->m_typeSize = static_cast<uint32_t>(this->calculateMaxSerializedSize(this->members_, 0));
} else {
this->m_typeSize = 4;
}
}
template<typename ServiceMembersType, typename MessageMembersType>
ResponseTypeSupport<ServiceMembersType, MessageMembersType>::ResponseTypeSupport(
const ServiceMembersType * members)
{
assert(members);
this->members_ = members->response_members_;
std::string name = std::string(members->package_name_) + "::srv::dds_::" +
members->service_name_ + "_Response_";
this->setName(name.c_str());
// TODO(wjwwood): this could be more intelligent, setting m_typeSize to the
// maximum serialized size of the message, when the message is a bounded one.
if (this->members_->member_count_ != 0) {
this->m_typeSize = static_cast<uint32_t>(this->calculateMaxSerializedSize(this->members_, 0));
} else {
this->m_typeSize = 4;
}
}
} // namespace rmw_cyclonedds_cpp
#endif // RMW_CYCLONEDDS_CPP__SERVICETYPESUPPORT_IMPL_HPP_

View file

@ -0,0 +1,141 @@
// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima).
//
// 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 RMW_CYCLONEDDS_CPP__TYPESUPPORT_HPP_
#define RMW_CYCLONEDDS_CPP__TYPESUPPORT_HPP_
#include <rosidl_generator_c/string.h>
#include <rosidl_generator_c/string_functions.h>
#include <fastcdr/FastBuffer.h>
#include <fastcdr/Cdr.h>
#include <cassert>
#include <string>
#include "rcutils/logging_macros.h"
#include "rosidl_typesupport_introspection_cpp/field_types.hpp"
#include "rosidl_typesupport_introspection_cpp/identifier.hpp"
#include "rosidl_typesupport_introspection_cpp/message_introspection.hpp"
#include "rosidl_typesupport_introspection_cpp/service_introspection.hpp"
#include "rosidl_typesupport_introspection_cpp/visibility_control.h"
#include "rosidl_typesupport_introspection_c/field_types.h"
#include "rosidl_typesupport_introspection_c/identifier.h"
#include "rosidl_typesupport_introspection_c/message_introspection.h"
#include "rosidl_typesupport_introspection_c/service_introspection.h"
#include "rosidl_typesupport_introspection_c/visibility_control.h"
namespace rmw_cyclonedds_cpp
{
// Helper class that uses template specialization to read/write string types to/from a
// eprosima::fastcdr::Cdr
template<typename MembersType>
struct StringHelper;
// For C introspection typesupport we create intermediate instances of std::string so that
// eprosima::fastcdr::Cdr can handle the string properly.
template<>
struct StringHelper<rosidl_typesupport_introspection_c__MessageMembers>
{
using type = rosidl_generator_c__String;
static std::string convert_to_std_string(void * data)
{
auto c_string = static_cast<rosidl_generator_c__String *>(data);
if (!c_string) {
RCUTILS_LOG_ERROR_NAMED(
"rmw_cyclonedds_cpp",
"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")
return "";
}
return std::string(c_string->data);
}
static std::string convert_to_std_string(rosidl_generator_c__String & data)
{
return std::string(data.data);
}
static void assign(eprosima::fastcdr::Cdr & deser, void * field, bool)
{
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());
}
};
// For C++ introspection typesupport we just reuse the same std::string transparently.
template<>
struct StringHelper<rosidl_typesupport_introspection_cpp::MessageMembers>
{
using type = std::string;
static std::string & convert_to_std_string(void * data)
{
return *(static_cast<std::string *>(data));
}
static void assign(eprosima::fastcdr::Cdr & deser, void * field, bool call_new)
{
std::string & str = *(std::string *)field;
if (call_new) {
new(&str) std::string;
}
deser >> str;
}
};
template<typename MembersType>
class TypeSupport
{
public:
bool serializeROSmessage(const void * ros_message, eprosima::fastcdr::Cdr & ser, std::function<void(eprosima::fastcdr::Cdr&)> prefix = nullptr);
bool deserializeROSmessage(eprosima::fastcdr::FastBuffer * data, void * ros_message);
bool deserializeROSmessage(eprosima::fastcdr::Cdr & deser, void * ros_message, std::function<void(eprosima::fastcdr::Cdr&)> prefix = nullptr);
protected:
TypeSupport();
size_t calculateMaxSerializedSize(const MembersType * members, size_t current_alignment);
void setName(const std::string& name);
const MembersType * members_;
std::string name;
size_t m_typeSize;
private:
bool serializeROSmessage(
eprosima::fastcdr::Cdr & ser, const MembersType * members, const void * ros_message);
bool deserializeROSmessage(
eprosima::fastcdr::Cdr & deser, const MembersType * members, void * ros_message,
bool call_new);
};
} // namespace rmw_cyclonedds_cpp
#include "TypeSupport_impl.hpp"
#endif // RMW_CYCLONEDDS_CPP__TYPESUPPORT_HPP_

View file

@ -0,0 +1,751 @@
// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima).
//
// 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 RMW_CYCLONEDDS_CPP__TYPESUPPORT_IMPL_HPP_
#define RMW_CYCLONEDDS_CPP__TYPESUPPORT_IMPL_HPP_
#include <fastcdr/FastBuffer.h>
#include <fastcdr/Cdr.h>
#include <cassert>
#include <functional>
#include <string>
#include <vector>
#include "rmw_cyclonedds_cpp/TypeSupport.hpp"
#include "rmw_cyclonedds_cpp/macros.hpp"
#include "rosidl_typesupport_introspection_cpp/field_types.hpp"
#include "rosidl_typesupport_introspection_cpp/message_introspection.hpp"
#include "rosidl_typesupport_introspection_cpp/service_introspection.hpp"
#include "rosidl_typesupport_introspection_c/message_introspection.h"
#include "rosidl_typesupport_introspection_c/service_introspection.h"
#include "rosidl_generator_c/primitives_array_functions.h"
namespace rmw_cyclonedds_cpp
{
template<typename T>
struct GenericCArray;
// 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)
typedef struct rosidl_generator_c__void__Array
{
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;
inline
bool
rosidl_generator_c__void__Array__init(
rosidl_generator_c__void__Array * array, size_t size, size_t member_size)
{
if (!array) {
return false;
}
void * data = nullptr;
if (size) {
data = static_cast<void *>(calloc(size, member_size));
if (!data) {
return false;
}
}
array->data = data;
array->size = size;
array->capacity = size;
return true;
}
inline
void
rosidl_generator_c__void__Array__fini(rosidl_generator_c__void__Array * array)
{
if (!array) {
return;
}
if (array->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;
} else {
// ensure that data, size, and capacity values are consistent
assert(0 == array->size);
assert(0 == array->capacity);
}
}
template<typename MembersType>
TypeSupport<MembersType>::TypeSupport()
{
name = "";
m_typeSize = 0;
}
template<typename MembersType>
void TypeSupport<MembersType>::setName(const std::string& name)
{
this->name = std::string(name);
}
static inline void *
align_(size_t __align, void * & __ptr) noexcept
{
const auto __intptr = reinterpret_cast<uintptr_t>(__ptr);
const auto __aligned = (__intptr - 1u + __align) & ~(__align - 1);
return __ptr = reinterpret_cast<void *>(__aligned);
}
template<typename MembersType>
static size_t calculateMaxAlign(const MembersType * members)
{
size_t max_align = 0;
for (uint32_t i = 0; i < members->member_count_; ++i) {
size_t alignment = 0;
const auto & member = members->members_[i];
if (member.is_array_ && (!member.array_size_ || member.is_upper_bound_)) {
alignment = alignof(std::vector<unsigned char>);
} else {
switch (member.type_id_) {
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BOOL:
alignment = alignof(bool);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BYTE:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT8:
alignment = alignof(uint8_t);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_CHAR:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT8:
alignment = alignof(char);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT32:
alignment = alignof(float);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT64:
alignment = alignof(double);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT16:
alignment = alignof(int16_t);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT16:
alignment = alignof(uint16_t);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT32:
alignment = alignof(int32_t);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT32:
alignment = alignof(uint32_t);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT64:
alignment = alignof(int64_t);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT64:
alignment = alignof(uint64_t);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_STRING:
// Note: specialization needed because calculateMaxAlign is called before
// casting submembers as std::string, returned value is the same on i386
if (std::is_same<MembersType,
rosidl_typesupport_introspection_c__MessageMembers>::value)
{
alignment = alignof(rosidl_generator_c__String);
} else {
alignment = alignof(std::string);
}
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE:
{
auto sub_members = (const MembersType *)member.members_->data;
alignment = calculateMaxAlign(sub_members);
}
break;
}
}
if (alignment > max_align) {
max_align = alignment;
}
}
return max_align;
}
// C++ specialization
template<typename T>
void serialize_field(
const rosidl_typesupport_introspection_cpp::MessageMember * member,
void * field,
eprosima::fastcdr::Cdr & ser)
{
if (!member->is_array_) {
ser << *static_cast<T *>(field);
} else if (member->array_size_ && !member->is_upper_bound_) {
ser.serializeArray(static_cast<T *>(field), member->array_size_);
} else {
std::vector<T> & data = *reinterpret_cast<std::vector<T> *>(field);
ser << data;
}
}
// C specialization
template<typename T>
void serialize_field(
const rosidl_typesupport_introspection_c__MessageMember * member,
void * field,
eprosima::fastcdr::Cdr & ser)
{
if (!member->is_array_) {
ser << *static_cast<T *>(field);
} else if (member->array_size_ && !member->is_upper_bound_) {
ser.serializeArray(static_cast<T *>(field), member->array_size_);
} else {
auto & data = *reinterpret_cast<typename GenericCArray<T>::type *>(field);
ser.serializeSequence(reinterpret_cast<T *>(data.data), data.size);
}
}
template<>
inline
void serialize_field<std::string>(
const rosidl_typesupport_introspection_c__MessageMember * member,
void * field,
eprosima::fastcdr::Cdr & ser)
{
using CStringHelper = StringHelper<rosidl_typesupport_introspection_c__MessageMembers>;
if (!member->is_array_) {
auto && str = CStringHelper::convert_to_std_string(field);
// Control maximum length.
if (member->string_upper_bound_ && str.length() > member->string_upper_bound_ + 1) {
throw std::runtime_error("string overcomes the maximum length");
}
ser << str;
} else {
// First, cast field to rosidl_generator_c
// Then convert to a std::string using StringHelper and serialize the std::string
if (member->array_size_ && !member->is_upper_bound_) {
// 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);
for (size_t i = 0; i < member->array_size_; ++i) {
tmpstring = string_field[i].data;
ser.serialize(tmpstring);
}
} else {
auto & string_array_field = *reinterpret_cast<rosidl_generator_c__String__Array *>(field);
std::vector<std::string> cpp_string_vector;
for (size_t i = 0; i < string_array_field.size; ++i) {
cpp_string_vector.push_back(
CStringHelper::convert_to_std_string(string_array_field.data[i]));
}
ser << cpp_string_vector;
}
}
}
inline
size_t get_array_size_and_assign_field(
const rosidl_typesupport_introspection_cpp::MessageMember * member,
void * field,
void * & subros_message,
size_t sub_members_size,
size_t max_align)
{
auto vector = reinterpret_cast<std::vector<unsigned char> *>(field);
void * ptr = reinterpret_cast<void *>(sub_members_size);
size_t vsize = vector->size() / reinterpret_cast<size_t>(align_(max_align, ptr));
if (member->is_upper_bound_ && vsize > member->array_size_) {
throw std::runtime_error("vector overcomes the maximum length");
}
subros_message = reinterpret_cast<void *>(vector->data());
return vsize;
}
inline
size_t get_array_size_and_assign_field(
const rosidl_typesupport_introspection_c__MessageMember * member,
void * 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_) {
throw std::runtime_error("vector overcomes the maximum length");
}
subros_message = reinterpret_cast<void *>(tmparray->data);
return tmparray->size;
}
template<typename MembersType>
bool TypeSupport<MembersType>::serializeROSmessage(
eprosima::fastcdr::Cdr & ser, const MembersType * members, const void * ros_message)
{
assert(members);
assert(ros_message);
for (uint32_t i = 0; i < members->member_count_; ++i) {
const auto member = members->members_ + i;
void * field = const_cast<char *>(static_cast<const char *>(ros_message)) + member->offset_;
switch (member->type_id_) {
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BOOL:
if (!member->is_array_) {
// don't cast to bool here because if the bool is
// uninitialized the random value can't be deserialized
ser << (*static_cast<uint8_t *>(field) ? true : false);
} else {
serialize_field<bool>(member, field, ser);
}
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BYTE:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT8:
serialize_field<uint8_t>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_CHAR:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT8:
serialize_field<char>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT32:
serialize_field<float>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT64:
serialize_field<double>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT16:
serialize_field<int16_t>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT16:
serialize_field<uint16_t>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT32:
serialize_field<int32_t>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT32:
serialize_field<uint32_t>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT64:
serialize_field<int64_t>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT64:
serialize_field<uint64_t>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_STRING:
serialize_field<std::string>(member, field, ser);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE:
{
auto sub_members = static_cast<const MembersType *>(member->members_->data);
if (!member->is_array_) {
serializeROSmessage(ser, sub_members, field);
} else {
void * subros_message = nullptr;
size_t array_size = 0;
size_t sub_members_size = sub_members->size_of_;
size_t max_align = calculateMaxAlign(sub_members);
if (member->array_size_ && !member->is_upper_bound_) {
subros_message = field;
array_size = member->array_size_;
} else {
array_size = get_array_size_and_assign_field(
member, field, subros_message, sub_members_size, max_align);
// Serialize length
ser << (uint32_t)array_size;
}
for (size_t index = 0; index < array_size; ++index) {
serializeROSmessage(ser, sub_members, subros_message);
subros_message = static_cast<char *>(subros_message) + sub_members_size;
subros_message = align_(max_align, subros_message);
}
}
}
break;
default:
throw std::runtime_error("unknown type");
}
}
return true;
}
template<typename T>
void deserialize_field(
const rosidl_typesupport_introspection_cpp::MessageMember * member,
void * field,
eprosima::fastcdr::Cdr & deser,
bool call_new)
{
if (!member->is_array_) {
deser >> *static_cast<T *>(field);
} else if (member->array_size_ && !member->is_upper_bound_) {
deser.deserializeArray(static_cast<T *>(field), member->array_size_);
} else {
auto & vector = *reinterpret_cast<std::vector<T> *>(field);
if (call_new) {
new(&vector) std::vector<T>;
}
deser >> vector;
}
}
template<typename T>
void deserialize_field(
const rosidl_typesupport_introspection_c__MessageMember * member,
void * field,
eprosima::fastcdr::Cdr & deser,
bool call_new)
{
(void)call_new;
if (!member->is_array_) {
deser >> *static_cast<T *>(field);
} else if (member->array_size_ && !member->is_upper_bound_) {
deser.deserializeArray(static_cast<T *>(field), member->array_size_);
} else {
auto & data = *reinterpret_cast<typename GenericCArray<T>::type *>(field);
int32_t dsize = 0;
deser >> dsize;
GenericCArray<T>::init(&data, dsize);
deser.deserializeArray(reinterpret_cast<T *>(data.data), dsize);
}
}
template<>
inline void deserialize_field<std::string>(
const rosidl_typesupport_introspection_c__MessageMember * member,
void * field,
eprosima::fastcdr::Cdr & deser,
bool call_new)
{
(void)call_new;
if (!member->is_array_) {
using CStringHelper = StringHelper<rosidl_typesupport_introspection_c__MessageMembers>;
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);
// 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");
}
}
} else {
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())) {
throw std::runtime_error("unable to initialize rosidl_generator_c__String array");
}
for (size_t i = 0; i < cpp_string_vector.size(); ++i) {
if (!rosidl_generator_c__String__assign(&string_array_field.data[i],
cpp_string_vector[i].c_str()))
{
throw std::runtime_error("unable to assign rosidl_generator_c__String");
}
}
}
}
}
inline size_t get_submessage_array_deserialize(
const rosidl_typesupport_introspection_cpp::MessageMember * member,
eprosima::fastcdr::Cdr & deser,
void * field,
void * & subros_message,
bool call_new,
size_t sub_members_size,
size_t max_align)
{
(void)member;
uint32_t vsize = 0;
// Deserialize length
deser >> vsize;
auto vector = reinterpret_cast<std::vector<unsigned char> *>(field);
if (call_new) {
new(vector) std::vector<unsigned char>;
}
void * ptr = reinterpret_cast<void *>(sub_members_size);
vector->resize(vsize * (size_t)align_(max_align, ptr));
subros_message = reinterpret_cast<void *>(vector->data());
return vsize;
}
inline size_t get_submessage_array_deserialize(
const rosidl_typesupport_introspection_c__MessageMember * member,
eprosima::fastcdr::Cdr & deser,
void * field,
void * & subros_message,
bool,
size_t sub_members_size,
size_t)
{
(void)member;
// 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);
subros_message = reinterpret_cast<void *>(tmparray->data);
return vsize;
}
template<typename MembersType>
bool TypeSupport<MembersType>::deserializeROSmessage(
eprosima::fastcdr::Cdr & deser, const MembersType * members, void * ros_message, bool call_new)
{
assert(members);
assert(ros_message);
for (uint32_t i = 0; i < members->member_count_; ++i) {
const auto * member = members->members_ + i;
void * field = static_cast<char *>(ros_message) + member->offset_;
switch (member->type_id_) {
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BOOL:
deserialize_field<bool>(member, field, deser, call_new);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BYTE:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT8:
deserialize_field<uint8_t>(member, field, deser, call_new);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_CHAR:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT8:
deserialize_field<char>(member, field, deser, call_new);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT32:
deserialize_field<float>(member, field, deser, call_new);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT64:
deserialize_field<double>(member, field, deser, call_new);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT16:
deserialize_field<int16_t>(member, field, deser, call_new);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT16:
deserialize_field<uint16_t>(member, field, deser, call_new);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT32:
deserialize_field<int32_t>(member, field, deser, call_new);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT32:
deserialize_field<uint32_t>(member, field, deser, call_new);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT64:
deserialize_field<int64_t>(member, field, deser, call_new);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT64:
deserialize_field<uint64_t>(member, field, deser, call_new);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_STRING:
deserialize_field<std::string>(member, field, deser, call_new);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE:
{
auto sub_members = (const MembersType *)member->members_->data;
if (!member->is_array_) {
deserializeROSmessage(deser, sub_members, field, call_new);
} else {
void * subros_message = nullptr;
size_t array_size = 0;
size_t sub_members_size = sub_members->size_of_;
size_t max_align = calculateMaxAlign(sub_members);
bool recall_new = call_new;
if (member->array_size_ && !member->is_upper_bound_) {
subros_message = field;
array_size = member->array_size_;
} else {
array_size = get_submessage_array_deserialize(
member, deser, field, subros_message,
call_new, sub_members_size, max_align);
recall_new = true;
}
for (size_t index = 0; index < array_size; ++index) {
deserializeROSmessage(deser, sub_members, subros_message, recall_new);
subros_message = static_cast<char *>(subros_message) + sub_members_size;
subros_message = align_(max_align, subros_message);
}
}
}
break;
default:
throw std::runtime_error("unknown type");
}
}
return true;
}
template<typename MembersType>
size_t TypeSupport<MembersType>::calculateMaxSerializedSize(
const MembersType * members, size_t current_alignment)
{
assert(members);
size_t initial_alignment = current_alignment;
// Encapsulation
const size_t padding = 4;
current_alignment += padding;
for (uint32_t i = 0; i < members->member_count_; ++i) {
const auto * member = members->members_ + i;
size_t array_size = 1;
if (member->is_array_) {
array_size = member->array_size_;
// Whether it is a sequence.
if (array_size == 0 || member->is_upper_bound_) {
current_alignment += padding +
eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
}
}
switch (member->type_id_) {
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BOOL:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BYTE:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT8:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_CHAR:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT8:
current_alignment += array_size * sizeof(int8_t);
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT16:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT16:
current_alignment += array_size * sizeof(uint16_t) +
eprosima::fastcdr::Cdr::alignment(current_alignment, sizeof(uint16_t));
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT32:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT32:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT32:
current_alignment += array_size * sizeof(uint32_t) +
eprosima::fastcdr::Cdr::alignment(current_alignment, sizeof(uint32_t));
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT64:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT64:
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT64:
current_alignment += array_size * sizeof(uint64_t) +
eprosima::fastcdr::Cdr::alignment(current_alignment, sizeof(uint64_t));
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_STRING:
{
for (size_t index = 0; index < array_size; ++index) {
current_alignment += padding +
eprosima::fastcdr::Cdr::alignment(current_alignment, padding) +
member->string_upper_bound_ + 1;
}
}
break;
case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE:
{
auto sub_members = static_cast<const MembersType *>(member->members_->data);
for (size_t index = 0; index < array_size; ++index) {
current_alignment += calculateMaxSerializedSize(sub_members, current_alignment);
}
}
break;
default:
throw std::runtime_error("unknown type");
}
}
return current_alignment - initial_alignment;
}
template<typename MembersType>
bool TypeSupport<MembersType>::serializeROSmessage(
const void * ros_message, eprosima::fastcdr::Cdr & ser,
std::function<void(eprosima::fastcdr::Cdr&)> prefix)
{
assert(ros_message);
// Serialize encapsulation
ser.serialize_encapsulation();
if (prefix) {
prefix(ser);
}
if (members_->member_count_ != 0) {
TypeSupport::serializeROSmessage(ser, members_, ros_message);
} else {
ser << (uint8_t)0;
}
return true;
}
template<typename MembersType>
bool TypeSupport<MembersType>::deserializeROSmessage(
eprosima::fastcdr::Cdr & deser, void * ros_message,
std::function<void(eprosima::fastcdr::Cdr&)> prefix)
{
assert(ros_message);
// Deserialize encapsulation.
deser.read_encapsulation();
if (prefix) {
prefix(deser);
}
if (members_->member_count_ != 0) {
TypeSupport::deserializeROSmessage(deser, members_, ros_message, false);
} else {
uint8_t dump = 0;
deser >> dump;
(void)dump;
}
return true;
}
#if 0
template<typename MembersType>
std::function<uint32_t()> TypeSupport<MembersType>::getSerializedSizeProvider(void * data)
{
assert(data);
auto ser = static_cast<eprosima::fastcdr::Cdr *>(data);
return [ser]() -> uint32_t {return static_cast<uint32_t>(ser->getSerializedDataLength());};
}
#endif
} // namespace rmw_cyclonedds_cpp
#endif // RMW_CYCLONEDDS_CPP__TYPESUPPORT_IMPL_HPP_

View file

@ -0,0 +1,36 @@
// Copyright 2016 Open Source Robotics Foundation, Inc.
//
// 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 RMW_CYCLONEDDS_CPP__MACROS_HPP_
#define RMW_CYCLONEDDS_CPP__MACROS_HPP_
#include <limits>
#include <string>
#define SPECIALIZE_GENERIC_C_ARRAY(C_NAME, C_TYPE) \
template<> \
struct GenericCArray<C_TYPE> \
{ \
using type = rosidl_generator_c__ ## C_NAME ## __Array; \
\
static void fini(type * array) { \
rosidl_generator_c__ ## C_NAME ## __Array__fini(array); \
} \
\
static bool init(type * array, size_t size) { \
return rosidl_generator_c__ ## C_NAME ## __Array__init(array, size); \
} \
};
#endif // RMW_CYCLONEDDS_CPP__MACROS_HPP_

View file

@ -0,0 +1,56 @@
// Copyright 2017 Open Source Robotics Foundation, Inc.
//
// 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.
/* This header must be included by all rclcpp headers which declare symbols
* which are defined in the rclcpp library. When not building the rclcpp
* library, i.e. when using the headers in other package's code, the contents
* of this header change the visibility of certain symbols which the rclcpp
* library cannot have, but the consuming code must have inorder to link.
*/
#ifndef RMW_CYCLONEDDS_CPP__VISIBILITY_CONTROL_H_
#define RMW_CYCLONEDDS_CPP__VISIBILITY_CONTROL_H_
// This logic was borrowed (then namespaced) from the examples on the gcc wiki:
// https://gcc.gnu.org/wiki/Visibility
#if defined _WIN32 || defined __CYGWIN__
#ifdef __GNUC__
#define RMW_CYCLONEDDS_CPP_EXPORT __attribute__ ((dllexport))
#define RMW_CYCLONEDDS_CPP_IMPORT __attribute__ ((dllimport))
#else
#define RMW_CYCLONEDDS_CPP_EXPORT __declspec(dllexport)
#define RMW_CYCLONEDDS_CPP_IMPORT __declspec(dllimport)
#endif
#ifdef RMW_CYCLONEDDS_CPP_BUILDING_LIBRARY
#define RMW_CYCLONEDDS_CPP_PUBLIC RMW_CYCLONEDDS_CPP_EXPORT
#else
#define RMW_CYCLONEDDS_CPP_PUBLIC RMW_CYCLONEDDS_CPP_IMPORT
#endif
#define RMW_CYCLONEDDS_CPP_PUBLIC_TYPE RMW_CYCLONEDDS_CPP_PUBLIC
#define RMW_CYCLONEDDS_CPP_LOCAL
#else
#define RMW_CYCLONEDDS_CPP_EXPORT __attribute__ ((visibility("default")))
#define RMW_CYCLONEDDS_CPP_IMPORT
#if __GNUC__ >= 4
#define RMW_CYCLONEDDS_CPP_PUBLIC __attribute__ ((visibility("default")))
#define RMW_CYCLONEDDS_CPP_LOCAL __attribute__ ((visibility("hidden")))
#else
#define RMW_CYCLONEDDS_CPP_PUBLIC
#define RMW_CYCLONEDDS_CPP_LOCAL
#endif
#define RMW_CYCLONEDDS_CPP_PUBLIC_TYPE
#endif
#endif // RMW_CYCLONEDDS_CPP__VISIBILITY_CONTROL_H_

View file

@ -0,0 +1,41 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>rmw_cyclonedds_cpp</name>
<version>0.4.0</version>
<description>Implement the ROS middleware interface using Eclipse CycloneDDS in C++.</description>
<maintainer email="erik.boasson@adlinktech.com">Erik Boasson</maintainer>
<license>Apache License 2.0</license>
<buildtool_depend>ament_cmake_ros</buildtool_depend>
<buildtool_depend>cyclonedds_cmake_module</buildtool_depend>
<buildtool_export_depend>ament_cmake</buildtool_export_depend>
<build_depend>fastcdr</build_depend>
<build_depend>cyclonedds</build_depend>
<build_depend>cyclonedds_cmake_module</build_depend>
<build_depend>rcutils</build_depend>
<build_depend>rmw</build_depend>
<build_depend>rosidl_generator_c</build_depend>
<build_depend>rosidl_typesupport_introspection_c</build_depend>
<build_depend>rosidl_typesupport_introspection_cpp</build_depend>
<build_export_depend>fastcdr</build_export_depend>
<build_export_depend>cyclonedds</build_export_depend>
<build_export_depend>cyclonedds_cmake_module</build_export_depend>
<build_export_depend>rcutils</build_export_depend>
<build_export_depend>rmw</build_export_depend>
<build_export_depend>rosidl_generator_c</build_export_depend>
<build_export_depend>rosidl_typesupport_introspection_c</build_export_depend>
<build_export_depend>rosidl_typesupport_introspection_cpp</build_export_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<member_of_group>rmw_implementation_packages</member_of_group>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

View file

@ -0,0 +1,19 @@
# Copyright 2017 Open Source Robotics Foundation, Inc.
#
# 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.
# copied from rmw_fastrtps_cpp/rmw_fastrtps_cpp-extras.cmake
find_package(fastcdr REQUIRED CONFIG)
list(APPEND rmw_fastrtps_cpp_LIBRARIES fastcdr)

View file

@ -0,0 +1,41 @@
// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima).
//
// 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 <string>
#include <vector>
#include "namespace_prefix.hpp"
extern "C"
{
// static for internal linkage
const char * const ros_topic_prefix = "rt";
const char * const ros_service_requester_prefix = "rq";
const char * const ros_service_response_prefix = "rr";
const std::vector<std::string> _ros_prefixes =
{ros_topic_prefix, ros_service_requester_prefix, ros_service_response_prefix};
} // extern "C"
/// Return the ROS specific prefix if it exists, otherwise "".
std::string
_get_ros_prefix_if_exists(const std::string & topic_name)
{
for (auto prefix : _ros_prefixes) {
if (topic_name.rfind(std::string(prefix) + "/", 0) == 0) {
return prefix;
}
}
return "";
}

View file

@ -0,0 +1,34 @@
// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima).
//
// 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 NAMESPACE_PREFIX_HPP_
#define NAMESPACE_PREFIX_HPP_
#include <vector>
#include <string>
extern "C"
{
extern const char * const ros_topic_prefix;
extern const char * const ros_service_requester_prefix;
extern const char * const ros_service_response_prefix;
extern const std::vector<std::string> _ros_prefixes;
} // extern "C"
/// Return the ROS specific prefix if it exists, otherwise "".
std::string
_get_ros_prefix_if_exists(const std::string & topic_name);
#endif // NAMESPACE_PREFIX_HPP_

View file

@ -0,0 +1,8 @@
module rmw {
module cyclonedds {
struct topic {
boolean dummy;
};
#pragma keylist rmw::cyclonedds::topic
};
};

File diff suppressed because it is too large Load diff