diff --git a/NOTICE b/NOTICE index 09be901b..4a88c0da 100644 --- a/NOTICE +++ b/NOTICE @@ -3,3 +3,4 @@ Copyright 2016-2018 Esteve Fernandez (esteve@apache.org) This product includes software developed by Esteve Fernandez (esteve@apache.org) +Stefan Hoffmann (stefan.hoffmann@schiller.de) diff --git a/rcldotnet/CMakeLists.txt b/rcldotnet/CMakeLists.txt index 766db758..2bd0f0c1 100644 --- a/rcldotnet/CMakeLists.txt +++ b/rcldotnet/CMakeLists.txt @@ -15,6 +15,8 @@ find_package(rmw REQUIRED) find_package(rmw_implementation REQUIRED) find_package(rmw_implementation_cmake REQUIRED) find_package(rosidl_generator_c REQUIRED) +find_package(sensor_msgs REQUIRED) +find_package(std_msgs REQUIRED) find_package(dotnet_cmake_module REQUIRED) find_package(DotNETExtra REQUIRED) @@ -76,6 +78,8 @@ set(_assemblies_dep_dlls ${builtin_interfaces_ASSEMBLIES_DLL} ${rcldotnet_common_ASSEMBLIES_DLL} ${unique_identifier_msgs_ASSEMBLIES_DLL} + ${sensor_msgs_ASSEMBLIES_DLL} + ${std_msgs_ASSEMBLIES_DLL} ) add_dotnet_library(${PROJECT_NAME}_assemblies @@ -141,7 +145,7 @@ if(BUILD_TESTING) if(DEFINED ENV{RCLDOTNET_TEST_TARGET_FRAMEWORK}) set(RCLDOTNET_TEST_TARGET_FRAMEWORK $ENV{RCLDOTNET_TEST_TARGET_FRAMEWORK}) else() - set(RCLDOTNET_TEST_TARGET_FRAMEWORK "net6.0") + set(RCLDOTNET_TEST_TARGET_FRAMEWORK "net7.0") endif() add_dotnet_test(test_messages diff --git a/rcldotnet/RCLdotnet.cs b/rcldotnet/RCLdotnet.cs index e52c03f5..a19a304f 100644 --- a/rcldotnet/RCLdotnet.cs +++ b/rcldotnet/RCLdotnet.cs @@ -18,6 +18,9 @@ using action_msgs.msg; using action_msgs.srv; using ROS2.Utils; +using sensor_msgs.msg; +using System.Collections.Generic; +using System.Diagnostics; namespace ROS2 { @@ -898,7 +901,21 @@ private static bool Take(Subscription subscription, IRosMessage message) switch (ret) { case RCLRet.Ok: - ReadFromMessageHandle(message, messageHandle); + if (message is sensor_msgs.msg.Image) + { + HackedReadFromImageMessageHandle(subscription, message, messageHandle); + + } + else if (message is sensor_msgs.msg.PointCloud2) + { + // Console.WriteLine("PointCloud2"); + HackedReadFromPointCloudMessageHandle(subscription, message, messageHandle); + } + else + { + ReadFromMessageHandle(message, messageHandle); + } + return true; case RCLRet.SubscriptionTakeFailed: @@ -1485,6 +1502,217 @@ public static string GetRMWIdentifier() return rmw_identifier; } + + // WORKAROUND IMAGES + // public static Dictionary lastImages =new Dictionary(); + + public static Dictionary pointCloudSubscription = new Dictionary(); + + public static Dictionary imageSubscription = new Dictionary(); + + public static Dictionary lastImagesBytes = new Dictionary(); + + public static Dictionary lastPointCloudsBytes = new Dictionary(); + + public static object IMG_DATA_LOCK = new object(); + public static object POINTCLOUD_DATA_LOCK = new object(); + + + public static void GetLastPointCloudCopy(sensor_msgs.msg.PointCloud2 pointCloud2, ref byte[] pointCloudData) + { + lock (POINTCLOUD_DATA_LOCK) + { + if (lastPointCloudsBytes.ContainsKey(pointCloud2)) + { + var cloudData = lastPointCloudsBytes[pointCloud2]; + + // cloudData = lastPointCloudsBytes[pointCloud2]; + if(pointCloudData == null || pointCloudData.Length != cloudData.Length) + { + pointCloudData = new byte[lastPointCloudsBytes[pointCloud2].Length]; + } + + Buffer.BlockCopy(cloudData, 0, pointCloudData, 0, cloudData.Length); + // Marshal.Copy(lastPointCloudsBytes[pointCloud2], 0, pointCloudData, cloudData.Length); + + } + else + { + pointCloudData = null; + } + } + } + + // public static byte[] GetLastPointCloudBytes(sensor_msgs.msg.PointCloud2 pointCloud2) + // { + // lock (POINTCLOUD_DATA_LOCK) + // { + // if (lastPointCloudsBytes.ContainsKey(pointCloud2)) + // { + // return lastPointCloudsBytes[pointCloud2]; + // } + // return null; + // } + // } + + public static void HackedPointCloud__ReadFromHandle(Subscription subscription, global::System.IntPtr messageHandle, sensor_msgs.msg.PointCloud2 pointCloud2) + { + Debug.WriteLine("HackedPointCloud__ReadFromHandle"); + var sw = System.Diagnostics.Stopwatch.StartNew(); + lock(POINTCLOUD_DATA_LOCK) + { + pointCloud2.Header.__ReadFromHandle(sensor_msgs.msg.PointCloud2.native_get_field_header_HANDLE(messageHandle)); + pointCloud2.Height = sensor_msgs.msg.PointCloud2.native_read_field_height(messageHandle); + pointCloud2.Width = sensor_msgs.msg.PointCloud2.native_read_field_width(messageHandle); + pointCloud2.PointStep = sensor_msgs.msg.PointCloud2.native_read_field_point_step(messageHandle); + pointCloud2.RowStep = sensor_msgs.msg.PointCloud2.native_read_field_row_step(messageHandle); + pointCloud2.IsBigendian = sensor_msgs.msg.PointCloud2.native_read_field_is_bigendian(messageHandle); + { + int size = sensor_msgs.msg.PointCloud2.native_getsize_field_data_message(messageHandle); + HackedPointCloudMemoryCopy(subscription, messageHandle, pointCloud2, size); + } + } + } + + public static void HackedImage__ReadFromHandle(Subscription subscription, global::System.IntPtr messageHandle, sensor_msgs.msg.Image image) + { + // Debug.WriteLine("HackedImage__ReadFromHandle"); + // var sw = System.Diagnostics.Stopwatch.StartNew(); + + lock(IMG_DATA_LOCK) + { + image.Header.__ReadFromHandle(sensor_msgs.msg.Image.native_get_field_header_HANDLE(messageHandle)); + image.Height = sensor_msgs.msg.Image.native_read_field_height(messageHandle); + image.Width = sensor_msgs.msg.Image.native_read_field_width(messageHandle); + IntPtr pStr_Encoding = sensor_msgs.msg.Image.native_read_field_encoding(messageHandle); + image.Encoding = Marshal.PtrToStringAnsi(pStr_Encoding); + + image.IsBigendian = sensor_msgs.msg.Image.native_read_field_is_bigendian(messageHandle); + image.Step = sensor_msgs.msg.Image.native_read_field_step(messageHandle); + { + int size__local_variable = sensor_msgs.msg.Image.native_getsize_field_data_message(messageHandle); + + HackedMemoryCopy(subscription, messageHandle, image, size__local_variable); + + // sw.Stop(); + + // var sw2 = System.Diagnostics.Stopwatch.StartNew(); + + // image.Data = new System.Collections.Generic.List(size__local_variable); + // for (int i__local_variable = 0; i__local_variable < size__local_variable; i__local_variable++) + // { + // image.Data.Add(sensor_msgs.msg.Image.native_read_field_data(sensor_msgs.msg.Image.native_get_field_data_message(messageHandle, i__local_variable))); + // } + + // sw2.Stop(); + // Console.WriteLine($"copying image took: {sw.ElapsedTicks} ticks, {sw2.ElapsedTicks} ticks: {(float)(sw.ElapsedTicks - sw2.ElapsedTicks)/(float)sw.ElapsedTicks}"); + + } + } + + // sw.Stop(); + // Debug.WriteLine($"HackedImage__ReadFromHandle END: {sw.ElapsedMilliseconds} ms"); + } + + private static void HackedPointCloudMemoryCopy(Subscription subscription, IntPtr messageHandle, sensor_msgs.msg.PointCloud2 pointCloud2, int size__local_variable) + { + IntPtr first = sensor_msgs.msg.PointCloud2.native_get_field_data_message(messageHandle, 0); + byte[] bytes = null; + if (pointCloudSubscription.ContainsKey(subscription)) + { + var lastPointCloud = pointCloudSubscription[subscription]; + bytes = lastPointCloudsBytes[lastPointCloud]; + lastPointCloudsBytes.Remove(lastPointCloud); + } + + if (bytes == null || bytes.Length != size__local_variable) + { + bytes = new byte[size__local_variable]; + lastPointCloudsBytes[pointCloud2] = bytes; + } + + Marshal.Copy(first, bytes, 0, (int)(size__local_variable)); + lastPointCloudsBytes[pointCloud2] = bytes; + pointCloudSubscription[subscription] = pointCloud2; + } + + private static void HackedMemoryCopy(Subscription subscription, IntPtr messageHandle, sensor_msgs.msg.Image image, int size__local_variable) + { + IntPtr first = sensor_msgs.msg.Image.native_get_field_data_message(messageHandle, 0); + + // lastImagesHandles[image] = new Tuple(first, (uint)size__local_variable); + + byte[] bytes = null; + if (imageSubscription.ContainsKey(subscription)) + { + var lastImage = imageSubscription[subscription]; + bytes = lastImagesBytes[lastImage]; + lastImagesBytes.Remove(lastImage); + } + + if (bytes == null || bytes.Length != size__local_variable) + { + // Debug.WriteLine("HackedImage__ReadFromHandle: new byte buffer created"); + + bytes = new byte[size__local_variable]; + // Console.WriteLine($"makmustReleaseing new size for image subscription: {size__local_variable} subscription: {subscription.GetHashCode()}"); + } + + + Marshal.Copy(first,bytes, 0, (int)(size__local_variable)); + + lastImagesBytes[image] = bytes; + imageSubscription[subscription] = image; + } + + internal static void HackedReadFromPointCloudMessageHandle(Subscription subscription, IRosMessage message, SafeHandle messageHandle) + { + bool mustRelease = false; + try + { + messageHandle.DangerousAddRef(ref mustRelease); + HackedPointCloud__ReadFromHandle(subscription, messageHandle.DangerousGetHandle(),message as sensor_msgs.msg.PointCloud2); + } + finally + { + if (mustRelease) + { + messageHandle.DangerousRelease(); + } + } + } + + + + internal static void HackedReadFromImageMessageHandle(Subscription subscription, IRosMessage message, SafeHandle messageHandle) + { + bool mustRelease = false; + try + { + // Using SafeHandles for __ReadFromHandle() is very tedious as + // this needs to be handled in generated code across multiple + // assemblies. Array and collection indexing would need to + // create SafeHandles everywhere. It's not worth it, especially + // considering the extra allocations for SafeHandles in arrays + // or collections that don't really represent their own native + // resource. + messageHandle.DangerousAddRef(ref mustRelease); + HackedImage__ReadFromHandle(subscription, messageHandle.DangerousGetHandle(),message as sensor_msgs.msg.Image); + //message.__ReadFromHandle(messageHandle.DangerousGetHandle()); + } + catch(Exception e) + { + // Debug.WriteLine("HackedImage__ReadFromHandle: exception"); + } + finally + { + if (mustRelease) + { + messageHandle.DangerousRelease(); + } + } + } + internal static void ReadFromMessageHandle(IRosMessage message, SafeHandle messageHandle) { bool mustRelease = false; diff --git a/rcldotnet/SafeSubscriptionHandle.cs b/rcldotnet/SafeSubscriptionHandle.cs index a7075035..9dd3f397 100644 --- a/rcldotnet/SafeSubscriptionHandle.cs +++ b/rcldotnet/SafeSubscriptionHandle.cs @@ -28,7 +28,7 @@ namespace ROS2 /// of the subscription handle and node handle. This also applies to publisher, service and client handles, /// which point to a rcl_publisher_t, rcl_service_t or rcl_client_t. /// - internal sealed class SafeSubscriptionHandle : SafeHandleZeroOrMinusOneIsInvalid + public sealed class SafeSubscriptionHandle : SafeHandleZeroOrMinusOneIsInvalid { // Trick with parent handles taken from https://github.com/dotnet/corefx/pull/6366 // Commit from early 2016, but still in current .NET as of september 2021: diff --git a/rcldotnet/Subscription.cs b/rcldotnet/Subscription.cs index cc639f37..754d2698 100644 --- a/rcldotnet/Subscription.cs +++ b/rcldotnet/Subscription.cs @@ -34,7 +34,7 @@ internal Subscription() // internal handle is disposed. // By relying on the GC/Finalizer of SafeHandle the handle only gets // Disposed if the subscription is not live anymore. - internal abstract SafeSubscriptionHandle Handle { get; } + public abstract SafeSubscriptionHandle Handle { get; } internal abstract IRosMessage CreateMessage(); @@ -54,7 +54,7 @@ internal Subscription(SafeSubscriptionHandle handle, Action callback) _callback = callback; } - internal override SafeSubscriptionHandle Handle { get; } + public override SafeSubscriptionHandle Handle { get; } internal override IRosMessage CreateMessage() => (IRosMessage)new T(); diff --git a/rcldotnet/package.xml b/rcldotnet/package.xml index df264e07..085a97ca 100644 --- a/rcldotnet/package.xml +++ b/rcldotnet/package.xml @@ -16,6 +16,7 @@ rmw_implementation_cmake rosidl_generator_c rosidl_parser + std_msgs rmw_implementation_cmake rcl @@ -25,6 +26,8 @@ action_msgs builtin_interfaces unique_identifier_msgs + sensor_msgs + std_msgs rcl rcl_interfaces @@ -32,6 +35,7 @@ action_msgs builtin_interfaces unique_identifier_msgs + unique_identifier_msgs std_msgs test_msgs diff --git a/rcldotnet/rcldotnet.c b/rcldotnet/rcldotnet.c index 40be6421..c59a9e1b 100644 --- a/rcldotnet/rcldotnet.c +++ b/rcldotnet/rcldotnet.c @@ -26,6 +26,7 @@ #include "rcldotnet.h" static rcl_context_t context; +static rcl_clock_t clock; int32_t native_rcl_init(int argc, const char *argv[]) { context = rcl_get_zero_initialized_context(); @@ -40,6 +41,7 @@ int32_t native_rcl_init(int argc, const char *argv[]) { return ret; } + ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &allocator); return ret; } diff --git a/rcldotnet/rcldotnet_node.c b/rcldotnet/rcldotnet_node.c index 989dc8b4..7222d9bd 100644 --- a/rcldotnet/rcldotnet_node.c +++ b/rcldotnet/rcldotnet_node.c @@ -223,7 +223,6 @@ int32_t native_rcl_action_create_server_handle(void **action_server_handle, rcl_action_server_options_t action_server_ops = rcl_action_server_get_default_options(); - rcl_ret_t ret = rcl_action_server_init(action_server, node, clock, ts, action_name, &action_server_ops); @@ -258,4 +257,4 @@ const char * native_rcl_node_get_fully_qualified_name_handle(void *node_handle) rcl_node_t *node = (rcl_node_t *)node_handle; return rcl_node_get_fully_qualified_name(node); -} \ No newline at end of file +} diff --git a/rcldotnet_common/DllLoadUtils.cs b/rcldotnet_common/DllLoadUtils.cs index 556d80a9..f112b5e4 100644 --- a/rcldotnet_common/DllLoadUtils.cs +++ b/rcldotnet_common/DllLoadUtils.cs @@ -42,6 +42,7 @@ public enum Platform MacOSX, WindowsDesktop, UWP, + Android, Unknown } @@ -65,6 +66,12 @@ public class DllLoadUtilsFactory [DllImport("libdl.so.2", EntryPoint = "dlclose")] private static extern int dlclose_unix(IntPtr handle); + [DllImport("libdl.so", EntryPoint = "dlopen")] + private static extern IntPtr dlopen_android(string fileName, int flags); + + [DllImport("libdl.so", EntryPoint = "dlclose")] + private static extern int dlclose_android(IntPtr handle); + [DllImport("libdl.dylib", EntryPoint = "dlopen")] private static extern IntPtr dlopen_macosx(string fileName, int flags); @@ -85,6 +92,8 @@ public static DllLoadUtils GetDllLoadUtils() return new DllLoadUtilsWindowsDesktop(); case Platform.UWP: return new DllLoadUtilsUWP(); + case Platform.Android: + return new DllLoadUtilsAndroid(); case Platform.Unknown: default: throw new UnknownPlatformError(); @@ -133,6 +142,20 @@ private static bool IsUnix() } } + private static bool IsAndroid() + { + try + { + IntPtr ptr = dlopen_android("libdl.so", RTLD_NOW); + dlclose_android(ptr); + return true; + } + catch (TypeLoadException) + { + return false; + } + } + private static bool IsMacOSX() { try @@ -165,6 +188,10 @@ private static Platform CheckPlatform() { return Platform.UWP; } + else if (IsAndroid()) + { + return Platform.Android; + } else { return Platform.Unknown; @@ -253,6 +280,50 @@ public override IntPtr LoadLibrary(string fileName) } } + internal class DllLoadUtilsAndroid : DllLoadUtilsAbs + { + + [DllImport("libdl.so", ExactSpelling = true)] + private static extern IntPtr dlopen(string fileName, int flags); + + [DllImport("libdl.so", ExactSpelling = true)] + private static extern IntPtr dlsym(IntPtr handle, string symbol); + + [DllImport("libdl.so", ExactSpelling = true)] + private static extern int dlclose(IntPtr handle); + + [DllImport("libdl.so", ExactSpelling = true)] + private static extern IntPtr dlerror(); + + private const int RTLD_NOW = 2; + + public override void FreeLibrary(IntPtr handle) => dlclose(handle); + + public override IntPtr GetProcAddress(IntPtr dllHandle, string name) + { + // clear previous errors if any + dlerror(); + var res = dlsym(dllHandle, name); + var errPtr = dlerror(); + if (errPtr != IntPtr.Zero) + { + throw new Exception("dlsym: " + Marshal.PtrToStringAnsi(errPtr)); + } + return res; + } + + public override IntPtr LoadLibrary(string fileName) + { + string libraryName = "lib" + fileName + "_native.so"; + IntPtr ptr = dlopen(libraryName, RTLD_NOW); + if (ptr == IntPtr.Zero) + { + throw new UnsatisfiedLinkError(libraryName); + } + return ptr; + } + } + internal class DllLoadUtilsUnix : DllLoadUtilsAbs { diff --git a/rcldotnet_examples/RCLDotnetTalker.cs b/rcldotnet_examples/RCLDotnetTalker.cs index a82e0950..0e35d5a0 100644 --- a/rcldotnet_examples/RCLDotnetTalker.cs +++ b/rcldotnet_examples/RCLDotnetTalker.cs @@ -1,4 +1,6 @@ using System; +using System.Threading; + using ROS2; namespace ConsoleApplication diff --git a/rosidl_generator_dotnet/cmake/rosidl_generator_dotnet_generate_interfaces.cmake b/rosidl_generator_dotnet/cmake/rosidl_generator_dotnet_generate_interfaces.cmake index 52e9aadc..316e7608 100644 --- a/rosidl_generator_dotnet/cmake/rosidl_generator_dotnet_generate_interfaces.cmake +++ b/rosidl_generator_dotnet/cmake/rosidl_generator_dotnet_generate_interfaces.cmake @@ -25,10 +25,10 @@ find_package(DotNETExtra REQUIRED) # Get a list of typesupport implementations from valid rmw implementations. rosidl_generator_dotnet_get_typesupports(_typesupport_impls) -if(_typesupport_impls STREQUAL "") - message(WARNING "No valid typesupport for .NET generator. .NET messages will not be generated.") - return() -endif() +# if(_typesupport_impls STREQUAL "") +# message(WARNING "No valid typesupport for .NET generator. .NET messages will not be generated.") +# return() +# endif() set(_output_path "${CMAKE_CURRENT_BINARY_DIR}/rosidl_generator_dotnet/${PROJECT_NAME}") diff --git a/rosidl_generator_dotnet/package.xml b/rosidl_generator_dotnet/package.xml index 40d363b8..493d4482 100644 --- a/rosidl_generator_dotnet/package.xml +++ b/rosidl_generator_dotnet/package.xml @@ -21,7 +21,7 @@ rosidl_runtime_c - rmw_implementation + rmw_implementation_cmake rosidl_runtime_c rosidl_generator_c diff --git a/rosidl_generator_dotnet/resource/msg.cs.em b/rosidl_generator_dotnet/resource/msg.cs.em index 5d4ca694..3568152d 100644 --- a/rosidl_generator_dotnet/resource/msg.cs.em +++ b/rosidl_generator_dotnet/resource/msg.cs.em @@ -28,7 +28,7 @@ namespace @('.'.join(message.structure.namespaced_type.namespaces)) { public class @(type_name) : global::ROS2.IRosMessage@(additional_interfaces_str) { - private static readonly DllLoadUtils dllLoadUtils; + public static readonly DllLoadUtils dllLoadUtils; @[for member in message.structure.members]@ @[ if isinstance(member.type, Array)]@ @@ -181,54 +181,54 @@ public class @(type_name) : global::ROS2.IRosMessage@(additional_interfaces_str) } [UnmanagedFunctionPointer(CallingConvention.Cdecl)] - private delegate IntPtr NativeGetTypeSupportType(); + public delegate IntPtr NativeGetTypeSupportType(); - private static NativeGetTypeSupportType native_get_typesupport = null; + public static NativeGetTypeSupportType native_get_typesupport = null; [UnmanagedFunctionPointer(CallingConvention.Cdecl)] - private delegate Safe@(type_name)Handle NativeCreateNativeType(); + public delegate Safe@(type_name)Handle NativeCreateNativeType(); - private static NativeCreateNativeType native_create_native_message = null; + public static NativeCreateNativeType native_create_native_message = null; [UnmanagedFunctionPointer(CallingConvention.Cdecl)] - private delegate void NativeDestroyNativeType(IntPtr messageHandle); + public delegate void NativeDestroyNativeType(IntPtr messageHandle); - private static NativeDestroyNativeType native_destroy_native_message = null; + public static NativeDestroyNativeType native_destroy_native_message = null; @[for member in message.structure.members]@ @[ if isinstance(member.type, Array) or isinstance(member.type, AbstractSequence)]@ - private static NativeGetField@(get_field_name(type_name, member.name))Type native_get_field_@(member.name)_message = null; + public static NativeGetField@(get_field_name(type_name, member.name))Type native_get_field_@(member.name)_message = null; @[ if isinstance(member.type, AbstractSequence)]@ - private static NativeGetSizeField@(get_field_name(type_name, member.name))Type native_getsize_field_@(member.name)_message = null; - private static NativeInitSequenceField@(get_field_name(type_name, member.name))Type native_init_seqence_field_@(member.name)_message = null; + public static NativeGetSizeField@(get_field_name(type_name, member.name))Type native_getsize_field_@(member.name)_message = null; + public static NativeInitSequenceField@(get_field_name(type_name, member.name))Type native_init_seqence_field_@(member.name)_message = null; @[ end if]@ @[ if isinstance(member.type.value_type, BasicType) or isinstance(member.type.value_type, AbstractString)]@ - private static NativeWriteField@(get_field_name(type_name, member.name))Type native_write_field_@(member.name) = null; - private static NativeReadField@(get_field_name(type_name, member.name))Type native_read_field_@(member.name) = null; + public static NativeWriteField@(get_field_name(type_name, member.name))Type native_write_field_@(member.name) = null; + public static NativeReadField@(get_field_name(type_name, member.name))Type native_read_field_@(member.name) = null; @[ end if]@ [UnmanagedFunctionPointer(CallingConvention.Cdecl)] - private delegate IntPtr NativeGetField@(get_field_name(type_name, member.name))Type( + public delegate IntPtr NativeGetField@(get_field_name(type_name, member.name))Type( IntPtr messageHandle, int index); @[ if isinstance(member.type, AbstractSequence)]@ [UnmanagedFunctionPointer(CallingConvention.Cdecl)] - private delegate int NativeGetSizeField@(get_field_name(type_name, member.name))Type( + public delegate int NativeGetSizeField@(get_field_name(type_name, member.name))Type( IntPtr messageHandle); [UnmanagedFunctionPointer(CallingConvention.Cdecl)] - private delegate bool NativeInitSequenceField@(get_field_name(type_name, member.name))Type( + public delegate bool NativeInitSequenceField@(get_field_name(type_name, member.name))Type( IntPtr messageHandle, int size); @[ end if]@ @[ if isinstance(member.type.value_type, AbstractString)]@ [UnmanagedFunctionPointer(CallingConvention.Cdecl)] - private delegate void NativeWriteField@(get_field_name(type_name, member.name))Type( + public delegate void NativeWriteField@(get_field_name(type_name, member.name))Type( IntPtr messageHandle, [MarshalAs (UnmanagedType.LPStr)] string value); [UnmanagedFunctionPointer(CallingConvention.Cdecl)] - private delegate IntPtr NativeReadField@(get_field_name(type_name, member.name))Type(IntPtr messageHandle); + public delegate IntPtr NativeReadField@(get_field_name(type_name, member.name))Type(IntPtr messageHandle); @[ else]@ [UnmanagedFunctionPointer(CallingConvention.Cdecl)] - private delegate @(get_dotnet_type(member.type.value_type)) NativeReadField@(get_field_name(type_name, member.name))Type( + public delegate @(get_dotnet_type(member.type.value_type)) NativeReadField@(get_field_name(type_name, member.name))Type( IntPtr messageHandle); [UnmanagedFunctionPointer(CallingConvention.Cdecl)] - private delegate void NativeWriteField@(get_field_name(type_name, member.name))Type( + public delegate void NativeWriteField@(get_field_name(type_name, member.name))Type( IntPtr messageHandle, @(get_dotnet_type(member.type.value_type)) value); @[ end if]@ @[ elif isinstance(member.type, AbstractWString)]@ @@ -236,28 +236,28 @@ public class @(type_name) : global::ROS2.IRosMessage@(additional_interfaces_str) @[ elif isinstance(member.type, BasicType) or isinstance(member.type, AbstractString)]@ @[ if isinstance(member.type, AbstractString)]@ [UnmanagedFunctionPointer(CallingConvention.Cdecl)] - private delegate IntPtr NativeReadField@(get_field_name(type_name, member.name))Type(IntPtr messageHandle); + public delegate IntPtr NativeReadField@(get_field_name(type_name, member.name))Type(IntPtr messageHandle); [UnmanagedFunctionPointer(CallingConvention.Cdecl)] - private delegate void NativeWriteField@(get_field_name(type_name, member.name))Type( + public delegate void NativeWriteField@(get_field_name(type_name, member.name))Type( IntPtr messageHandle, [MarshalAs (UnmanagedType.LPStr)] string value); @[ else]@ [UnmanagedFunctionPointer(CallingConvention.Cdecl)] - private delegate @(get_dotnet_type(member.type)) NativeReadField@(get_field_name(type_name, member.name))Type( + public delegate @(get_dotnet_type(member.type)) NativeReadField@(get_field_name(type_name, member.name))Type( IntPtr messageHandle); [UnmanagedFunctionPointer(CallingConvention.Cdecl)] - private delegate void NativeWriteField@(get_field_name(type_name, member.name))Type( + public delegate void NativeWriteField@(get_field_name(type_name, member.name))Type( IntPtr messageHandle, @(get_dotnet_type(member.type)) value); @[ end if]@ - private static NativeReadField@(get_field_name(type_name, member.name))Type native_read_field_@(member.name) = null; + public static NativeReadField@(get_field_name(type_name, member.name))Type native_read_field_@(member.name) = null; - private static NativeWriteField@(get_field_name(type_name, member.name))Type native_write_field_@(member.name) = null; + public static NativeWriteField@(get_field_name(type_name, member.name))Type native_write_field_@(member.name) = null; @[ else]@ [UnmanagedFunctionPointer(CallingConvention.Cdecl)] - private delegate IntPtr NativeGetField@(get_field_name(type_name, member.name))Type(IntPtr messageHandle); + public delegate IntPtr NativeGetField@(get_field_name(type_name, member.name))Type(IntPtr messageHandle); - private static NativeGetField@(get_field_name(type_name, member.name))Type native_get_field_@(member.name)_HANDLE = null; + public static NativeGetField@(get_field_name(type_name, member.name))Type native_get_field_@(member.name)_HANDLE = null; @[ end if]@ @[end for]@ @@ -407,7 +407,7 @@ public class @(type_name) : global::ROS2.IRosMessage@(additional_interfaces_str) } @[end if]@ - private sealed class Safe@(type_name)Handle : global::System.Runtime.InteropServices.SafeHandle + public sealed class Safe@(type_name)Handle : global::System.Runtime.InteropServices.SafeHandle { public Safe@(type_name)Handle() : base(global::System.IntPtr.Zero, true) { }