Serialized message move constructor (#1097)

* correct use of move semantics

Signed-off-by: Knese Karsten <karsten@openrobotics.org>

* more tests

Signed-off-by: Knese Karsten <karsten@openrobotics.org>

* make error message more exact

Signed-off-by: Karsten Knese <karsten@openrobotics.org>

* use std::exchange

Signed-off-by: Karsten Knese <karsten@openrobotics.org>

* fix typo

Signed-off-by: Karsten Knese <karsten@openrobotics.org>
This commit is contained in:
Karsten Knese 2020-04-27 22:23:43 -07:00 committed by GitHub
parent 814298480c
commit c1b80bd367
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
3 changed files with 60 additions and 27 deletions

View file

@ -55,8 +55,11 @@ void SerializationBase::deserialize_message(
rcpputils::check_true(nullptr != type_support_, "Typesupport is nullpointer."); rcpputils::check_true(nullptr != type_support_, "Typesupport is nullpointer.");
rcpputils::check_true(nullptr != serialized_message, "Serialized message is nullpointer."); rcpputils::check_true(nullptr != serialized_message, "Serialized message is nullpointer.");
rcpputils::check_true( rcpputils::check_true(
0 != serialized_message->capacity() && 0 != serialized_message->size(), 0u != serialized_message->capacity(),
"Serialized message is wrongly initialized."); "Wrongly initialized. Serialized message has a capacity of zero.");
rcpputils::check_true(
0u != serialized_message->size(),
"Wrongly initialized. Serialized message has a size of zero.");
rcpputils::check_true(nullptr != ros_message, "ROS message is a nullpointer."); rcpputils::check_true(nullptr != ros_message, "ROS message is a nullpointer.");
const auto ret = rmw_deserialize( const auto ret = rmw_deserialize(

View file

@ -66,50 +66,51 @@ SerializedMessage::SerializedMessage(const rcl_serialized_message_t & other)
} }
SerializedMessage::SerializedMessage(SerializedMessage && other) SerializedMessage::SerializedMessage(SerializedMessage && other)
: SerializedMessage(other.serialized_message_) : serialized_message_(
{ std::exchange(other.serialized_message_, rmw_get_zero_initialized_serialized_message()))
other.serialized_message_ = rmw_get_zero_initialized_serialized_message(); {}
}
SerializedMessage::SerializedMessage(rcl_serialized_message_t && other) SerializedMessage::SerializedMessage(rcl_serialized_message_t && other)
: serialized_message_(other) : serialized_message_(
{ std::exchange(other, rmw_get_zero_initialized_serialized_message()))
// reset buffer to prevent double free {}
other = rmw_get_zero_initialized_serialized_message();
}
SerializedMessage & SerializedMessage::operator=(const SerializedMessage & other) SerializedMessage & SerializedMessage::operator=(const SerializedMessage & other)
{ {
serialized_message_ = rmw_get_zero_initialized_serialized_message(); if (this != &other) {
copy_rcl_message(other.serialized_message_, serialized_message_); serialized_message_ = rmw_get_zero_initialized_serialized_message();
copy_rcl_message(other.serialized_message_, serialized_message_);
}
return *this; return *this;
} }
SerializedMessage & SerializedMessage::operator=(const rcl_serialized_message_t & other) SerializedMessage & SerializedMessage::operator=(const rcl_serialized_message_t & other)
{ {
serialized_message_ = rmw_get_zero_initialized_serialized_message(); if (&serialized_message_ != &other) {
copy_rcl_message(other, serialized_message_); serialized_message_ = rmw_get_zero_initialized_serialized_message();
copy_rcl_message(other, serialized_message_);
}
return *this; return *this;
} }
SerializedMessage & SerializedMessage::operator=(SerializedMessage && other) SerializedMessage & SerializedMessage::operator=(SerializedMessage && other)
{ {
*this = other.serialized_message_; if (this != &other) {
other.serialized_message_ = rmw_get_zero_initialized_serialized_message(); serialized_message_ =
std::exchange(other.serialized_message_, rmw_get_zero_initialized_serialized_message());
}
return *this; return *this;
} }
SerializedMessage & SerializedMessage::operator=(rcl_serialized_message_t && other) SerializedMessage & SerializedMessage::operator=(rcl_serialized_message_t && other)
{ {
serialized_message_ = rmw_get_zero_initialized_serialized_message(); if (&serialized_message_ != &other) {
serialized_message_ = other; serialized_message_ =
std::exchange(other, rmw_get_zero_initialized_serialized_message());
// reset original to prevent double free }
other = rmw_get_zero_initialized_serialized_message();
return *this; return *this;
} }

View file

@ -52,6 +52,7 @@ TEST(TestSerializedMessage, various_constructors) {
rcl_handle.buffer_length = content_size; rcl_handle.buffer_length = content_size;
EXPECT_STREQ(content.c_str(), reinterpret_cast<char *>(rcl_handle.buffer)); EXPECT_STREQ(content.c_str(), reinterpret_cast<char *>(rcl_handle.buffer));
EXPECT_EQ(content_size, serialized_message.capacity()); EXPECT_EQ(content_size, serialized_message.capacity());
EXPECT_EQ(content_size, serialized_message.size());
// Copy Constructor // Copy Constructor
rclcpp::SerializedMessage other_serialized_message(serialized_message); rclcpp::SerializedMessage other_serialized_message(serialized_message);
@ -158,9 +159,9 @@ TEST(TestSerializedMessage, serialization) {
} }
} }
template<typename MessageT> void serialize_default_ros_msg()
void test_empty_msg_serialize()
{ {
using MessageT = test_msgs::msg::BasicTypes;
rclcpp::Serialization<MessageT> serializer; rclcpp::Serialization<MessageT> serializer;
MessageT ros_msg; MessageT ros_msg;
rclcpp::SerializedMessage serialized_msg; rclcpp::SerializedMessage serialized_msg;
@ -168,12 +169,40 @@ void test_empty_msg_serialize()
serializer.serialize_message(&ros_msg, &serialized_msg); serializer.serialize_message(&ros_msg, &serialized_msg);
} }
template<typename MessageT> void serialize_default_ros_msg_into_nullptr()
void test_empty_msg_deserialize()
{ {
using MessageT = test_msgs::msg::BasicTypes;
rclcpp::Serialization<MessageT> serializer;
MessageT ros_msg;
serializer.serialize_message(&ros_msg, nullptr);
}
void deserialize_default_serialized_message()
{
using MessageT = test_msgs::msg::BasicTypes;
rclcpp::Serialization<MessageT> serializer; rclcpp::Serialization<MessageT> serializer;
MessageT ros_msg; MessageT ros_msg;
rclcpp::SerializedMessage serialized_msg; rclcpp::SerializedMessage serialized_msg;
serializer.deserialize_message(&serialized_msg, &ros_msg); serializer.deserialize_message(&serialized_msg, &ros_msg);
} }
void deserialize_nullptr()
{
using MessageT = test_msgs::msg::BasicTypes;
rclcpp::Serialization<MessageT> serializer;
MessageT ros_msg;
rclcpp::SerializedMessage serialized_msg;
serializer.deserialize_message(&serialized_msg, &ros_msg);
}
TEST(TestSerializedMessage, serialization_empty_messages)
{
EXPECT_NO_THROW(serialize_default_ros_msg());
EXPECT_THROW(serialize_default_ros_msg_into_nullptr(), rcpputils::IllegalStateException);
EXPECT_THROW(serialize_default_ros_msg_into_nullptr(), rcpputils::IllegalStateException);
EXPECT_THROW(deserialize_default_serialized_message(), rcpputils::IllegalStateException);
EXPECT_THROW(deserialize_nullptr(), rcpputils::IllegalStateException);
}