Skip to content

Commit 2bf79f7

Browse files
budrusKarsten1987
andauthored
new semaphore strategy in rmw_wait (#11)
* new semaphore strategy in rmw_wait Signed-off-by: Poehnl Michael (CC-AD/ESW1) <michael.poehnl@de.bosch.com> * apply latest uncrustify Signed-off-by: Karsten Knese <karsten.knese@us.bosch.com> Co-authored-by: Karsten Knese <Karsten1987@users.noreply.github.com>
1 parent 5420960 commit 2bf79f7

16 files changed

+114
-76
lines changed

iceoryx_ros2_bridge/src/generic_subscription.cpp

Lines changed: 11 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -106,16 +106,17 @@ GenericSubscription::borrow_serialized_message(size_t capacity)
106106
rclcpp::exceptions::throw_from_rcl_error(init_return);
107107
}
108108

109-
auto serialized_msg = std::shared_ptr<rmw_serialized_message_t>(message,
110-
[](rmw_serialized_message_t * msg) {
111-
auto fini_return = rmw_serialized_message_fini(msg);
112-
delete msg;
113-
if (fini_return != RCL_RET_OK) {
114-
RCLCPP_ERROR_STREAM(
115-
rclcpp::get_logger("iceoryx_ros2_bridge"),
116-
"Failed to destroy serialized message: " << rcl_get_error_string().str);
117-
}
118-
});
109+
auto serialized_msg = std::shared_ptr<rmw_serialized_message_t>(
110+
message,
111+
[](rmw_serialized_message_t * msg) {
112+
auto fini_return = rmw_serialized_message_fini(msg);
113+
delete msg;
114+
if (fini_return != RCL_RET_OK) {
115+
RCLCPP_ERROR_STREAM(
116+
rclcpp::get_logger("iceoryx_ros2_bridge"),
117+
"Failed to destroy serialized message: " << rcl_get_error_string().str);
118+
}
119+
});
119120

120121
return serialized_msg;
121122
}

iceoryx_ros2_bridge/src/iceoryx_ros2_bridge.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -231,7 +231,8 @@ int main(int argc, char ** argv)
231231
std::function<void(std::shared_ptr<rmw_serialized_message_t>)> cb =
232232
std::bind(&publish_to_iceoryx, std::placeholders::_1, ts, iceoryx_pubs.back());
233233

234-
ros2_subs.emplace_back(std::make_shared<iceoryx_ros2_bridge::GenericSubscription>(
234+
ros2_subs.emplace_back(
235+
std::make_shared<iceoryx_ros2_bridge::GenericSubscription>(
235236
node->get_node_base_interface().get(), *ts, topic, cb));
236237
node->get_node_topics_interface()->add_subscription(ros2_subs.back(), nullptr);
237238
}
@@ -261,7 +262,8 @@ int main(int argc, char ** argv)
261262

262263
auto ts = iceoryx_ros2_bridge::get_typesupport(type, "rosidl_typesupport_cpp");
263264

264-
ros2_pubs.emplace_back(std::make_shared<iceoryx_ros2_bridge::GenericPublisher>(
265+
ros2_pubs.emplace_back(
266+
std::make_shared<iceoryx_ros2_bridge::GenericPublisher>(
265267
node->get_node_base_interface().get(), topic, *ts));
266268

267269
auto service_desc =

rmw_iceoryx_cpp/src/internal/iceoryx_deserialize.cpp

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -203,8 +203,9 @@ const char * copy_payload_cpp(
203203
serialized_msg += size;
204204
} else {
205205
if (member->array_size_ > 0 && !member->is_upper_bound_) {
206-
serialized_msg = copy_payload_fixed_array_cpp<T>(serialized_msg, ros_message_field,
207-
member->array_size_);
206+
serialized_msg = copy_payload_fixed_array_cpp<T>(
207+
serialized_msg, ros_message_field,
208+
member->array_size_);
208209
} else {
209210
serialized_msg = copy_payload_array_cpp<T>(serialized_msg, ros_message_field);
210211
}
@@ -271,8 +272,9 @@ const char * copy_payload_c(
271272
serialized_msg += size;
272273
} else {
273274
if (member->array_size_ > 0 && !member->is_upper_bound_) {
274-
serialized_msg = copy_payload_fixed_array_cpp<T>(serialized_msg, ros_message_field,
275-
member->array_size_);
275+
serialized_msg = copy_payload_fixed_array_cpp<T>(
276+
serialized_msg, ros_message_field,
277+
member->array_size_);
276278
} else {
277279
serialized_msg = copy_payload_array_c<T>(serialized_msg, ros_message_field);
278280
}

rmw_iceoryx_cpp/src/internal/iceoryx_name_conversion.cpp

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -103,8 +103,9 @@ get_name_n_type_from_iceoryx_service_description(
103103
// ARA Naming
104104
std::string delimiter_msg = "_ara_msgs/msg/";
105105

106-
return std::make_tuple("/" + instance + "/" + service + "/" + event,
107-
service + delimiter_msg + event);
106+
return std::make_tuple(
107+
"/" + instance + "/" + service + "/" + event,
108+
service + delimiter_msg + event);
108109
}
109110
}
110111

@@ -119,9 +120,10 @@ get_iceoryx_service_description(
119120
type_name = package_name + "/" + type_name;
120121

121122
auto serviceDescriptionTuple = get_service_description_elements(topic_name, type_name);
122-
return iox::capro::ServiceDescription(std::get<0>(serviceDescriptionTuple),
123-
std::get<1>(serviceDescriptionTuple),
124-
std::get<2>(serviceDescriptionTuple));
123+
return iox::capro::ServiceDescription(
124+
std::get<0>(serviceDescriptionTuple),
125+
std::get<1>(serviceDescriptionTuple),
126+
std::get<2>(serviceDescriptionTuple));
125127
}
126128

127129
} // namespace rmw_iceoryx_cpp

rmw_iceoryx_cpp/src/internal/iceoryx_serialize.cpp

Lines changed: 8 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -242,9 +242,10 @@ void copy_data_c_ros_message(
242242
} else {
243243
void * subros_message = nullptr;
244244
size_t sub_members_size = sub_members->size_of_;
245-
size_t array_elememts = get_array_elememts_and_assign_ros_message_field_c(member,
246-
ros_message_field,
247-
subros_message);
245+
size_t array_elememts = get_array_elememts_and_assign_ros_message_field_c(
246+
member,
247+
ros_message_field,
248+
subros_message);
248249

249250
store_array_size(payloadVector, array_elememts);
250251

@@ -268,9 +269,10 @@ void copy_data_cpp_ros_message(
268269
size_t array_elements;
269270
size_t sub_members_size = sub_members->size_of_;
270271

271-
array_elements = get_array_elememts_and_assign_ros_message_field_cpp(member, ros_message_field,
272-
subros_message,
273-
sub_members_size);
272+
array_elements = get_array_elememts_and_assign_ros_message_field_cpp(
273+
member, ros_message_field,
274+
subros_message,
275+
sub_members_size);
274276
store_array_size(payloadVector, array_elements);
275277
for (size_t index = 0; index < array_elements; ++index) {
276278
serialize(subros_message, sub_members, payloadVector);

rmw_iceoryx_cpp/src/internal/iceoryx_topic_names_and_types.cpp

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -81,7 +81,8 @@ void fill_topic_containers(
8181
std::string(receiver.m_caproEventMethodID.to_cstring()));
8282

8383
names_n_types[std::get<0>(name_and_type)] = std::get<1>(name_and_type);
84-
subscribers_topics[std::string(receiver.m_runnable.to_cstring())].push_back(std::get<0>(
84+
subscribers_topics[std::string(receiver.m_runnable.to_cstring())].push_back(
85+
std::get<0>(
8586
name_and_type));
8687
}
8788
for (auto & sender : port_sample->m_senderList) {
@@ -91,7 +92,8 @@ void fill_topic_containers(
9192
std::string(sender.m_caproEventMethodID.to_cstring()));
9293

9394
names_n_types[std::get<0>(name_and_type)] = std::get<1>(name_and_type);
94-
publishers_topics[std::string(sender.m_runnable.to_cstring())].push_back(std::get<0>(
95+
publishers_topics[std::string(sender.m_runnable.to_cstring())].push_back(
96+
std::get<0>(
9597
name_and_type));
9698
}
9799
port_receiver.releaseChunk(latest_chunk_header);
@@ -186,8 +188,9 @@ rmw_ret_t fill_rmw_names_and_types(
186188
rmw_ret_t rmw_ret = RMW_RET_ERROR;
187189

188190
if (!iceoryx_topic_names_and_types.empty()) {
189-
rmw_ret = rmw_names_and_types_init(rmw_topic_names_and_types,
190-
iceoryx_topic_names_and_types.size(), allocator);
191+
rmw_ret = rmw_names_and_types_init(
192+
rmw_topic_names_and_types,
193+
iceoryx_topic_names_and_types.size(), allocator);
191194
if (rmw_ret != RMW_RET_OK) {
192195
return rmw_ret;
193196
}

rmw_iceoryx_cpp/src/rmw_guard_condition.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,8 @@ rmw_create_guard_condition(rmw_context_t * context)
2929
{
3030
RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, nullptr);
3131

32-
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(rmw_create_guard_condition
32+
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
33+
rmw_create_guard_condition
3334
: context,
3435
context->implementation_identifier,
3536
rmw_get_implementation_identifier(),
@@ -80,7 +81,8 @@ rmw_destroy_guard_condition(rmw_guard_condition_t * guard_condition)
8081
{
8182
RCUTILS_CHECK_ARGUMENT_FOR_NULL(guard_condition, RMW_RET_ERROR);
8283

83-
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(rmw_destroy_guard_condition
84+
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
85+
rmw_destroy_guard_condition
8486
: guard_condition,
8587
guard_condition->implementation_identifier,
8688
rmw_get_implementation_identifier(),

rmw_iceoryx_cpp/src/rmw_init.cpp

Lines changed: 10 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,8 @@ rmw_init_options_copy(const rmw_init_options_t * src, rmw_init_options_t * dst)
4848
{
4949
RMW_CHECK_ARGUMENT_FOR_NULL(src, RMW_RET_INVALID_ARGUMENT);
5050
RMW_CHECK_ARGUMENT_FOR_NULL(dst, RMW_RET_INVALID_ARGUMENT);
51-
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(rmw_init_options_copy
51+
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
52+
rmw_init_options_copy
5253
: source options,
5354
src->implementation_identifier,
5455
rmw_get_implementation_identifier(),
@@ -67,7 +68,8 @@ rmw_init_options_fini(rmw_init_options_t * init_options)
6768
{
6869
RCUTILS_CHECK_ARGUMENT_FOR_NULL(init_options, RMW_RET_INVALID_ARGUMENT);
6970
RCUTILS_CHECK_ALLOCATOR(&(init_options->allocator), return RMW_RET_INVALID_ARGUMENT);
70-
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(rmw_init_options_fini
71+
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
72+
rmw_init_options_fini
7173
: options,
7274
init_options->implementation_identifier,
7375
rmw_get_implementation_identifier(),
@@ -81,7 +83,8 @@ rmw_init(const rmw_init_options_t * options, rmw_context_t * context)
8183
{
8284
RCUTILS_CHECK_ARGUMENT_FOR_NULL(options, RMW_RET_INVALID_ARGUMENT);
8385
RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
84-
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(rmw_init
86+
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
87+
rmw_init
8588
: options,
8689
options->implementation_identifier,
8790
rmw_get_implementation_identifier(),
@@ -110,7 +113,8 @@ rmw_ret_t
110113
rmw_shutdown(rmw_context_t * context)
111114
{
112115
RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
113-
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(rmw_shutdown
116+
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
117+
rmw_shutdown
114118
: context,
115119
context->implementation_identifier,
116120
rmw_get_implementation_identifier(),
@@ -123,7 +127,8 @@ rmw_ret_t
123127
rmw_context_fini(rmw_context_t * context)
124128
{
125129
RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
126-
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(rmw_context_fini
130+
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
131+
rmw_context_fini
127132
: context,
128133
context->implementation_identifier,
129134
rmw_get_implementation_identifier(),

rmw_iceoryx_cpp/src/rmw_node.cpp

Lines changed: 10 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,8 @@ rmw_create_node(
7272
RMW_SET_ERROR_MSG("failed to allocate memory for graph change notifier");
7373
goto fail;
7474
}
75-
RMW_TRY_PLACEMENT_NEW(graph_change_notifier, graph_change_notifier, goto fail,
75+
RMW_TRY_PLACEMENT_NEW(
76+
graph_change_notifier, graph_change_notifier, goto fail,
7677
IceoryxGraphChangeNotifier, guard_condition)
7778

7879
// allocate iceoryx_runnable
@@ -92,7 +93,8 @@ rmw_create_node(
9293
RMW_SET_ERROR_MSG("failed to allocate memory for node info");
9394
goto fail;
9495
}
95-
RMW_TRY_PLACEMENT_NEW(node_info, node_info, goto fail, IceoryxNodeInfo, guard_condition,
96+
RMW_TRY_PLACEMENT_NEW(
97+
node_info, node_info, goto fail, IceoryxNodeInfo, guard_condition,
9698
graph_change_notifier, iceoryx_runnable)
9799

98100
node_handle->data = node_info;
@@ -160,7 +162,8 @@ rmw_destroy_node(rmw_node_t * node)
160162
IceoryxNodeInfo * node_info = static_cast<IceoryxNodeInfo *>(node->data);
161163
if (node_info) {
162164
if (node_info->graph_change_notifier_) {
163-
RMW_TRY_DESTRUCTOR(node_info->graph_change_notifier_->~IceoryxGraphChangeNotifier(),
165+
RMW_TRY_DESTRUCTOR(
166+
node_info->graph_change_notifier_->~IceoryxGraphChangeNotifier(),
164167
node_info->graph_change_notifier_,
165168
result = RMW_RET_ERROR)
166169
rmw_free(node_info->graph_change_notifier_);
@@ -170,12 +173,14 @@ rmw_destroy_node(rmw_node_t * node)
170173
result = RMW_RET_ERROR;
171174
}
172175
if (node_info->iceoryx_runnable_) {
173-
RMW_TRY_DESTRUCTOR(node_info->iceoryx_runnable_->~Runnable(),
176+
RMW_TRY_DESTRUCTOR(
177+
node_info->iceoryx_runnable_->~Runnable(),
174178
node_info->iceoryx_runnable_,
175179
result = RMW_RET_ERROR)
176180
rmw_free(node_info->iceoryx_runnable_);
177181
}
178-
RMW_TRY_DESTRUCTOR(node_info->~IceoryxNodeInfo(),
182+
RMW_TRY_DESTRUCTOR(
183+
node_info->~IceoryxNodeInfo(),
179184
node_info_,
180185
result = RMW_RET_ERROR)
181186
rmw_free(node_info);

rmw_iceoryx_cpp/src/rmw_publisher.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -183,12 +183,14 @@ rmw_destroy_publisher(rmw_node_t * node, rmw_publisher_t * publisher)
183183
IceoryxPublisher * iceoryx_publisher = static_cast<IceoryxPublisher *>(publisher->data);
184184
if (iceoryx_publisher) {
185185
if (iceoryx_publisher->iceoryx_sender_) {
186-
RMW_TRY_DESTRUCTOR(iceoryx_publisher->iceoryx_sender_->~Publisher(),
186+
RMW_TRY_DESTRUCTOR(
187+
iceoryx_publisher->iceoryx_sender_->~Publisher(),
187188
iceoryx_publisher->iceoryx_sender_,
188189
result = RMW_RET_ERROR)
189190
rmw_free(iceoryx_publisher->iceoryx_sender_);
190191
}
191-
RMW_TRY_DESTRUCTOR(iceoryx_publisher->~IceoryxPublisher(),
192+
RMW_TRY_DESTRUCTOR(
193+
iceoryx_publisher->~IceoryxPublisher(),
192194
iceoryx_publisher,
193195
result = RMW_RET_ERROR)
194196
rmw_free(iceoryx_publisher);

0 commit comments

Comments
 (0)