Skip to content

Commit

Permalink
fix bool pInvokes in actions
Browse files Browse the repository at this point in the history
  • Loading branch information
hoffmann-stefan committed May 19, 2023
1 parent a8ed964 commit 44a6ec0
Show file tree
Hide file tree
Showing 7 changed files with 85 additions and 59 deletions.
6 changes: 3 additions & 3 deletions rcldotnet/ActionClient.cs
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ internal delegate RCLRet NativeRCLActionSendCancelRequestType(

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

internal static NativeRCLActionServerIsAvailableType native_rcl_action_server_is_available = null;

Expand Down Expand Up @@ -156,10 +156,10 @@ internal ActionClient(SafeActionClientHandle handle, Node node)

public override bool ServerIsReady()
{
RCLRet ret = ActionClientDelegates.native_rcl_action_server_is_available(_node.Handle, Handle, out var serverIsReady);
RCLRet ret = ActionClientDelegates.native_rcl_action_server_is_available(_node.Handle, Handle, out int serverIsReady);
RCLExceptionHelper.CheckReturnValue(ret, $"{nameof(ActionClientDelegates.native_rcl_action_server_is_available)}() failed.");

return serverIsReady;
return serverIsReady != 0;
}

public Task<ActionClientGoalHandle<TAction, TGoal, TResult, TFeedback>> SendGoalAsync(TGoal goal)
Expand Down
4 changes: 2 additions & 2 deletions rcldotnet/ActionServerGoalHandle.cs
Original file line number Diff line number Diff line change
Expand Up @@ -87,8 +87,8 @@ public override bool IsActive
{
get
{
bool isActive = RCLdotnetDelegates.native_rcl_action_goal_handle_is_active(Handle);
return isActive;
int isActive = RCLdotnetDelegates.native_rcl_action_goal_handle_is_active(Handle);
return isActive != 0;
}
}

Expand Down
42 changes: 21 additions & 21 deletions rcldotnet/RCLdotnet.cs
Original file line number Diff line number Diff line change
Expand Up @@ -188,7 +188,7 @@ internal delegate RCLRet NativeRCLActionWaitSetAddActionClientType(

[UnmanagedFunctionPointer(CallingConvention.Cdecl)]
internal delegate RCLRet NativeRCLActionClientWaitSetGetEntitiesReadyType(
SafeWaitSetHandle waitSetHandle, SafeActionClientHandle actionClientHandle, out bool isFeedbackReady, out bool isStatusReady, out bool isGoalResponseReady, out bool isCancelResponseReady, out bool isResultResponseReady);
SafeWaitSetHandle waitSetHandle, SafeActionClientHandle actionClientHandle, out int isFeedbackReady, out int isStatusReady, out int isGoalResponseReady, out int isCancelResponseReady, out int isResultResponseReady);

internal static NativeRCLActionClientWaitSetGetEntitiesReadyType native_rcl_action_client_wait_set_get_entities_ready = null;

Expand All @@ -206,7 +206,7 @@ internal delegate RCLRet NativeRCLActionWaitSetAddActionServerType(

[UnmanagedFunctionPointer(CallingConvention.Cdecl)]
internal delegate RCLRet NativeRCLActionServerWaitSetGetEntitiesReadyType(
SafeWaitSetHandle waitSetHandle, SafeActionServerHandle actionServerHandle, out bool isGoalRequestReady, out bool isCancelRequestReady, out bool isResultRequestReady, out bool isGoalExpired);
SafeWaitSetHandle waitSetHandle, SafeActionServerHandle actionServerHandle, out int isGoalRequestReady, out int isCancelRequestReady, out int isResultRequestReady, out int isGoalExpired);

internal static NativeRCLActionServerWaitSetGetEntitiesReadyType native_rcl_action_server_wait_set_get_entities_ready = null;

Expand Down Expand Up @@ -319,7 +319,7 @@ internal delegate RCLRet NativeRCLActionExpireGoalsType(
internal static NativeRCLActionExpireGoalsType native_rcl_action_expire_goals = null;

[UnmanagedFunctionPointer(CallingConvention.Cdecl)]
internal delegate bool NativeRCLActionGoalHandleIsActiveType(SafeActionGoalHandle actionGoalHandleHandle);
internal delegate int NativeRCLActionGoalHandleIsActiveType(SafeActionGoalHandle actionGoalHandleHandle);
internal static NativeRCLActionGoalHandleIsActiveType native_rcl_action_goal_handle_is_active = null;

[UnmanagedFunctionPointer(CallingConvention.Cdecl)]
Expand Down Expand Up @@ -1205,18 +1205,18 @@ public static void SpinOnce(Node node, long timeout)
RCLRet ret = RCLdotnetDelegates.native_rcl_action_client_wait_set_get_entities_ready(
waitSetHandle,
actionClient.Handle,
out bool isFeedbackReady,
out bool isStatusReady,
out bool isGoalResponseReady,
out bool isCancelResponseReady,
out bool isResultResponseReady);
out int isFeedbackReady,
out int isStatusReady,
out int isGoalResponseReady,
out int isCancelResponseReady,
out int isResultResponseReady);

RCLExceptionHelper.CheckReturnValue(ret, $"{nameof(RCLdotnetDelegates.native_rcl_action_client_wait_set_get_entities_ready)}() failed.");

// Check isGoalResponseReady so that a new goalHandle is
// already created if the status or feedback for the new
// goal is received.
if (isGoalResponseReady)
if (isGoalResponseReady != 0)
{
var goalResponse = actionClient.CreateSendGoalResponse();

Expand All @@ -1231,7 +1231,7 @@ public static void SpinOnce(Node node, long timeout)
// Check isStatusReady before isFeedbackReady so that
// the feedback callback already has the newest status
// information if updates are received at the same time.
if (isStatusReady)
if (isStatusReady != 0)
{
var statusMessage = new GoalStatusArray();

Expand All @@ -1242,7 +1242,7 @@ public static void SpinOnce(Node node, long timeout)
}
}

if (isFeedbackReady)
if (isFeedbackReady != 0)
{
var feedbackMessage = actionClient.CreateFeedbackMessage();

Expand All @@ -1253,7 +1253,7 @@ public static void SpinOnce(Node node, long timeout)
}
}

if (isCancelResponseReady)
if (isCancelResponseReady != 0)
{
var cancelResponse = new CancelGoal_Response();

Expand All @@ -1265,7 +1265,7 @@ public static void SpinOnce(Node node, long timeout)
}
}

if (isResultResponseReady)
if (isResultResponseReady != 0)
{
var resultResponse = actionClient.CreateGetResultResponse();

Expand All @@ -1283,14 +1283,14 @@ public static void SpinOnce(Node node, long timeout)
RCLRet ret = RCLdotnetDelegates.native_rcl_action_server_wait_set_get_entities_ready(
waitSetHandle,
actionServer.Handle,
out bool isGoalRequestReady,
out bool isCancelRequestReady,
out bool isResultRequestReady,
out bool isGoalExpired);
out int isGoalRequestReady,
out int isCancelRequestReady,
out int isResultRequestReady,
out int isGoalExpired);

RCLExceptionHelper.CheckReturnValue(ret, $"{nameof(RCLdotnetDelegates.native_rcl_action_server_wait_set_get_entities_ready)}() failed.");

if (isGoalRequestReady)
if (isGoalRequestReady != 0)
{
var goalRequest = actionServer.CreateSendGoalRequest();

Expand All @@ -1301,7 +1301,7 @@ public static void SpinOnce(Node node, long timeout)
}
}

if (isCancelRequestReady)
if (isCancelRequestReady != 0)
{
var cancelRequest = new CancelGoal_Request();

Expand All @@ -1312,7 +1312,7 @@ public static void SpinOnce(Node node, long timeout)
}
}

if (isResultRequestReady)
if (isResultRequestReady != 0)
{
var resultRequest = actionServer.CreateGetResultRequest();

Expand All @@ -1327,7 +1327,7 @@ public static void SpinOnce(Node node, long timeout)
}
}

if (isGoalExpired)
if (isGoalExpired != 0)
{
actionServer.HandleGoalExpired();
}
Expand Down
63 changes: 43 additions & 20 deletions rcldotnet/rcldotnet.c
Original file line number Diff line number Diff line change
Expand Up @@ -318,45 +318,67 @@ bool native_rcl_wait_set_guard_condition_ready(void *wait_set_handle, int32_t in
int32_t native_rcl_action_client_wait_set_get_entities_ready(
void *wait_set_handle,
void *action_client_handle,
bool *is_feedback_ready,
bool *is_status_ready,
bool *is_goal_response_ready,
bool *is_cancel_response_ready,
bool *is_result_response_ready)
int32_t *is_feedback_ready,
int32_t *is_status_ready,
int32_t *is_goal_response_ready,
int32_t *is_cancel_response_ready,
int32_t *is_result_response_ready)
{
rcl_wait_set_t *wait_set = (rcl_wait_set_t *)wait_set_handle;
rcl_action_client_t *action_client = (rcl_action_client_t *)action_client_handle;

bool is_feedback_ready_as_bool;
bool is_status_ready_as_bool;
bool is_goal_response_ready_as_bool;
bool is_cancel_response_ready_as_bool;
bool is_result_response_ready_as_bool;

rcl_ret_t ret = rcl_action_client_wait_set_get_entities_ready(
wait_set,
action_client,
is_feedback_ready,
is_status_ready,
is_goal_response_ready,
is_cancel_response_ready,
is_result_response_ready);
&is_feedback_ready_as_bool,
&is_status_ready_as_bool,
&is_goal_response_ready_as_bool,
&is_cancel_response_ready_as_bool,
&is_result_response_ready_as_bool);

*is_feedback_ready = is_feedback_ready_as_bool ? 1 : 0;
*is_status_ready = is_status_ready_as_bool ? 1 : 0;
*is_goal_response_ready = is_goal_response_ready_as_bool ? 1 : 0;
*is_cancel_response_ready = is_cancel_response_ready_as_bool ? 1 : 0;
*is_result_response_ready = is_result_response_ready_as_bool ? 1 : 0;

return ret;
}

int32_t native_rcl_action_server_wait_set_get_entities_ready(
void *wait_set_handle,
void *action_server_handle,
bool *is_goal_request_ready,
bool *is_cancel_request_ready,
bool *is_result_request_ready,
bool *is_goal_expired)
int32_t *is_goal_request_ready,
int32_t *is_cancel_request_ready,
int32_t *is_result_request_ready,
int32_t *is_goal_expired)
{
rcl_wait_set_t *wait_set = (rcl_wait_set_t *)wait_set_handle;
rcl_action_server_t *action_server = (rcl_action_server_t *)action_server_handle;

bool is_goal_request_ready_as_bool;
bool is_cancel_request_ready_as_bool;
bool is_result_request_ready_as_bool;
bool is_goal_expired_as_bool;

rcl_ret_t ret = rcl_action_server_wait_set_get_entities_ready(
wait_set,
action_server,
is_goal_request_ready,
is_cancel_request_ready,
is_result_request_ready,
is_goal_expired);
&is_goal_request_ready_as_bool,
&is_cancel_request_ready_as_bool,
&is_result_request_ready_as_bool,
&is_goal_expired_as_bool);

*is_goal_request_ready = is_goal_request_ready_as_bool ? 1 : 0;
*is_cancel_request_ready = is_cancel_request_ready_as_bool ? 1 : 0;
*is_result_request_ready = is_result_request_ready_as_bool ? 1 : 0;
*is_goal_expired = is_goal_expired_as_bool ? 1 : 0;

return ret;
}
Expand Down Expand Up @@ -626,10 +648,11 @@ int32_t native_rcl_action_expire_goals(void *action_server_handle, void *goal_in
return ret;
}

bool native_rcl_action_goal_handle_is_active(void *action_goal_handle_handle) {
int32_t native_rcl_action_goal_handle_is_active(void *action_goal_handle_handle) {
rcl_action_goal_handle_t *goal_handle = (rcl_action_goal_handle_t *)action_goal_handle_handle;

return rcl_action_goal_handle_is_active(goal_handle);
bool result = rcl_action_goal_handle_is_active(goal_handle);
return result ? 1 : 0;
}

int32_t native_rcl_action_goal_handle_get_status(void *action_goal_handle_handle, int8_t *status) {
Expand Down
20 changes: 10 additions & 10 deletions rcldotnet/rcldotnet.h
Original file line number Diff line number Diff line change
Expand Up @@ -117,20 +117,20 @@ RCLDOTNET_EXPORT
int32_t RCLDOTNET_CDECL native_rcl_action_client_wait_set_get_entities_ready(
void *wait_set_handle,
void *action_client_handle,
bool *is_feedback_ready,
bool *is_status_ready,
bool *is_goal_response_ready,
bool *is_cancel_response_ready,
bool *is_result_response_ready);
int32_t *is_feedback_ready,
int32_t *is_status_ready,
int32_t *is_goal_response_ready,
int32_t *is_cancel_response_ready,
int32_t *is_result_response_ready);

RCLDOTNET_EXPORT
int32_t RCLDOTNET_CDECL native_rcl_action_server_wait_set_get_entities_ready(
void *wait_set_handle,
void *action_server_handle,
bool *is_goal_request_ready,
bool *is_cancel_request_ready,
bool *is_result_request_ready,
bool *is_goal_expired);
int32_t *is_goal_request_ready,
int32_t *is_cancel_request_ready,
int32_t *is_result_request_ready,
int32_t *is_goal_expired);

RCLDOTNET_EXPORT
int32_t RCLDOTNET_CDECL native_rcl_take(void *, void *);
Expand Down Expand Up @@ -211,7 +211,7 @@ RCLDOTNET_EXPORT
int32_t RCLDOTNET_CDECL native_rcl_action_expire_goals(void *action_server_handle, void *goal_info_handle, int32_t *num_expired);

RCLDOTNET_EXPORT
bool RCLDOTNET_CDECL native_rcl_action_goal_handle_is_active(void *action_goal_handle_handle);
int32_t RCLDOTNET_CDECL native_rcl_action_goal_handle_is_active(void *action_goal_handle_handle);

RCLDOTNET_EXPORT
int32_t RCLDOTNET_CDECL native_rcl_action_goal_handle_get_status(void *action_goal_handle_handle, int8_t *status);
Expand Down
7 changes: 5 additions & 2 deletions rcldotnet/rcldotnet_action_client.c
Original file line number Diff line number Diff line change
Expand Up @@ -49,10 +49,13 @@ int32_t native_rcl_action_send_cancel_request(void *action_client_handle, void *
return ret;
}

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

rcl_ret_t ret = rcl_action_server_is_available(node, client, is_available);
bool is_available_as_bool;
rcl_ret_t ret = rcl_action_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_action_client.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,6 @@ RCLDOTNET_EXPORT
int32_t RCLDOTNET_CDECL native_rcl_action_send_cancel_request(void *action_client_handle, void *cancel_request_handle, int64_t *sequence_number);

RCLDOTNET_EXPORT
int32_t RCLDOTNET_CDECL native_rcl_action_server_is_available(void *node_handle, void *action_client_handle, bool *is_available);
int32_t RCLDOTNET_CDECL native_rcl_action_server_is_available(void *node_handle, void *action_client_handle, int32_t *is_available);

#endif // RCLDOTNET_CLIENT_H

0 comments on commit 44a6ec0

Please sign in to comment.