-
Notifications
You must be signed in to change notification settings - Fork 118
/
Copy pathrmw_init.cpp
167 lines (147 loc) · 5.22 KB
/
rmw_init.cpp
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
165
166
167
// Copyright 2020 Open Source Robotics Foundation, Inc.
// Copyright 2016-2018 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 <cassert>
#include <cstring>
#include <memory>
#include "rcutils/strdup.h"
#include "rcutils/types.h"
#include "rmw/error_handling.h"
#include "rmw/init.h"
#include "rmw/impl/cpp/macros.hpp"
#include "rmw/init_options.h"
#include "rmw/publisher_options.h"
#include "rmw/rmw.h"
#include "rcpputils/scope_exit.hpp"
#include "rmw_dds_common/context.hpp"
#include "rmw_dds_common/msg/participant_entities_info.hpp"
#include "rmw_fastrtps_shared_cpp/custom_participant_info.hpp"
#include "rmw_fastrtps_shared_cpp/participant.hpp"
#include "rmw_fastrtps_shared_cpp/publisher.hpp"
#include "rmw_fastrtps_shared_cpp/rmw_context_impl.hpp"
#include "rmw_fastrtps_shared_cpp/rmw_init.hpp"
#include "rmw_fastrtps_shared_cpp/subscription.hpp"
#include "rosidl_typesupport_cpp/message_type_support.hpp"
#include "rmw_fastrtps_cpp/identifier.hpp"
#include "rmw_fastrtps_cpp/publisher.hpp"
#include "rmw_fastrtps_cpp/subscription.hpp"
extern "C"
{
rmw_ret_t
rmw_init_options_init(rmw_init_options_t * init_options, rcutils_allocator_t allocator)
{
return rmw_fastrtps_shared_cpp::rmw_init_options_init(
eprosima_fastrtps_identifier, init_options, allocator);
}
rmw_ret_t
rmw_init_options_copy(const rmw_init_options_t * src, rmw_init_options_t * dst)
{
return rmw_fastrtps_shared_cpp::rmw_init_options_copy(
eprosima_fastrtps_identifier, src, dst);
}
rmw_ret_t
rmw_init_options_fini(rmw_init_options_t * init_options)
{
return rmw_fastrtps_shared_cpp::rmw_init_options_fini(
eprosima_fastrtps_identifier, init_options);
}
using rmw_dds_common::msg::ParticipantEntitiesInfo;
rmw_ret_t
rmw_init(const rmw_init_options_t * options, rmw_context_t * context)
{
RMW_CHECK_ARGUMENT_FOR_NULL(options, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_FOR_NULL_WITH_MSG(
options->implementation_identifier,
"expected initialized init options",
return RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
options,
options->implementation_identifier,
eprosima_fastrtps_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
RMW_CHECK_FOR_NULL_WITH_MSG(
options->enclave,
"expected non-null enclave",
return RMW_RET_INVALID_ARGUMENT);
if (NULL != context->implementation_identifier) {
RMW_SET_ERROR_MSG("expected a zero-initialized context");
return RMW_RET_INVALID_ARGUMENT;
}
auto restore_context = rcpputils::make_scope_exit(
[context]() {*context = rmw_get_zero_initialized_context();});
context->instance_id = options->instance_id;
context->implementation_identifier = eprosima_fastrtps_identifier;
context->actual_domain_id =
RMW_DEFAULT_DOMAIN_ID == options->domain_id ? 0uL : options->domain_id;
context->impl = new (std::nothrow) rmw_context_impl_t();
if (nullptr == context->impl) {
RMW_SET_ERROR_MSG("failed to allocate context impl");
return RMW_RET_BAD_ALLOC;
}
auto cleanup_impl = rcpputils::make_scope_exit(
[context]() {delete context->impl;});
context->impl->is_shutdown = false;
context->options = rmw_get_zero_initialized_init_options();
rmw_ret_t ret = rmw_init_options_copy(options, &context->options);
if (RMW_RET_OK != ret) {
return ret;
}
cleanup_impl.cancel();
restore_context.cancel();
return RMW_RET_OK;
}
rmw_ret_t
rmw_shutdown(rmw_context_t * context)
{
RMW_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_FOR_NULL_WITH_MSG(
context->impl,
"expected initialized context",
return RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
context,
context->implementation_identifier,
eprosima_fastrtps_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
context->impl->is_shutdown = true;
return RMW_RET_OK;
}
rmw_ret_t
rmw_context_fini(rmw_context_t * context)
{
RMW_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_FOR_NULL_WITH_MSG(
context->impl,
"expected initialized context",
return RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
context,
context->implementation_identifier,
eprosima_fastrtps_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
if (!context->impl->is_shutdown) {
RCUTILS_SET_ERROR_MSG("context has not been shutdown");
return RMW_RET_INVALID_ARGUMENT;
}
if (context->impl->count > 0) {
RMW_SET_ERROR_MSG("Finalizing a context with active nodes");
return RMW_RET_ERROR;
}
rmw_ret_t ret = rmw_init_options_fini(&context->options);
delete context->impl;
*context = rmw_get_zero_initialized_context();
return ret;
}
} // extern "C"