Skip to content

Commit

Permalink
fix bool pInvokes in rcldotnet
Browse files Browse the repository at this point in the history
  • Loading branch information
hoffmann-stefan committed May 26, 2023
1 parent d05e99d commit c7add72
Show file tree
Hide file tree
Showing 6 changed files with 40 additions and 30 deletions.
6 changes: 3 additions & 3 deletions rcldotnet/Client.cs
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ internal delegate RCLRet NativeRCLSendRequestType(

[UnmanagedFunctionPointer(CallingConvention.Cdecl)]
internal delegate RCLRet NativeRCLServiceServerIsAvailableType(
SafeNodeHandle nodeHandle, SafeClientHandle clientHandle, out bool isAvailable);
SafeNodeHandle nodeHandle, SafeClientHandle clientHandle, out int isAvailable);

internal static NativeRCLServiceServerIsAvailableType native_rcl_service_server_is_available = null;

Expand Down Expand Up @@ -95,10 +95,10 @@ internal Client(SafeClientHandle handle, Node node)

public bool ServiceIsReady()
{
RCLRet ret = ClientDelegates.native_rcl_service_server_is_available(_node.Handle, Handle, out var serviceIsReady);
RCLRet ret = ClientDelegates.native_rcl_service_server_is_available(_node.Handle, Handle, out int serviceIsReady);
RCLExceptionHelper.CheckReturnValue(ret, $"{nameof(ClientDelegates.native_rcl_service_server_is_available)}() failed.");

return serviceIsReady;
return serviceIsReady != 0;
}

public Task<TResponse> SendRequestAsync(TRequest request)
Expand Down
20 changes: 10 additions & 10 deletions rcldotnet/RCLdotnet.cs
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ internal delegate void NativeRCLGetErrorStringType(
internal static NativeRCLResetErrorType native_rcl_reset_error = null;

[UnmanagedFunctionPointer(CallingConvention.Cdecl)]
internal delegate bool NativeRCLOkType();
internal delegate int NativeRCLOkType();

internal static NativeRCLOkType native_rcl_ok = null;

Expand Down Expand Up @@ -117,22 +117,22 @@ internal delegate RCLRet NativeRCLCreateWaitSetHandleType(
internal static NativeRCLWaitType native_rcl_wait = null;

[UnmanagedFunctionPointer(CallingConvention.Cdecl)]
internal delegate bool NativeRCLWaitSetSubscriptionReady(SafeWaitSetHandle waitSetHandle, int index);
internal delegate int NativeRCLWaitSetSubscriptionReady(SafeWaitSetHandle waitSetHandle, int index);

internal static NativeRCLWaitSetSubscriptionReady native_rcl_wait_set_subscription_ready = null;

[UnmanagedFunctionPointer(CallingConvention.Cdecl)]
internal delegate bool NativeRCLWaitSetClientReady(SafeWaitSetHandle waitSetHandle, int index);
internal delegate int NativeRCLWaitSetClientReady(SafeWaitSetHandle waitSetHandle, int index);

internal static NativeRCLWaitSetClientReady native_rcl_wait_set_client_ready = null;

[UnmanagedFunctionPointer(CallingConvention.Cdecl)]
internal delegate bool NativeRCLWaitSetServiceReady(SafeWaitSetHandle waitSetHandle, int index);
internal delegate int NativeRCLWaitSetServiceReady(SafeWaitSetHandle waitSetHandle, int index);

internal static NativeRCLWaitSetServiceReady native_rcl_wait_set_service_ready = null;

[UnmanagedFunctionPointer(CallingConvention.Cdecl)]
internal delegate bool NativeRCLWaitSetGuardConditionReady(SafeWaitSetHandle waitSetHandle, int index);
internal delegate int NativeRCLWaitSetGuardConditionReady(SafeWaitSetHandle waitSetHandle, int index);

internal static NativeRCLWaitSetGuardConditionReady native_rcl_wait_set_guard_condition_ready = null;

Expand Down Expand Up @@ -354,7 +354,7 @@ public static class RCLdotnet

public static bool Ok()
{
return RCLdotnetDelegates.native_rcl_ok();
return RCLdotnetDelegates.native_rcl_ok() != 0;
}

public static Node CreateNode(string nodeName)
Expand Down Expand Up @@ -676,7 +676,7 @@ public static void SpinOnce(Node node, long timeout)
int subscriptionIndex = 0;
foreach (Subscription subscription in node.Subscriptions)
{
if (RCLdotnetDelegates.native_rcl_wait_set_subscription_ready(waitSetHandle, subscriptionIndex))
if (RCLdotnetDelegates.native_rcl_wait_set_subscription_ready(waitSetHandle, subscriptionIndex) != 0)
{
IRosMessage message = subscription.CreateMessage();
bool result = Take(subscription, message);
Expand All @@ -695,7 +695,7 @@ public static void SpinOnce(Node node, long timeout)
int serviceIndex = 0;
foreach (var service in node.Services)
{
if (RCLdotnetDelegates.native_rcl_wait_set_service_ready(waitSetHandle, serviceIndex))
if (RCLdotnetDelegates.native_rcl_wait_set_service_ready(waitSetHandle, serviceIndex) != 0)
{
var request = service.CreateRequest();
var response = service.CreateResponse();
Expand All @@ -715,7 +715,7 @@ public static void SpinOnce(Node node, long timeout)
int clientIndex = 0;
foreach (var client in node.Clients)
{
if (RCLdotnetDelegates.native_rcl_wait_set_client_ready(waitSetHandle, clientIndex))
if (RCLdotnetDelegates.native_rcl_wait_set_client_ready(waitSetHandle, clientIndex) != 0)
{
var response = client.CreateResponse();

Expand All @@ -734,7 +734,7 @@ public static void SpinOnce(Node node, long timeout)
int guardConditionIndex = 0;
foreach (GuardCondition guardCondition in node.GuardConditions)
{
if (RCLdotnetDelegates.native_rcl_wait_set_guard_condition_ready(waitSetHandle, guardConditionIndex))
if (RCLdotnetDelegates.native_rcl_wait_set_guard_condition_ready(waitSetHandle, guardConditionIndex) != 0)
{
guardCondition.TriggerCallback();
}
Expand Down
25 changes: 16 additions & 9 deletions rcldotnet/rcldotnet.c
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,10 @@ void native_rcl_reset_error(void) {
rcl_reset_error();
}

bool native_rcl_ok() { return rcl_context_is_valid(&context); }
int32_t native_rcl_ok() {
bool result = rcl_context_is_valid(&context);
return result ? 1 : 0;
}

int32_t native_rcl_create_node_handle(void **node_handle, const char *name, const char *namespace) {
rcl_node_t *node = (rcl_node_t *)malloc(sizeof(rcl_node_t));
Expand Down Expand Up @@ -178,48 +181,52 @@ int32_t native_rcl_wait(void *wait_set_handle, int64_t timeout) {
return ret;
}

bool native_rcl_wait_set_subscription_ready(void *wait_set_handle, int32_t index) {
int32_t native_rcl_wait_set_subscription_ready(void *wait_set_handle, int32_t index) {
rcl_wait_set_t *wait_set = (rcl_wait_set_t *)wait_set_handle;

if (index >= wait_set->size_of_subscriptions)
{
return false;
}

return wait_set->subscriptions[index] != NULL;
bool result = wait_set->subscriptions[index] != NULL;
return result ? 1 : 0;
}

bool native_rcl_wait_set_client_ready(void *wait_set_handle, int32_t index) {
int32_t native_rcl_wait_set_client_ready(void *wait_set_handle, int32_t index) {
rcl_wait_set_t *wait_set = (rcl_wait_set_t *)wait_set_handle;

if (index >= wait_set->size_of_clients)
{
return false;
}

return wait_set->clients[index] != NULL;
bool result = wait_set->clients[index] != NULL;
return result ? 1 : 0;
}

bool native_rcl_wait_set_service_ready(void *wait_set_handle, int32_t index) {
int32_t native_rcl_wait_set_service_ready(void *wait_set_handle, int32_t index) {
rcl_wait_set_t *wait_set = (rcl_wait_set_t *)wait_set_handle;

if (index >= wait_set->size_of_services)
{
return false;
}

return wait_set->services[index] != NULL;
bool result = wait_set->services[index] != NULL;
return result ? 1 : 0;
}

bool native_rcl_wait_set_guard_condition_ready(void *wait_set_handle, int32_t index) {
int32_t native_rcl_wait_set_guard_condition_ready(void *wait_set_handle, int32_t index) {
rcl_wait_set_t *wait_set = (rcl_wait_set_t *)wait_set_handle;

if (index >= wait_set->size_of_guard_conditions)
{
return false;
}

return wait_set->guard_conditions[index] != NULL;
bool result = wait_set->guard_conditions[index] != NULL;
return result ? 1 : 0;
}

int32_t native_rcl_take(void *subscription_handle, void *message_handle) {
Expand Down
10 changes: 5 additions & 5 deletions rcldotnet/rcldotnet.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ RCLDOTNET_EXPORT
void RCLDOTNET_CDECL native_rcl_reset_error(void);

RCLDOTNET_EXPORT
bool RCLDOTNET_CDECL native_rcl_ok();
int32_t RCLDOTNET_CDECL native_rcl_ok();

RCLDOTNET_EXPORT
int32_t RCLDOTNET_CDECL native_rcl_create_node_handle(void **, const char *, const char *);
Expand Down Expand Up @@ -76,16 +76,16 @@ RCLDOTNET_EXPORT
int32_t RCLDOTNET_CDECL native_rcl_wait(void *, int64_t);

RCLDOTNET_EXPORT
bool RCLDOTNET_CDECL native_rcl_wait_set_subscription_ready(void *wait_set_handle, int32_t index);
int32_t RCLDOTNET_CDECL native_rcl_wait_set_subscription_ready(void *wait_set_handle, int32_t index);

RCLDOTNET_EXPORT
bool RCLDOTNET_CDECL native_rcl_wait_set_client_ready(void *wait_set_handle, int32_t index);
int32_t RCLDOTNET_CDECL native_rcl_wait_set_client_ready(void *wait_set_handle, int32_t index);

RCLDOTNET_EXPORT
bool RCLDOTNET_CDECL native_rcl_wait_set_service_ready(void *wait_set_handle, int32_t index);
int32_t RCLDOTNET_CDECL native_rcl_wait_set_service_ready(void *wait_set_handle, int32_t index);

RCLDOTNET_EXPORT
bool RCLDOTNET_CDECL native_rcl_wait_set_guard_condition_ready(void *wait_set_handle, int32_t index);
int32_t RCLDOTNET_CDECL native_rcl_wait_set_guard_condition_ready(void *wait_set_handle, int32_t index);

RCLDOTNET_EXPORT
int32_t RCLDOTNET_CDECL native_rcl_take(void *, void *);
Expand Down
7 changes: 5 additions & 2 deletions rcldotnet/rcldotnet_client.c
Original file line number Diff line number Diff line change
Expand Up @@ -34,10 +34,13 @@ int32_t native_rcl_send_request(void *client_handle, void *request_handle, int64
return ret;
}

int32_t native_rcl_service_server_is_available(void *node_handle, void *client_handle, bool *is_available) {
int32_t native_rcl_service_server_is_available(void *node_handle, void *client_handle, int32_t *is_available) {
rcl_node_t * node = (rcl_node_t *)node_handle;
rcl_client_t * client = (rcl_client_t *)client_handle;

rcl_ret_t ret = rcl_service_server_is_available(node, client, is_available);
bool is_available_as_bool;
rcl_ret_t ret = rcl_service_server_is_available(node, client, &is_available_as_bool);
*is_available = is_available_as_bool ? 1 : 0;

return ret;
}
2 changes: 1 addition & 1 deletion rcldotnet/rcldotnet_client.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,6 @@ RCLDOTNET_EXPORT
int32_t RCLDOTNET_CDECL native_rcl_send_request(void *client_handle, void *request_handle, int64_t *sequence_number);

RCLDOTNET_EXPORT
int32_t RCLDOTNET_CDECL native_rcl_service_server_is_available(void *node_handle, void *client_handle, bool *is_available);
int32_t RCLDOTNET_CDECL native_rcl_service_server_is_available(void *node_handle, void *client_handle, int32_t *is_available);

#endif // RCLDOTNET_CLIENT_H

0 comments on commit c7add72

Please sign in to comment.