diff --git a/rosidl_typesupport_c/resource/srv__type_support.cpp.em b/rosidl_typesupport_c/resource/srv__type_support.cpp.em index b1cd2616..7a7c9935 100644 --- a/rosidl_typesupport_c/resource/srv__type_support.cpp.em +++ b/rosidl_typesupport_c/resource/srv__type_support.cpp.em @@ -118,13 +118,11 @@ static const type_support_map_t _@(service.namespaced_type.name)_service_typesup &_@(service.namespaced_type.name)_service_typesupport_data.data[0], }; - @#TODO(ihasdapie): Import Postfixes @{event_type = '__'.join([package_name, *interface_path.parents[0].parts, service.namespaced_type.name]) + SERVICE_EVENT_MESSAGE_SUFFIX}@ @{request_type = '__'.join([package_name, *interface_path.parents[0].parts, service.namespaced_type.name]) + SERVICE_REQUEST_MESSAGE_SUFFIX}@ @{response_type = '__'.join([package_name, *interface_path.parents[0].parts, service.namespaced_type.name]) + SERVICE_RESPONSE_MESSAGE_SUFFIX}@ - void * rosidl_typesupport_c_@('__'.join([package_name, *interface_path.parents[0].parts, service.namespaced_type.name]))__event_message__create( const rosidl_service_introspection_info_t * info, @@ -148,14 +146,14 @@ rosidl_typesupport_c_@('__'.join([package_name, *interface_path.parents[0].parts } if (!enable_message_payload) { - return event_msg; + return event_msg; } if (request_message) { event_msg->response.capacity = 1; event_msg->response.size = 1; event_msg->response.data = static_cast<@response_type *>(allocator->allocate(sizeof(@response_type), allocator->state)); - if (! @(response_type)__copy((@response_type *) response_message, &event_msg->response.data[0])) { + if (!@(response_type)__copy(reinterpret_cast(response_message), &event_msg->response.data[0])) { allocator->deallocate(event_msg, allocator->state); return NULL; } @@ -164,7 +162,7 @@ rosidl_typesupport_c_@('__'.join([package_name, *interface_path.parents[0].parts event_msg->request.capacity = 1; event_msg->request.size = 1; event_msg->request.data = static_cast<@request_type *>(allocator->allocate(sizeof(@request_type), allocator->state)); - if (! @(request_type)__copy((@request_type *) request_message, &event_msg->request.data[0])){ + if (!@(request_type)__copy(reinterpret_cast(request_message), &event_msg->request.data[0])) { allocator->deallocate(event_msg, allocator->state); return NULL; } @@ -176,17 +174,17 @@ bool rosidl_typesupport_c_@('__'.join([package_name, *interface_path.parents[0].parts, service.namespaced_type.name]))__event_message__destroy( void * event_msg, rcutils_allocator_t * allocator) -{ +{ if (NULL == event_msg) { return false; } auto * _event_msg = static_cast<@event_type *>(event_msg); - @(event_type)__fini((@event_type *) _event_msg); - if (_event_msg->request.data){ + @(event_type)__fini(reinterpret_cast<@event_type *>(_event_msg)); + if (_event_msg->request.data) { allocator->deallocate(_event_msg->request.data, allocator->state); } - if (_event_msg->response.data){ + if (_event_msg->response.data) { allocator->deallocate(_event_msg->response.data, allocator->state); } allocator->deallocate(_event_msg, allocator->state); diff --git a/rosidl_typesupport_c/test/benchmark/benchmark_type_support_dispatch.cpp b/rosidl_typesupport_c/test/benchmark/benchmark_type_support_dispatch.cpp index bc77f83f..a582d1b6 100644 --- a/rosidl_typesupport_c/test/benchmark/benchmark_type_support_dispatch.cpp +++ b/rosidl_typesupport_c/test/benchmark/benchmark_type_support_dispatch.cpp @@ -42,7 +42,7 @@ rosidl_message_type_support_t get_rosidl_message_type_support(const char * ident rosidl_service_type_support_t get_rosidl_service_type_support(const char * identifier) { - return {identifier, nullptr, nullptr}; + return {identifier, nullptr, nullptr, nullptr, nullptr, nullptr}; } type_support_map_t get_typesupport_map(void ** library_array) diff --git a/rosidl_typesupport_cpp/resource/srv__type_support.cpp.em b/rosidl_typesupport_cpp/resource/srv__type_support.cpp.em index 196f52fc..afd63556 100644 --- a/rosidl_typesupport_cpp/resource/srv__type_support.cpp.em +++ b/rosidl_typesupport_cpp/resource/srv__type_support.cpp.em @@ -1,5 +1,4 @@ @# Included from rosidl_typesupport_cpp/resource/idl__type_support.cpp.em -#include "rosidl_runtime_c/service_type_support_struct.h" @{ TEMPLATE( 'msg__type_support.cpp.em', @@ -120,8 +119,9 @@ static const type_support_map_t _@(service.namespaced_type.name)_service_typesup &_@(service.namespaced_type.name)_service_typesupport_data.data[0], }; -@{event_type = '::'.join([package_name, *interface_path.parents[0].parts, service.namespaced_type.name]) + SERVICE_EVENT_MESSAGE_SUFFIX} - +@{ +event_type = '::'.join([package_name, *interface_path.parents[0].parts, service.namespaced_type.name]) + SERVICE_EVENT_MESSAGE_SUFFIX +}@ void * rosidl_@('_'.join([package_name, *interface_path.parents[0].parts, service.namespaced_type.name]))_event_message_create( const rosidl_service_introspection_info_t * info, @@ -156,10 +156,10 @@ rosidl_@('_'.join([package_name, *interface_path.parents[0].parts, service.names return event_msg; } if (nullptr != request_message) { - event_msg->request.push_back(*static_cast (request_message)); + event_msg->request.push_back(*static_cast(request_message)); } if (nullptr != response_message) { - event_msg->response.push_back(*static_cast (response_message)); + event_msg->response.push_back(*static_cast(response_message)); } return event_msg; @@ -167,7 +167,7 @@ rosidl_@('_'.join([package_name, *interface_path.parents[0].parts, service.names bool rosidl_@('_'.join([package_name, *interface_path.parents[0].parts, service.namespaced_type.name]))_event_message_destroy( - void* event_msg, + void * event_msg, rcutils_allocator_t * allocator) { auto * event_msg_ = static_cast<@event_type *>(event_msg); @@ -176,12 +176,11 @@ rosidl_@('_'.join([package_name, *interface_path.parents[0].parts, service.names return true; } - static const rosidl_service_type_support_t @(service.namespaced_type.name)_service_type_support_handle = { .typesupport_identifier = ::rosidl_typesupport_cpp::typesupport_identifier, .data = reinterpret_cast(&_@(service.namespaced_type.name)_service_typesupport_map), .func = ::rosidl_typesupport_cpp::get_service_typesupport_handle_function, - .event_message_create_handle = rosidl_@('_'.join([package_name, *interface_path.parents[0].parts, service.namespaced_type.name]))_event_message_create, + .event_message_create_handle = rosidl_@('_'.join([package_name, *interface_path.parents[0].parts, service.namespaced_type.name]))_event_message_create, .event_message_destroy_handle = rosidl_@('_'.join([package_name, *interface_path.parents[0].parts, service.namespaced_type.name]))_event_message_destroy, .event_typesupport = ::rosidl_typesupport_cpp::get_message_type_support_handle<@('::'.join([package_name, *interface_path.parents[0].parts, service.namespaced_type.name]))_Event>(), };