Skip to content

Commit

Permalink
cosmetic touchups
Browse files Browse the repository at this point in the history
Signed-off-by: Karsten Knese <karsten@openrobotics.org>
  • Loading branch information
Karsten1987 committed Apr 21, 2020
1 parent 1b87de0 commit 306d58c
Show file tree
Hide file tree
Showing 5 changed files with 58 additions and 130 deletions.
117 changes: 28 additions & 89 deletions rclcpp/include/rclcpp/serialization.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,18 +27,39 @@

#include "rosidl_typesupport_cpp/message_type_support.hpp"


namespace rclcpp
{

class SerializedMessage;

namespace serialization_traits
{
// trait to check if type is the object oriented serialized message
template<typename T>
struct is_serialized_message_class : std::false_type
{};

template<>
struct is_serialized_message_class<rcl_serialized_message_t>: std::true_type
{};

template<>
struct is_serialized_message_class<SerializedMessage>: std::true_type
{};
} // namespace serialization_traits

/// Interface to (de)serialize a message
class RCLCPP_PUBLIC_TYPE SerializationBase
{
protected:
public:
/// Constructor of SerializationBase
/**
* \param[in] type_support handle for the message type support
* to be used for serialization and deserialization.
*/
explicit SerializationBase(const rosidl_message_type_support_t * type_support);

/// Destructor of SerializationBase
virtual ~SerializationBase() = default;

/// Serialize a ROS2 message to a serialized stream
Expand All @@ -57,6 +78,7 @@ class RCLCPP_PUBLIC_TYPE SerializationBase
void deserialize_message(
const SerializedMessage * serialized_message, void * ros_message) const;

private:
const rosidl_message_type_support_t * type_support_;
};

Expand All @@ -65,99 +87,16 @@ template<typename MessageT>
class Serialization : public SerializationBase
{
public:
/// Constructor of Serialization
Serialization()
: SerializationBase(rosidl_typesupport_cpp::get_message_type_support_handle<MessageT>())
{}

void serialize_message(
const MessageT & ros_message, SerializedMessage & serialized_message) const
{
SerializationBase::serialize_message(
reinterpret_cast<const void *>(&ros_message),
&serialized_message);
}

void deserialize_message(
const SerializedMessage & serialized_message, MessageT & ros_message) const
{
SerializationBase::deserialize_message(
&serialized_message,
reinterpret_cast<void *>(&ros_message));
static_assert(
!serialization_traits::is_serialized_message_class<MessageT>::value,
"Serialization of serialized message to serialized message is not possible.");
}
};

template<>
class Serialization<SerializedMessage>: public SerializationBase
{
public:
Serialization()
: SerializationBase(nullptr)
{}

void serialize_message(
const SerializedMessage & ros_message,
SerializedMessage & serialized_message) const
{
(void)ros_message;
(void)serialized_message;
throw std::runtime_error(
"Serialization of serialized message to serialized message is not possible.");
}

void deserialize_message(
const SerializedMessage & serialized_message,
SerializedMessage & ros_message) const
{
(void)ros_message;
(void)serialized_message;
throw std::runtime_error(
"Deserialization of serialized message to serialized message is not possible.");
}
};

template<>
class Serialization<rcl_serialized_message_t>: public SerializationBase
{
public:
Serialization()
: SerializationBase(nullptr)
{}

void serialize_message(
rcl_serialized_message_t & ros_message,
const SerializedMessage & serialized_message) const
{
(void)ros_message;
(void)serialized_message;
throw std::runtime_error(
"Serialization of serialized message to serialized message is not possible.");
}

void deserialize_message(
const SerializedMessage & serialized_message,
rcl_serialized_message_t & ros_message) const
{
(void)ros_message;
(void)serialized_message;
throw std::runtime_error(
"Deserialization of serialized message to serialized message is not possible.");
}
};

// trait to check if type is the object oriented serialized message
template<typename T>
struct is_serialized_message_class : std::false_type
{};

template<>
struct is_serialized_message_class<rcl_serialized_message_t>: std::false_type
{};

template<>
struct is_serialized_message_class<SerializedMessage>
: std::true_type
{};

} // namespace rclcpp

#endif // RCLCPP__SERIALIZATION_HPP_
12 changes: 9 additions & 3 deletions rclcpp/include/rclcpp/serialized_message.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ class RCLCPP_PUBLIC_TYPE SerializedMessage : public rcl_serialized_message_t
/**
* Default constructs a serialized message and initalizes it
* with initial capacity of 0.
* The allocator defaults to `rcl_get_default_allocator()`.
*
* \param[in] allocator The allocator to be used for the initialization.
*/
Expand All @@ -40,7 +41,8 @@ class RCLCPP_PUBLIC_TYPE SerializedMessage : public rcl_serialized_message_t
/// Default constructor for a SerializedMessage
/**
* Default constructs a serialized message and initalizes it
* with initial capacity of 0.
* with the provided capacity.
* The allocator defaults to `rcl_get_default_allocator()`.
*
* \param[in] initial_capacity The amount of memory to be allocated.
* \param[in] allocator The allocator to be used for the initialization.
Expand All @@ -52,21 +54,25 @@ class RCLCPP_PUBLIC_TYPE SerializedMessage : public rcl_serialized_message_t
/// Copy Constructor for a SerializedMessage
SerializedMessage(const SerializedMessage & serialized_message);

/// Copy Constructor for a SerializedMessage from a rcl_serialized_message_t
/// Constructor for a SerializedMessage from a rcl_serialized_message_t
explicit SerializedMessage(const rcl_serialized_message_t & serialized_message);

/// Move Constructor for a SerializedMessage
SerializedMessage(SerializedMessage && serialized_message);

/// Move Constructor for a SerializedMessage from a rcl_serialized_message_t
/// Constructor for a SerializedMessage from a moved rcl_serialized_message_t
explicit SerializedMessage(rcl_serialized_message_t && serialized_message);

/// Copy assignment operator
SerializedMessage & operator=(const SerializedMessage & other);

/// Copy assignment operator from a rcl_serialized_message_t
SerializedMessage & operator=(const rcl_serialized_message_t & other);

/// Move assignment operator
SerializedMessage & operator=(SerializedMessage && other);

/// Move assignment operator from a rcl_serialized_message_t
SerializedMessage & operator=(rcl_serialized_message_t && other);

/// Destructor for a SerializedMessage
Expand Down
25 changes: 13 additions & 12 deletions rclcpp/src/rclcpp/serialization.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,14 +29,16 @@ namespace rclcpp

SerializationBase::SerializationBase(const rosidl_message_type_support_t * type_support)
: type_support_(type_support)
{}
{
rcpputils::check_true(nullptr != type_support, "Typesupport is nullpointer.");
}

void SerializationBase::serialize_message(
const void * ros_message, SerializedMessage * serialized_message) const
{
rcpputils::check_true(type_support_ != nullptr, "Typesupport is nullpointer.");
rcpputils::check_true(ros_message != nullptr, "ROS message is nullpointer.");
rcpputils::check_true(serialized_message != nullptr, "Serialized message is nullpointer.");
rcpputils::check_true(nullptr != type_support_, "Typesupport is nullpointer.");
rcpputils::check_true(nullptr != ros_message, "ROS message is nullpointer.");
rcpputils::check_true(nullptr != serialized_message, "Serialized message is nullpointer.");

const auto ret = rmw_serialize(
ros_message,
Expand All @@ -47,17 +49,16 @@ void SerializationBase::serialize_message(
}
}

void
SerializationBase::deserialize_message(
void SerializationBase::deserialize_message(
const SerializedMessage * serialized_message, void * ros_message) const
{
rcpputils::check_true(type_support_ != nullptr, "Typesupport is nullpointer.");
rcpputils::check_true(serialized_message != nullptr, "Serialized message is nullpointer.");
rcpputils::check_true(nullptr != type_support_, "Typesupport is nullpointer.");
rcpputils::check_true(nullptr != serialized_message, "Serialized message is nullpointer.");
rcpputils::check_true(
serialized_message->buffer_capacity != 0 &&
serialized_message->buffer_length != 0 &&
serialized_message->buffer != nullptr, "Serialized message is wrongly initialized.");
rcpputils::check_true(ros_message != nullptr, "ROS message is a nullpointer.");
0 != serialized_message->buffer_capacity &&
0 != serialized_message->buffer_length &&
nullptr != serialized_message->buffer, "Serialized message is wrongly initialized.");
rcpputils::check_true(nullptr != ros_message, "ROS message is a nullpointer.");

const auto ret = rmw_deserialize(serialized_message, type_support_, ros_message);
if (ret != RMW_RET_OK) {
Expand Down
8 changes: 4 additions & 4 deletions rclcpp/src/rclcpp/serialized_message.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ SerializedMessage::SerializedMessage(
{
const auto ret = rmw_serialized_message_init(
this, initial_capacity, &allocator);
if (ret != RCL_RET_OK) {
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret);
}
}
Expand All @@ -49,7 +49,7 @@ SerializedMessage::SerializedMessage(const rcl_serialized_message_t & serialized
{
const auto ret = rmw_serialized_message_init(
this, serialized_message.buffer_capacity, &serialized_message.allocator);
if (ret != RCL_RET_OK) {
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret);
}

Expand Down Expand Up @@ -86,7 +86,7 @@ SerializedMessage & SerializedMessage::operator=(const rcl_serialized_message_t

const auto ret = rmw_serialized_message_init(
this, other.buffer_capacity, &other.allocator);
if (ret != RCL_RET_OK) {
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret);
}

Expand Down Expand Up @@ -123,7 +123,7 @@ SerializedMessage::~SerializedMessage()
{
if (nullptr != buffer) {
const auto fini_ret = rmw_serialized_message_fini(this);
if (fini_ret != RCL_RET_OK) {
if (RCL_RET_OK != fini_ret) {
RCLCPP_ERROR(
get_logger("rclcpp"),
"Failed to destroy serialized message: %s", rcl_get_error_string().str);
Expand Down
26 changes: 4 additions & 22 deletions rclcpp/test/test_serialized_message.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,11 +118,11 @@ TEST(TestSerializedMessage, serialization) {
for (const auto & ros_msg : basic_type_ros_msgs) {
// convert ros msg to serialized msg
rclcpp::SerializedMessage serialized_msg;
serializer.serialize_message(*ros_msg, serialized_msg);
serializer.serialize_message(ros_msg.get(), &serialized_msg);

// convert serialized msg back to ros msg
MessageT deserialized_ros_msg;
serializer.deserialize_message(serialized_msg, deserialized_ros_msg);
serializer.deserialize_message(&serialized_msg, &deserialized_ros_msg);

EXPECT_EQ(*ros_msg, deserialized_ros_msg);
}
Expand All @@ -135,7 +135,7 @@ void test_empty_msg_serialize()
MessageT ros_msg;
rclcpp::SerializedMessage serialized_msg;

serializer.serialize_message(ros_msg, serialized_msg);
serializer.serialize_message(&ros_msg, &serialized_msg);
}

template<typename MessageT>
Expand All @@ -145,23 +145,5 @@ void test_empty_msg_deserialize()
MessageT ros_msg;
rclcpp::SerializedMessage serialized_msg;

serializer.deserialize_message(serialized_msg, ros_msg);
}

TEST(TestSerializedMessage, serialization_invalid) {
// serialized messages (used as ROS message) should throw an exception while (de)serialization

EXPECT_THROW(
test_empty_msg_serialize<rclcpp::SerializedMessage>(),
std::runtime_error);
EXPECT_THROW(
test_empty_msg_serialize<rcl_serialized_message_t>(),
std::runtime_error);

EXPECT_THROW(
test_empty_msg_deserialize<rclcpp::SerializedMessage>(),
std::runtime_error);
EXPECT_THROW(
test_empty_msg_deserialize<rcl_serialized_message_t>(),
std::runtime_error);
serializer.deserialize_message(&serialized_msg, &ros_msg);
}

0 comments on commit 306d58c

Please sign in to comment.