ROS 2 rclcpp + rcl - rolling  rolling-e615c7c3
ROS 2 C++ Client Library with ROS Client Library
service_event_publisher.c
1 // Copyright 2022 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "rcl/service_event_publisher.h"
16 
17 #include <string.h>
18 
19 #include "rcl/allocator.h"
20 #include "rcl/macros.h"
21 #include "rcl/error_handling.h"
22 #include "rcl/publisher.h"
23 #include "rcl/node.h"
24 #include "rcl/service_introspection.h"
25 #include "rcl/time.h"
26 #include "rcl/types.h"
27 #include "rcutils/logging_macros.h"
28 #include "rcutils/macros.h"
29 #include "rmw/error_handling.h"
30 #include "service_msgs/msg/service_event_info.h"
31 
32 rcl_service_event_publisher_t rcl_get_zero_initialized_service_event_publisher(void)
33 {
34  // All members are initialized to 0 or NULL by C99 6.7.8/10.
35  static rcl_service_event_publisher_t zero_service_event_publisher;
36  return zero_service_event_publisher;
37 }
38 
39 bool
40 rcl_service_event_publisher_is_valid(const rcl_service_event_publisher_t * service_event_publisher)
41 {
42  RCL_CHECK_FOR_NULL_WITH_MSG(
43  service_event_publisher, "service_event_publisher is invalid", return false);
44  RCL_CHECK_FOR_NULL_WITH_MSG(
45  service_event_publisher->service_type_support,
46  "service_event_publisher's service type support is invalid", return false);
47  if (!rcl_clock_valid(service_event_publisher->clock)) {
48  RCL_SET_ERROR_MSG("service_event_publisher's clock is invalid");
49  return false;
50  }
51  return true;
52 }
53 
54 static rcl_ret_t introspection_create_publisher(
55  rcl_service_event_publisher_t * service_event_publisher,
56  const rcl_node_t * node)
57 {
58  rcl_allocator_t allocator = service_event_publisher->publisher_options.allocator;
59  RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "allocator is invalid", return RCL_RET_ERROR);
60 
61  service_event_publisher->publisher = allocator.allocate(
62  sizeof(rcl_publisher_t), allocator.state);
63  RCL_CHECK_FOR_NULL_WITH_MSG(
64  service_event_publisher->publisher,
65  "allocate service_event_publisher failed in enable", return RCL_RET_BAD_ALLOC);
66  *service_event_publisher->publisher = rcl_get_zero_initialized_publisher();
68  service_event_publisher->publisher, node,
69  service_event_publisher->service_type_support->event_typesupport,
70  service_event_publisher->service_event_topic_name,
71  &service_event_publisher->publisher_options);
72  if (RCL_RET_OK != ret) {
73  allocator.deallocate(service_event_publisher->publisher, allocator.state);
74  service_event_publisher->publisher = NULL;
75  rcutils_reset_error();
76  RCL_SET_ERROR_MSG(rcl_get_error_string().str);
77  return ret;
78  }
79 
80  return RCL_RET_OK;
81 }
82 
83 rcl_ret_t rcl_service_event_publisher_init(
84  rcl_service_event_publisher_t * service_event_publisher,
85  const rcl_node_t * node,
86  rcl_clock_t * clock,
87  const rcl_publisher_options_t publisher_options,
88  const char * service_name,
89  const rosidl_service_type_support_t * service_type_support)
90 {
91  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
92  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_ALREADY_INIT);
93  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_NODE_INVALID);
94  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_BAD_ALLOC);
95  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_ERROR);
96  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_TOPIC_NAME_INVALID);
97  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_PUBLISHER_INVALID);
98 
99  RCL_CHECK_ARGUMENT_FOR_NULL(service_event_publisher, RCL_RET_INVALID_ARGUMENT);
100  RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
101  RCL_CHECK_ARGUMENT_FOR_NULL(service_name, RCL_RET_INVALID_ARGUMENT);
102  RCL_CHECK_ARGUMENT_FOR_NULL(service_type_support, RCL_RET_INVALID_ARGUMENT);
103 
105  &publisher_options.allocator,
106  "allocator is invalid", return RCL_RET_ERROR);
107 
108  rcl_allocator_t allocator = publisher_options.allocator;
109 
110  rcl_ret_t ret = RCL_RET_OK;
111 
112  if (!rcl_node_is_valid(node)) {
113  return RCL_RET_NODE_INVALID;
114  }
115 
116  if (!rcl_clock_valid(clock)) {
117  rcutils_reset_error();
118  RCL_SET_ERROR_MSG("clock is invalid");
119  return RCL_RET_ERROR;
120  }
121 
122  RCUTILS_LOG_DEBUG_NAMED(
123  ROS_PACKAGE_NAME, "Initializing service introspection for service name '%s'", service_name);
124 
125  // Typesupports have static lifetimes
126  service_event_publisher->service_type_support = service_type_support;
127  service_event_publisher->clock = clock;
128  service_event_publisher->publisher_options = publisher_options;
129 
130  size_t topic_length = strlen(service_name) + strlen(RCL_SERVICE_INTROSPECTION_TOPIC_POSTFIX) + 1;
131  service_event_publisher->service_event_topic_name = (char *) allocator.allocate(
132  topic_length, allocator.state);
133  RCL_CHECK_FOR_NULL_WITH_MSG(
134  service_event_publisher->service_event_topic_name,
135  "allocating memory for service introspection topic name failed",
136  return RCL_RET_BAD_ALLOC;);
137 
138  snprintf(
139  service_event_publisher->service_event_topic_name,
140  topic_length,
141  "%s%s", service_name, RCL_SERVICE_INTROSPECTION_TOPIC_POSTFIX);
142 
143  ret = introspection_create_publisher(service_event_publisher, node);
144  if (ret != RCL_RET_OK) {
145  goto free_topic_name;
146  }
147 
148  RCUTILS_LOG_DEBUG_NAMED(
149  ROS_PACKAGE_NAME, "Service introspection for service '%s' initialized", service_name);
150 
151  return RCL_RET_OK;
152 
153 free_topic_name:
154  allocator.deallocate(service_event_publisher->service_event_topic_name, allocator.state);
155 
156  return ret;
157 }
158 
159 rcl_ret_t rcl_service_event_publisher_fini(
160  rcl_service_event_publisher_t * service_event_publisher,
161  rcl_node_t * node)
162 {
163  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
164  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_ALREADY_SHUTDOWN);
165  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_NODE_INVALID);
166  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_PUBLISHER_INVALID);
167  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_ERROR);
168  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_BAD_ALLOC);
169 
170  if (!rcl_service_event_publisher_is_valid(service_event_publisher)) {
171  return RCL_RET_ERROR;
172  }
173 
175  return RCL_RET_NODE_INVALID;
176  }
177 
178  rcl_allocator_t allocator = service_event_publisher->publisher_options.allocator;
179  RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "allocator is invalid", return RCL_RET_ERROR);
180 
181  if (service_event_publisher->publisher) {
182  rcl_ret_t ret = rcl_publisher_fini(service_event_publisher->publisher, node);
183  allocator.deallocate(service_event_publisher->publisher, allocator.state);
184  service_event_publisher->publisher = NULL;
185  if (RCL_RET_OK != ret) {
186  return ret;
187  }
188  }
189 
190  allocator.deallocate(service_event_publisher->service_event_topic_name, allocator.state);
191  service_event_publisher->service_event_topic_name = NULL;
192 
193  return RCL_RET_OK;
194 }
195 
196 rcl_ret_t rcl_send_service_event_message(
197  const rcl_service_event_publisher_t * service_event_publisher,
198  const uint8_t event_type,
199  const void * ros_response_request,
200  const int64_t sequence_number,
201  const uint8_t guid[16])
202 {
203  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
204  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_PUBLISHER_INVALID);
205  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_ERROR);
206  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_BAD_ALLOC);
207 
208  RCL_CHECK_ARGUMENT_FOR_NULL(ros_response_request, RCL_RET_INVALID_ARGUMENT);
209  RCL_CHECK_FOR_NULL_WITH_MSG(guid, "guid is NULL", return RCL_RET_INVALID_ARGUMENT);
210 
211  if (!rcl_service_event_publisher_is_valid(service_event_publisher)) {
212  return RCL_RET_ERROR;
213  }
214 
215  if (service_event_publisher->introspection_state == RCL_SERVICE_INTROSPECTION_OFF) {
216  return RCL_RET_ERROR;
217  }
218 
219  rcl_allocator_t allocator = service_event_publisher->publisher_options.allocator;
220  RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
221 
222  if (!rcl_publisher_is_valid(service_event_publisher->publisher)) {
224  }
225 
226  rcl_ret_t ret;
227 
229  ret = rcl_clock_get_now(service_event_publisher->clock, &now);
230  if (RMW_RET_OK != ret) {
231  rcutils_reset_error();
232  RCL_SET_ERROR_MSG(rmw_get_error_string().str);
233  return RCL_RET_ERROR;
234  }
235 
236  rosidl_service_introspection_info_t info = {
237  .event_type = event_type,
238  .stamp_sec = (int32_t)RCL_NS_TO_S(now),
239  .stamp_nanosec = now % (1000LL * 1000LL * 1000LL),
240  .sequence_number = sequence_number,
241  };
242 
243  memcpy(info.client_gid, guid, 16);
244 
245  void * service_introspection_message;
246  if (service_event_publisher->introspection_state == RCL_SERVICE_INTROSPECTION_METADATA) {
247  ros_response_request = NULL;
248  }
249  switch (event_type) {
250  case service_msgs__msg__ServiceEventInfo__REQUEST_RECEIVED:
251  case service_msgs__msg__ServiceEventInfo__REQUEST_SENT:
252  service_introspection_message =
253  service_event_publisher->service_type_support->event_message_create_handle_function(
254  &info, &allocator, ros_response_request, NULL);
255  break;
256  case service_msgs__msg__ServiceEventInfo__RESPONSE_RECEIVED:
257  case service_msgs__msg__ServiceEventInfo__RESPONSE_SENT:
258  service_introspection_message =
259  service_event_publisher->service_type_support->event_message_create_handle_function(
260  &info, &allocator, NULL, ros_response_request);
261  break;
262  default:
263  rcutils_reset_error();
264  RCL_SET_ERROR_MSG("unsupported event type");
265  return RCL_RET_ERROR;
266  }
267  RCL_CHECK_FOR_NULL_WITH_MSG(
268  service_introspection_message, "service_introspection_message is NULL", return RCL_RET_ERROR);
269 
270  // and publish it out!
271  ret = rcl_publish(service_event_publisher->publisher, service_introspection_message, NULL);
272  // clean up before error checking
273  service_event_publisher->service_type_support->event_message_destroy_handle_function(
274  service_introspection_message, &allocator);
275  if (RCL_RET_OK != ret) {
276  rcutils_reset_error();
277  RCL_SET_ERROR_MSG(rmw_get_error_string().str);
278  }
279 
280  return ret;
281 }
282 
283 rcl_ret_t
284 rcl_service_event_publisher_change_state(
285  rcl_service_event_publisher_t * service_event_publisher,
286  rcl_service_introspection_state_t introspection_state)
287 {
288  if (!rcl_service_event_publisher_is_valid(service_event_publisher)) {
289  return RCL_RET_ERROR;
290  }
291 
292  service_event_publisher->introspection_state = introspection_state;
293 
294  return RCL_RET_OK;
295 }
#define RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, msg, fail_statement)
Check that the given allocator is initialized, or fail with a message.
Definition: allocator.h:56
rcutils_allocator_t rcl_allocator_t
Encapsulation of an allocator.
Definition: allocator.h:31
RCL_PUBLIC bool rcl_node_is_valid(const rcl_node_t *node)
Return true if the node is valid, else false.
Definition: node.c:394
RCL_PUBLIC bool rcl_node_is_valid_except_context(const rcl_node_t *node)
Return true if node is valid, except for the context being valid.
Definition: node.c:384
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_publisher_init(rcl_publisher_t *publisher, const rcl_node_t *node, const rosidl_message_type_support_t *type_support, const char *topic_name, const rcl_publisher_options_t *options)
Initialize a rcl publisher.
Definition: publisher.c:48
RCL_PUBLIC bool rcl_publisher_is_valid(const rcl_publisher_t *publisher)
Return true if the publisher is valid, otherwise false.
Definition: publisher.c:418
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_publish(const rcl_publisher_t *publisher, const void *ros_message, rmw_publisher_allocation_t *allocation)
Publish a ROS message on a topic using a publisher.
Definition: publisher.c:271
RCL_PUBLIC RCL_WARN_UNUSED rcl_publisher_t rcl_get_zero_initialized_publisher(void)
Return a rcl_publisher_t struct with members set to NULL.
Definition: publisher.c:40
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_publisher_fini(rcl_publisher_t *publisher, rcl_node_t *node)
Finalize a rcl_publisher_t.
Definition: publisher.c:179
Encapsulation of a time source.
Definition: time.h:138
Structure which encapsulates a ROS Node.
Definition: node.h:45
Options available for a rcl publisher.
Definition: publisher.h:44
rcl_allocator_t allocator
Custom allocator for the publisher, used for incidental allocations.
Definition: publisher.h:49
Structure which encapsulates a ROS Publisher.
Definition: publisher.h:37
char * service_event_topic_name
Name of service introspection topic: <service_name>/<RCL_SERVICE_INTROSPECTION_TOPIC_POSTFIX>
const rosidl_service_type_support_t * service_type_support
Handle to service typesupport.
rcl_publisher_options_t publisher_options
Publisher options for service event publisher.
rcl_service_introspection_state_t introspection_state
Current state of introspection; off, metadata, or contents.
rcl_publisher_t * publisher
Handle to publisher for publishing service events.
rcl_clock_t * clock
Handle to clock for timestamping service events.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_clock_get_now(rcl_clock_t *clock, rcl_time_point_value_t *time_point_value)
Fill the time point value with the current value of the associated clock.
Definition: time.c:263
#define RCL_NS_TO_S
Convenience macro to convert nanoseconds to seconds.
Definition: time.h:39
rcutils_time_point_value_t rcl_time_point_value_t
A single point in time, measured in nanoseconds since the Unix epoch.
Definition: time.h:46
RCL_PUBLIC RCL_WARN_UNUSED bool rcl_clock_valid(rcl_clock_t *clock)
Check if the clock has valid values.
Definition: time.c:86
#define RCL_RET_ALREADY_INIT
rcl_init() already called return code.
Definition: types.h:41
#define RCL_RET_OK
Success return code.
Definition: types.h:27
#define RCL_RET_BAD_ALLOC
Failed to allocate memory return code.
Definition: types.h:33
#define RCL_RET_INVALID_ARGUMENT
Invalid argument return code.
Definition: types.h:35
#define RCL_RET_ERROR
Unspecified error return code.
Definition: types.h:29
#define RCL_RET_NODE_INVALID
Invalid rcl_node_t given return code.
Definition: types.h:59
#define RCL_RET_TOPIC_NAME_INVALID
Topic name does not pass validation.
Definition: types.h:47
#define RCL_RET_ALREADY_SHUTDOWN
rcl_shutdown() already called return code.
Definition: types.h:53
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:24
#define RCL_RET_PUBLISHER_INVALID
Invalid rcl_publisher_t given return code.
Definition: types.h:69