forked from ros2/rclcpp
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathserialized_message.cpp
More file actions
164 lines (136 loc) · 4.64 KB
/
serialized_message.cpp
File metadata and controls
164 lines (136 loc) · 4.64 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
// Copyright 2020 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.
#include "rclcpp/serialized_message.hpp"
#include <cstring>
#include "rclcpp/exceptions.hpp"
#include "rclcpp/logging.hpp"
#include "rmw/types.h"
namespace rclcpp
{
inline void copy_rcl_message(const rcl_serialized_message_t & from, rcl_serialized_message_t & to)
{
const auto ret = rmw_serialized_message_init(
&to, from.buffer_capacity, &from.allocator);
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret);
}
// do not call memcpy if the pointer is "static"
if (to.buffer != from.buffer) {
std::memcpy(to.buffer, from.buffer, from.buffer_length);
}
to.buffer_length = from.buffer_length;
}
/// Object oriented version of rcl_serialized_message_t with destructor to avoid memory leaks
SerializedMessage::SerializedMessage(const rcl_allocator_t & allocator)
: SerializedMessage(0u, allocator)
{}
SerializedMessage::SerializedMessage(
size_t initial_capacity, const rcl_allocator_t & allocator)
: serialized_message_(rmw_get_zero_initialized_serialized_message())
{
const auto ret = rmw_serialized_message_init(
&serialized_message_, initial_capacity, &allocator);
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret);
}
}
SerializedMessage::SerializedMessage(const SerializedMessage & other)
: SerializedMessage(other.serialized_message_)
{}
SerializedMessage::SerializedMessage(const rcl_serialized_message_t & other)
: serialized_message_(rmw_get_zero_initialized_serialized_message())
{
copy_rcl_message(other, serialized_message_);
}
SerializedMessage::SerializedMessage(SerializedMessage && other)
: serialized_message_(
std::exchange(other.serialized_message_, rmw_get_zero_initialized_serialized_message()))
{}
SerializedMessage::SerializedMessage(rcl_serialized_message_t && other)
: serialized_message_(
std::exchange(other, rmw_get_zero_initialized_serialized_message()))
{}
SerializedMessage & SerializedMessage::operator=(const SerializedMessage & other)
{
if (this != &other) {
serialized_message_ = rmw_get_zero_initialized_serialized_message();
copy_rcl_message(other.serialized_message_, serialized_message_);
}
return *this;
}
SerializedMessage & SerializedMessage::operator=(const rcl_serialized_message_t & other)
{
if (&serialized_message_ != &other) {
serialized_message_ = rmw_get_zero_initialized_serialized_message();
copy_rcl_message(other, serialized_message_);
}
return *this;
}
SerializedMessage & SerializedMessage::operator=(SerializedMessage && other)
{
if (this != &other) {
serialized_message_ =
std::exchange(other.serialized_message_, rmw_get_zero_initialized_serialized_message());
}
return *this;
}
SerializedMessage & SerializedMessage::operator=(rcl_serialized_message_t && other)
{
if (&serialized_message_ != &other) {
serialized_message_ =
std::exchange(other, rmw_get_zero_initialized_serialized_message());
}
return *this;
}
SerializedMessage::~SerializedMessage()
{
if (nullptr != serialized_message_.buffer) {
const auto fini_ret = rmw_serialized_message_fini(&serialized_message_);
if (RCL_RET_OK != fini_ret) {
RCLCPP_ERROR(
get_logger("rclcpp"),
"Failed to destroy serialized message: %s", rcl_get_error_string().str);
}
}
}
rcl_serialized_message_t & SerializedMessage::get_rcl_serialized_message()
{
return serialized_message_;
}
const rcl_serialized_message_t & SerializedMessage::get_rcl_serialized_message() const
{
return serialized_message_;
}
size_t SerializedMessage::size() const
{
return serialized_message_.buffer_length;
}
size_t SerializedMessage::capacity() const
{
return serialized_message_.buffer_capacity;
}
void SerializedMessage::reserve(size_t capacity)
{
auto ret = rmw_serialized_message_resize(&serialized_message_, capacity);
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret);
}
}
rcl_serialized_message_t SerializedMessage::release_rcl_serialized_message()
{
auto ret = serialized_message_;
serialized_message_ = rmw_get_zero_initialized_serialized_message();
return ret;
}
} // namespace rclcpp