[rcl action] Exposes sequence numbers for all requests and responses. (#339)

This commit is contained in:
Michel Hidalgo 2018-11-21 21:50:03 -03:00 committed by Shane Loretz
parent f39ac3cbe7
commit f531f682ea
5 changed files with 130 additions and 58 deletions

View file

@ -264,6 +264,7 @@ rcl_action_client_get_default_options(void);
* *
* \param[in] action_client handle to the client that will make the goal request * \param[in] action_client handle to the client that will make the goal request
* \param[in] ros_goal_request pointer to the ROS goal message * \param[in] ros_goal_request pointer to the ROS goal message
* \param[out] sequence_number pointer to the goal request sequence number
* \return `RCL_RET_OK` if the request was sent successfully, or * \return `RCL_RET_OK` if the request was sent successfully, or
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
* \return `RCL_RET_ACTION_CLIENT_INVALID` if the client is invalid, or * \return `RCL_RET_ACTION_CLIENT_INVALID` if the client is invalid, or
@ -274,7 +275,8 @@ RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_action_send_goal_request( rcl_action_send_goal_request(
const rcl_action_client_t * action_client, const rcl_action_client_t * action_client,
const void * ros_goal_request); const void * ros_goal_request,
int64_t * sequence_number);
/// Take a response for a goal request from an action server using a rcl_action_client_t. /// Take a response for a goal request from an action server using a rcl_action_client_t.
/** /**
@ -306,6 +308,7 @@ rcl_action_send_goal_request(
* Lock-Free | Yes * Lock-Free | Yes
* *
* \param[in] action_client handle to the client that will take the goal response * \param[in] action_client handle to the client that will take the goal response
* \param[out] response_header pointer to the goal response header
* \param[out] ros_goal_response pointer to the response of a goal request * \param[out] ros_goal_response pointer to the response of a goal request
* \return `RCL_RET_OK` if the response was taken successfully, or * \return `RCL_RET_OK` if the response was taken successfully, or
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
@ -319,6 +322,7 @@ RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_action_take_goal_response( rcl_action_take_goal_response(
const rcl_action_client_t * action_client, const rcl_action_client_t * action_client,
rmw_request_id_t * response_header,
void * ros_goal_response); void * ros_goal_response);
/// Take a ROS feedback message for an active goal associated with a rcl_action_client_t. /// Take a ROS feedback message for an active goal associated with a rcl_action_client_t.
@ -450,6 +454,7 @@ rcl_action_take_status(
* \param[in] action_client handle to the client that will send the result request * \param[in] action_client handle to the client that will send the result request
* \param[in] ros_result_request pointer to a ROS result request message * \param[in] ros_result_request pointer to a ROS result request message
* \param[out] sequence_number pointer to the result request sequence number
* \return `RCL_RET_OK` if the request was sent successfully, or * \return `RCL_RET_OK` if the request was sent successfully, or
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
* \return `RCL_RET_ACTION_CLIENT_INVALID` if the action client is invalid, or * \return `RCL_RET_ACTION_CLIENT_INVALID` if the action client is invalid, or
@ -460,7 +465,8 @@ RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_action_send_result_request( rcl_action_send_result_request(
const rcl_action_client_t * action_client, const rcl_action_client_t * action_client,
const void * ros_result_request); const void * ros_result_request,
int64_t * sequence_number);
/// Take a ROS result message for a completed goal associated with a rcl_action_client_t. /// Take a ROS result message for a completed goal associated with a rcl_action_client_t.
/** /**
@ -497,6 +503,7 @@ rcl_action_send_result_request(
* <i>[1] only if required when filling the result response message, avoided for fixed sizes</i> * <i>[1] only if required when filling the result response message, avoided for fixed sizes</i>
* *
* \param[in] action_client handle to the client that will take the result response * \param[in] action_client handle to the client that will take the result response
* \param[out] response_header pointer to the result response header
* \param[out] ros_result_response preallocated, zero-initialized, struct where the ROS * \param[out] ros_result_response preallocated, zero-initialized, struct where the ROS
* result message is copied. * result message is copied.
* \return `RCL_RET_OK` if the response was taken successfully, or * \return `RCL_RET_OK` if the response was taken successfully, or
@ -512,6 +519,7 @@ RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_action_take_result_response( rcl_action_take_result_response(
const rcl_action_client_t * action_client, const rcl_action_client_t * action_client,
rmw_request_id_t * response_header,
void * ros_result); void * ros_result);
/// Send a cancel request for a goal using a rcl_action_client_t. /// Send a cancel request for a goal using a rcl_action_client_t.
@ -544,6 +552,7 @@ rcl_action_take_result_response(
* *
* \param[in] action_client handle to the client that will make the cancel request * \param[in] action_client handle to the client that will make the cancel request
* \param[in] ros_cancel_request pointer the ROS cancel request message * \param[in] ros_cancel_request pointer the ROS cancel request message
* \param[out] sequence_number pointer to the cancel request sequence number
* \return `RCL_RET_OK` if the response was taken successfully, or * \return `RCL_RET_OK` if the response was taken successfully, or
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
* \return `RCL_RET_ACTION_CLIENT_INVALID` if the action client is invalid, or * \return `RCL_RET_ACTION_CLIENT_INVALID` if the action client is invalid, or
@ -554,7 +563,8 @@ RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_action_send_cancel_request( rcl_action_send_cancel_request(
const rcl_action_client_t * action_client, const rcl_action_client_t * action_client,
const void * ros_cancel_request); const void * ros_cancel_request,
int64_t * sequence_number);
/// Take a cancel response using a rcl_action_client_t. /// Take a cancel response using a rcl_action_client_t.
/** /**
@ -585,6 +595,7 @@ rcl_action_send_cancel_request(
* Lock-Free | Yes * Lock-Free | Yes
* *
* \param[in] action_client handle to the client that will take the cancel response * \param[in] action_client handle to the client that will take the cancel response
* \param[out] request_header pointer to the cancel response header
* \param[out] ros_cancel_response a zero-initialized ROS cancel response message where * \param[out] ros_cancel_response a zero-initialized ROS cancel response message where
* the cancel response is copied. * the cancel response is copied.
* \return `RCL_RET_OK` if the response was taken successfully, or * \return `RCL_RET_OK` if the response was taken successfully, or
@ -600,6 +611,7 @@ RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_action_take_cancel_response( rcl_action_take_cancel_response(
const rcl_action_client_t * action_client, const rcl_action_client_t * action_client,
rmw_request_id_t * response_header,
void * ros_cancel_response); void * ros_cancel_response);
/// Get the name of the action for a rcl_action_client_t. /// Get the name of the action for a rcl_action_client_t.

View file

@ -258,6 +258,7 @@ rcl_action_server_get_default_options(void);
* <i>[1] only if required when filling the request, avoided for fixed sizes</i> * <i>[1] only if required when filling the request, avoided for fixed sizes</i>
* *
* \param[in] action_server handle to the action server that will take the request * \param[in] action_server handle to the action server that will take the request
* \param[out] request_header pointer to the goal request header
* \param[out] ros_goal_request a preallocated, zero-initialized, ROS goal request message * \param[out] ros_goal_request a preallocated, zero-initialized, ROS goal request message
* where the request is copied * where the request is copied
* \return `RCL_RET_OK` if the request was taken, or * \return `RCL_RET_OK` if the request was taken, or
@ -273,6 +274,7 @@ RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_action_take_goal_request( rcl_action_take_goal_request(
const rcl_action_server_t * action_server, const rcl_action_server_t * action_server,
rmw_request_id_t * request_header,
void * ros_goal_request); void * ros_goal_request);
/// Send a response for a goal request to an action client using an action server. /// Send a response for a goal request to an action client using an action server.
@ -308,6 +310,7 @@ rcl_action_take_goal_request(
* <i>[1] for unique pairs of action servers and responses, see above for more</i> * <i>[1] for unique pairs of action servers and responses, see above for more</i>
* *
* \param[in] action_server handle to the action server that will make the goal response * \param[in] action_server handle to the action server that will make the goal response
* \param[in] response_header pointer to the goal response header
* \param[in] ros_goal_response a ROS goal response message to send * \param[in] ros_goal_response a ROS goal response message to send
* \return `RCL_RET_OK` if the response was sent successfully, or * \return `RCL_RET_OK` if the response was sent successfully, or
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
@ -319,6 +322,7 @@ RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_action_send_goal_response( rcl_action_send_goal_response(
const rcl_action_server_t * action_server, const rcl_action_server_t * action_server,
rmw_request_id_t * response_header,
void * ros_goal_response); void * ros_goal_response);
/// Accept a new goal using an action server. /// Accept a new goal using an action server.
@ -509,6 +513,7 @@ rcl_action_publish_status(
* Lock-Free | Yes * Lock-Free | Yes
* *
* \param[in] action_server handle to the action server that will take the result request * \param[in] action_server handle to the action server that will take the result request
* \param[out] request_header pointer to the result request header
* \param[out] ros_result_request a preallocated ROS result request message where the * \param[out] ros_result_request a preallocated ROS result request message where the
* request is copied. * request is copied.
* \return `RCL_RET_OK` if the response was sent successfully, or * \return `RCL_RET_OK` if the response was sent successfully, or
@ -523,6 +528,7 @@ RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_action_take_result_request( rcl_action_take_result_request(
const rcl_action_server_t * action_server, const rcl_action_server_t * action_server,
rmw_request_id_t * request_header,
void * ros_result_request); void * ros_result_request);
/// Send a result response using an action server. /// Send a result response using an action server.
@ -546,6 +552,7 @@ rcl_action_take_result_request(
* Lock-Free | Yes * Lock-Free | Yes
* *
* \param[in] action_server handle to the action server that will send the result response * \param[in] action_server handle to the action server that will send the result response
* \param[in] response_header pointer to the result response header
* \param[in] ros_result_response a ROS result response message to send * \param[in] ros_result_response a ROS result response message to send
* \return `RCL_RET_OK` if the response was sent successfully, or * \return `RCL_RET_OK` if the response was sent successfully, or
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
@ -557,6 +564,7 @@ RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_action_send_result_response( rcl_action_send_result_response(
const rcl_action_server_t * action_server, const rcl_action_server_t * action_server,
rmw_request_id_t * response_header,
void * ros_result_response); void * ros_result_response);
/// Expires goals associated with an action server. /// Expires goals associated with an action server.
@ -629,6 +637,7 @@ rcl_action_expire_goals(
* Lock-Free | Yes * Lock-Free | Yes
* *
* \param[in] action_server handle to the action server that will take the cancel request * \param[in] action_server handle to the action server that will take the cancel request
* \param[out] request_header pointer to the cancel request header
* \param[out] ros_cancel_request a preallocated ROS cancel request where the request * \param[out] ros_cancel_request a preallocated ROS cancel request where the request
* message is copied * message is copied
* \return `RCL_RET_OK` if the response was sent successfully, or * \return `RCL_RET_OK` if the response was sent successfully, or
@ -643,6 +652,7 @@ RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_action_take_cancel_request( rcl_action_take_cancel_request(
const rcl_action_server_t * action_server, const rcl_action_server_t * action_server,
rmw_request_id_t * request_header,
void * ros_cancel_request); void * ros_cancel_request);
/// Process a cancel request using an action server. /// Process a cancel request using an action server.
@ -702,6 +712,7 @@ rcl_action_process_cancel_request(
* Lock-Free | Yes * Lock-Free | Yes
* *
* \param[in] action_server handle to the action server that will send the cancel response * \param[in] action_server handle to the action server that will send the cancel response
* \param[in] response_header pointer to the cancel response header
* \param[in] ros_cancel_response a ROS cancel response to send * \param[in] ros_cancel_response a ROS cancel response to send
* \return `RCL_RET_OK` if the request was taken, or * \return `RCL_RET_OK` if the request was taken, or
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
@ -713,6 +724,7 @@ RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_action_send_cancel_response( rcl_action_send_cancel_response(
const rcl_action_server_t * action_server, const rcl_action_server_t * action_server,
rmw_request_id_t * response_header,
void * ros_cancel_response); void * ros_cancel_response);
/// Get the action name for an action server. /// Get the action name for an action server.

View file

@ -240,15 +240,15 @@ rcl_action_client_get_default_options(void)
} }
// \internal Sends an action client specific service request. // \internal Sends an action client specific service request.
#define SEND_SERVICE_REQUEST(Type) \ #define SEND_SERVICE_REQUEST(Type, request, sequence_number) \
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Sending action " #Type " request"); \ RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Sending action " #Type " request"); \
if (!rcl_action_client_is_valid(action_client)) { \ if (!rcl_action_client_is_valid(action_client)) { \
return RCL_RET_ACTION_SERVER_INVALID; /* error already set */ \ return RCL_RET_ACTION_SERVER_INVALID; /* error already set */ \
} \ } \
RCL_CHECK_ARGUMENT_FOR_NULL(ros_ ## Type ## _request, RCL_RET_INVALID_ARGUMENT); \ RCL_CHECK_ARGUMENT_FOR_NULL(request, RCL_RET_INVALID_ARGUMENT); \
int64_t sequence_number; /* ignored */ \ RCL_CHECK_ARGUMENT_FOR_NULL(sequence_number, RCL_RET_INVALID_ARGUMENT); \
rcl_ret_t ret = rcl_send_request( \ rcl_ret_t ret = rcl_send_request( \
&action_client->impl->Type ## _client, ros_ ## Type ## _request, &sequence_number); \ &action_client->impl->Type ## _client, request, sequence_number); \
if (RCL_RET_OK != ret) { \ if (RCL_RET_OK != ret) { \
return RCL_RET_ERROR; /* error already set */ \ return RCL_RET_ERROR; /* error already set */ \
} \ } \
@ -256,15 +256,15 @@ rcl_action_client_get_default_options(void)
return RCL_RET_OK; return RCL_RET_OK;
// \internal Takes an action client specific service response. // \internal Takes an action client specific service response.
#define TAKE_SERVICE_RESPONSE(Type) \ #define TAKE_SERVICE_RESPONSE(Type, response_header, response) \
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Taking action " #Type " response"); \ RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Taking action " #Type " response"); \
if (!rcl_action_client_is_valid(action_client)) { \ if (!rcl_action_client_is_valid(action_client)) { \
return RCL_RET_ACTION_SERVER_INVALID; /* error already set */ \ return RCL_RET_ACTION_SERVER_INVALID; /* error already set */ \
} \ } \
RCL_CHECK_ARGUMENT_FOR_NULL(ros_ ## Type ## _response, RCL_RET_INVALID_ARGUMENT); \ RCL_CHECK_ARGUMENT_FOR_NULL(response_header, RCL_RET_INVALID_ARGUMENT); \
rmw_request_id_t request_header; /* ignored */ \ RCL_CHECK_ARGUMENT_FOR_NULL(response, RCL_RET_INVALID_ARGUMENT); \
rcl_ret_t ret = rcl_take_response( \ rcl_ret_t ret = rcl_take_response( \
&action_client->impl->Type ## _client, &request_header, ros_ ## Type ## _response); \ &action_client->impl->Type ## _client, response_header, response); \
if (RCL_RET_OK != ret) { \ if (RCL_RET_OK != ret) { \
if (RCL_RET_BAD_ALLOC == ret) { \ if (RCL_RET_BAD_ALLOC == ret) { \
return RCL_RET_BAD_ALLOC; /* error already set */ \ return RCL_RET_BAD_ALLOC; /* error already set */ \
@ -281,49 +281,55 @@ rcl_action_client_get_default_options(void)
rcl_ret_t rcl_ret_t
rcl_action_send_goal_request( rcl_action_send_goal_request(
const rcl_action_client_t * action_client, const rcl_action_client_t * action_client,
const void * ros_goal_request) const void * ros_goal_request,
int64_t * sequence_number)
{ {
SEND_SERVICE_REQUEST(goal) SEND_SERVICE_REQUEST(goal, ros_goal_request, sequence_number);
} }
rcl_ret_t rcl_ret_t
rcl_action_take_goal_response( rcl_action_take_goal_response(
const rcl_action_client_t * action_client, const rcl_action_client_t * action_client,
rmw_request_id_t * response_header,
void * ros_goal_response) void * ros_goal_response)
{ {
TAKE_SERVICE_RESPONSE(goal); TAKE_SERVICE_RESPONSE(goal, response_header, ros_goal_response);
} }
rcl_ret_t rcl_ret_t
rcl_action_send_result_request( rcl_action_send_result_request(
const rcl_action_client_t * action_client, const rcl_action_client_t * action_client,
const void * ros_result_request) const void * ros_result_request,
int64_t * sequence_number)
{ {
SEND_SERVICE_REQUEST(result); SEND_SERVICE_REQUEST(result, ros_result_request, sequence_number);
} }
rcl_ret_t rcl_ret_t
rcl_action_take_result_response( rcl_action_take_result_response(
const rcl_action_client_t * action_client, const rcl_action_client_t * action_client,
rmw_request_id_t * response_header,
void * ros_result_response) void * ros_result_response)
{ {
TAKE_SERVICE_RESPONSE(result); TAKE_SERVICE_RESPONSE(result, response_header, ros_result_response);
} }
rcl_ret_t rcl_ret_t
rcl_action_send_cancel_request( rcl_action_send_cancel_request(
const rcl_action_client_t * action_client, const rcl_action_client_t * action_client,
const void * ros_cancel_request) const void * ros_cancel_request,
int64_t * sequence_number)
{ {
SEND_SERVICE_REQUEST(cancel); SEND_SERVICE_REQUEST(cancel, ros_cancel_request, sequence_number);
} }
rcl_ret_t rcl_ret_t
rcl_action_take_cancel_response( rcl_action_take_cancel_response(
const rcl_action_client_t * action_client, const rcl_action_client_t * action_client,
rmw_request_id_t * response_header,
void * ros_cancel_response) void * ros_cancel_response)
{ {
TAKE_SERVICE_RESPONSE(cancel); TAKE_SERVICE_RESPONSE(cancel, response_header, ros_cancel_response);
} }
// \internal Takes an action client specific topic message. // \internal Takes an action client specific topic message.

View file

@ -264,14 +264,14 @@ rcl_action_server_get_default_options(void)
return default_options; return default_options;
} }
#define TAKE_SERVICE_REQUEST(Type) \ #define TAKE_SERVICE_REQUEST(Type, request_header, request) \
if (!rcl_action_server_is_valid(action_server)) { \ if (!rcl_action_server_is_valid(action_server)) { \
return RCL_RET_ACTION_SERVER_INVALID; /* error already set */ \ return RCL_RET_ACTION_SERVER_INVALID; /* error already set */ \
} \ } \
RCL_CHECK_ARGUMENT_FOR_NULL(ros_ ## Type ## _request, RCL_RET_INVALID_ARGUMENT); \ RCL_CHECK_ARGUMENT_FOR_NULL(request_header, RCL_RET_INVALID_ARGUMENT); \
rmw_request_id_t request_header; /* ignored */ \ RCL_CHECK_ARGUMENT_FOR_NULL(request, RCL_RET_INVALID_ARGUMENT); \
rcl_ret_t ret = rcl_take_request( \ rcl_ret_t ret = rcl_take_request( \
&action_server->impl->Type ## _service, &request_header, ros_ ## Type ## _request); \ &action_server->impl->Type ## _service, request_header, request); \
if (RCL_RET_OK != ret) { \ if (RCL_RET_OK != ret) { \
if (RCL_RET_BAD_ALLOC == ret) { \ if (RCL_RET_BAD_ALLOC == ret) { \
return RCL_RET_BAD_ALLOC; /* error already set */ \ return RCL_RET_BAD_ALLOC; /* error already set */ \
@ -283,14 +283,14 @@ rcl_action_server_get_default_options(void)
} \ } \
return RCL_RET_OK; \ return RCL_RET_OK; \
#define SEND_SERVICE_RESPONSE(Type) \ #define SEND_SERVICE_RESPONSE(Type, response_header, response) \
if (!rcl_action_server_is_valid(action_server)) { \ if (!rcl_action_server_is_valid(action_server)) { \
return RCL_RET_ACTION_SERVER_INVALID; /* error already set */ \ return RCL_RET_ACTION_SERVER_INVALID; /* error already set */ \
} \ } \
RCL_CHECK_ARGUMENT_FOR_NULL(ros_ ## Type ## _response, RCL_RET_INVALID_ARGUMENT); \ RCL_CHECK_ARGUMENT_FOR_NULL(response_header, RCL_RET_INVALID_ARGUMENT); \
rmw_request_id_t request_header; /* ignored */ \ RCL_CHECK_ARGUMENT_FOR_NULL(response, RCL_RET_INVALID_ARGUMENT); \
rcl_ret_t ret = rcl_send_response( \ rcl_ret_t ret = rcl_send_response( \
&action_server->impl->Type ## _service, &request_header, ros_ ## Type ## _response); \ &action_server->impl->Type ## _service, response_header, response); \
if (RCL_RET_OK != ret) { \ if (RCL_RET_OK != ret) { \
return RCL_RET_ERROR; /* error already set */ \ return RCL_RET_ERROR; /* error already set */ \
} \ } \
@ -299,17 +299,19 @@ rcl_action_server_get_default_options(void)
rcl_ret_t rcl_ret_t
rcl_action_take_goal_request( rcl_action_take_goal_request(
const rcl_action_server_t * action_server, const rcl_action_server_t * action_server,
rmw_request_id_t * request_header,
void * ros_goal_request) void * ros_goal_request)
{ {
TAKE_SERVICE_REQUEST(goal); TAKE_SERVICE_REQUEST(goal, request_header, ros_goal_request);
} }
rcl_ret_t rcl_ret_t
rcl_action_send_goal_response( rcl_action_send_goal_response(
const rcl_action_server_t * action_server, const rcl_action_server_t * action_server,
rmw_request_id_t * response_header,
void * ros_goal_response) void * ros_goal_response)
{ {
SEND_SERVICE_RESPONSE(goal); SEND_SERVICE_RESPONSE(goal, response_header, ros_goal_response);
} }
// Implementation only // Implementation only
@ -481,17 +483,19 @@ rcl_action_publish_status(
rcl_ret_t rcl_ret_t
rcl_action_take_result_request( rcl_action_take_result_request(
const rcl_action_server_t * action_server, const rcl_action_server_t * action_server,
rmw_request_id_t * request_header,
void * ros_result_request) void * ros_result_request)
{ {
TAKE_SERVICE_REQUEST(result); TAKE_SERVICE_REQUEST(result, request_header, ros_result_request);
} }
rcl_ret_t rcl_ret_t
rcl_action_send_result_response( rcl_action_send_result_response(
const rcl_action_server_t * action_server, const rcl_action_server_t * action_server,
rmw_request_id_t * response_header,
void * ros_result_response) void * ros_result_response)
{ {
SEND_SERVICE_RESPONSE(result); SEND_SERVICE_RESPONSE(result, response_header, ros_result_response);
} }
rcl_ret_t rcl_ret_t
@ -571,9 +575,10 @@ rcl_action_expire_goals(
rcl_ret_t rcl_ret_t
rcl_action_take_cancel_request( rcl_action_take_cancel_request(
const rcl_action_server_t * action_server, const rcl_action_server_t * action_server,
rmw_request_id_t * request_header,
void * ros_cancel_request) void * ros_cancel_request)
{ {
TAKE_SERVICE_REQUEST(cancel); TAKE_SERVICE_REQUEST(cancel, request_header, ros_cancel_request);
} }
rcl_ret_t rcl_ret_t
@ -694,9 +699,10 @@ cleanup:
rcl_ret_t rcl_ret_t
rcl_action_send_cancel_response( rcl_action_send_cancel_response(
const rcl_action_server_t * action_server, const rcl_action_server_t * action_server,
rmw_request_id_t * response_header,
void * ros_cancel_response) void * ros_cancel_response)
{ {
SEND_SERVICE_RESPONSE(cancel); SEND_SERVICE_RESPONSE(cancel, response_header, ros_cancel_response);
} }
const char * const char *

View file

@ -89,24 +89,30 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_take_goal_re
test_msgs__action__Fibonacci_Goal_Request__init(&goal_request); test_msgs__action__Fibonacci_Goal_Request__init(&goal_request);
// Take request with null action server // Take request with null action server
rcl_ret_t ret = rcl_action_take_goal_request(nullptr, &goal_request); rmw_request_id_t request_header;
rcl_ret_t ret = rcl_action_take_goal_request(nullptr, &request_header, &goal_request);
EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID); EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID);
rcl_reset_error(); rcl_reset_error();
// Take request with null header
ret = rcl_action_take_goal_request(&this->action_server, nullptr, &goal_request);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
rcl_reset_error();
// Take request with null message // Take request with null message
ret = rcl_action_take_goal_request(&this->action_server, nullptr); ret = rcl_action_take_goal_request(&this->action_server, &request_header, nullptr);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT); EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
rcl_reset_error(); rcl_reset_error();
// Take request with invalid action server // Take request with invalid action server
rcl_action_server_t invalid_action_server = rcl_action_get_zero_initialized_server(); rcl_action_server_t invalid_action_server = rcl_action_get_zero_initialized_server();
ret = rcl_action_take_goal_request(&invalid_action_server, &goal_request); ret = rcl_action_take_goal_request(&invalid_action_server, &request_header, &goal_request);
EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID); EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID);
rcl_reset_error(); rcl_reset_error();
// Take with valid arguments // Take with valid arguments
// TODO(jacobperron): Send a request from a client // TODO(jacobperron): Send a request from a client
// ret = rcl_action_take_goal_request(&this->action_server, &goal_request); // ret = rcl_action_take_goal_request(&this->action_server, &request_header, &goal_request);
// EXPECT_EQ(ret, RCL_RET_OK); // EXPECT_EQ(ret, RCL_RET_OK);
test_msgs__action__Fibonacci_Goal_Request__fini(&goal_request); test_msgs__action__Fibonacci_Goal_Request__fini(&goal_request);
@ -118,24 +124,30 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_send_goal_re
test_msgs__action__Fibonacci_Goal_Response__init(&goal_response); test_msgs__action__Fibonacci_Goal_Response__init(&goal_response);
// Send response with null action server // Send response with null action server
rcl_ret_t ret = rcl_action_send_goal_response(nullptr, &goal_response); rmw_request_id_t response_header;
rcl_ret_t ret = rcl_action_send_goal_response(nullptr, &response_header, &goal_response);
EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID); EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID);
rcl_reset_error(); rcl_reset_error();
// Send response with null header
ret = rcl_action_send_goal_response(&this->action_server, nullptr, &goal_response);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
rcl_reset_error();
// Send response with null message // Send response with null message
ret = rcl_action_send_goal_response(&this->action_server, nullptr); ret = rcl_action_send_goal_response(&this->action_server, &response_header, nullptr);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT); EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
rcl_reset_error(); rcl_reset_error();
// Send response with invalid action server // Send response with invalid action server
rcl_action_server_t invalid_action_server = rcl_action_get_zero_initialized_server(); rcl_action_server_t invalid_action_server = rcl_action_get_zero_initialized_server();
ret = rcl_action_send_goal_response(&invalid_action_server, &goal_response); ret = rcl_action_send_goal_response(&invalid_action_server, &response_header, &goal_response);
EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID); EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID);
rcl_reset_error(); rcl_reset_error();
// Send with valid arguments // Send with valid arguments
// TODO(jacobperron): Check with client on receiving end // TODO(jacobperron): Check with client on receiving end
ret = rcl_action_send_goal_response(&this->action_server, &goal_response); ret = rcl_action_send_goal_response(&this->action_server, &response_header, &goal_response);
EXPECT_EQ(ret, RCL_RET_OK); EXPECT_EQ(ret, RCL_RET_OK);
test_msgs__action__Fibonacci_Goal_Response__fini(&goal_response); test_msgs__action__Fibonacci_Goal_Response__fini(&goal_response);
@ -147,24 +159,30 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_take_cancel_
action_msgs__srv__CancelGoal_Request__init(&cancel_request); action_msgs__srv__CancelGoal_Request__init(&cancel_request);
// Take request with null action server // Take request with null action server
rcl_ret_t ret = rcl_action_take_cancel_request(nullptr, &cancel_request); rmw_request_id_t request_header;
rcl_ret_t ret = rcl_action_take_cancel_request(nullptr, &request_header, &cancel_request);
EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID); EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID);
rcl_reset_error(); rcl_reset_error();
// Take request with null header
ret = rcl_action_take_cancel_request(&this->action_server, nullptr, &cancel_request);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
rcl_reset_error();
// Take request with null message // Take request with null message
ret = rcl_action_take_cancel_request(&this->action_server, nullptr); ret = rcl_action_take_cancel_request(&this->action_server, &request_header, nullptr);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT); EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
rcl_reset_error(); rcl_reset_error();
// Take request with invalid action server // Take request with invalid action server
rcl_action_server_t invalid_action_server = rcl_action_get_zero_initialized_server(); rcl_action_server_t invalid_action_server = rcl_action_get_zero_initialized_server();
ret = rcl_action_take_cancel_request(&invalid_action_server, &cancel_request); ret = rcl_action_take_cancel_request(&invalid_action_server, &request_header, &cancel_request);
EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID); EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID);
rcl_reset_error(); rcl_reset_error();
// Take with valid arguments // Take with valid arguments
// TODO(jacobperron): Send a request from a client // TODO(jacobperron): Send a request from a client
// ret = rcl_action_take_cancel_request(&this->action_server, &cancel_request); // ret = rcl_action_take_cancel_request(&this->action_server, &request_header, &cancel_request);
// EXPECT_EQ(ret, RCL_RET_OK); // EXPECT_EQ(ret, RCL_RET_OK);
action_msgs__srv__CancelGoal_Request__fini(&cancel_request); action_msgs__srv__CancelGoal_Request__fini(&cancel_request);
@ -176,24 +194,30 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_send_cancel_
action_msgs__srv__CancelGoal_Response__init(&cancel_response); action_msgs__srv__CancelGoal_Response__init(&cancel_response);
// Send response with null action server // Send response with null action server
rcl_ret_t ret = rcl_action_send_cancel_response(nullptr, &cancel_response); rmw_request_id_t response_header;
rcl_ret_t ret = rcl_action_send_cancel_response(nullptr, &response_header, &cancel_response);
EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID); EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID);
rcl_reset_error(); rcl_reset_error();
// Send response with null header
ret = rcl_action_send_cancel_response(&this->action_server, nullptr, &cancel_response);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
rcl_reset_error();
// Send response with null message // Send response with null message
ret = rcl_action_send_cancel_response(&this->action_server, nullptr); ret = rcl_action_send_cancel_response(&this->action_server, &response_header, nullptr);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT); EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
rcl_reset_error(); rcl_reset_error();
// Send response with invalid action server // Send response with invalid action server
rcl_action_server_t invalid_action_server = rcl_action_get_zero_initialized_server(); rcl_action_server_t invalid_action_server = rcl_action_get_zero_initialized_server();
ret = rcl_action_send_cancel_response(&invalid_action_server, &cancel_response); ret = rcl_action_send_cancel_response(&invalid_action_server, &response_header, &cancel_response);
EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID); EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID);
rcl_reset_error(); rcl_reset_error();
// Send with valid arguments // Send with valid arguments
// TODO(jacobperron): Check with client on receiving end // TODO(jacobperron): Check with client on receiving end
ret = rcl_action_send_cancel_response(&this->action_server, &cancel_response); ret = rcl_action_send_cancel_response(&this->action_server, &response_header, &cancel_response);
EXPECT_EQ(ret, RCL_RET_OK); EXPECT_EQ(ret, RCL_RET_OK);
action_msgs__srv__CancelGoal_Response__fini(&cancel_response); action_msgs__srv__CancelGoal_Response__fini(&cancel_response);
@ -205,24 +229,30 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_take_result_
test_msgs__action__Fibonacci_Result_Request__init(&result_request); test_msgs__action__Fibonacci_Result_Request__init(&result_request);
// Take request with null action server // Take request with null action server
rcl_ret_t ret = rcl_action_take_result_request(nullptr, &result_request); rmw_request_id_t request_header;
rcl_ret_t ret = rcl_action_take_result_request(nullptr, &request_header, &result_request);
EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID); EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID);
rcl_reset_error(); rcl_reset_error();
// Take request with null header
ret = rcl_action_take_result_request(&this->action_server, nullptr, &result_request);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
rcl_reset_error();
// Take request with null message // Take request with null message
ret = rcl_action_take_result_request(&this->action_server, nullptr); ret = rcl_action_take_result_request(&this->action_server, &request_header, nullptr);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT); EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
rcl_reset_error(); rcl_reset_error();
// Take request with invalid action server // Take request with invalid action server
rcl_action_server_t invalid_action_server = rcl_action_get_zero_initialized_server(); rcl_action_server_t invalid_action_server = rcl_action_get_zero_initialized_server();
ret = rcl_action_take_result_request(&invalid_action_server, &result_request); ret = rcl_action_take_result_request(&invalid_action_server, &request_header, &result_request);
EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID); EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID);
rcl_reset_error(); rcl_reset_error();
// Take with valid arguments // Take with valid arguments
// TODO(jacobperron): Send a request from a client // TODO(jacobperron): Send a request from a client
// ret = rcl_action_take_result_request(&this->action_server, &result_request); // ret = rcl_action_take_result_request(&this->action_server, &request_header, &result_request);
// EXPECT_EQ(ret, RCL_RET_OK); // EXPECT_EQ(ret, RCL_RET_OK);
test_msgs__action__Fibonacci_Result_Request__fini(&result_request); test_msgs__action__Fibonacci_Result_Request__fini(&result_request);
@ -234,24 +264,30 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_send_result_
test_msgs__action__Fibonacci_Result_Response__init(&result_response); test_msgs__action__Fibonacci_Result_Response__init(&result_response);
// Send response with null action server // Send response with null action server
rcl_ret_t ret = rcl_action_send_result_response(nullptr, &result_response); rmw_request_id_t response_header;
rcl_ret_t ret = rcl_action_send_result_response(nullptr, &response_header, &result_response);
EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID); EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID);
rcl_reset_error(); rcl_reset_error();
// Send response with null header
ret = rcl_action_send_result_response(&this->action_server, nullptr, &result_response);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
rcl_reset_error();
// Send response with null message // Send response with null message
ret = rcl_action_send_result_response(&this->action_server, nullptr); ret = rcl_action_send_result_response(&this->action_server, &response_header, nullptr);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT); EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
rcl_reset_error(); rcl_reset_error();
// Send response with invalid action server // Send response with invalid action server
rcl_action_server_t invalid_action_server = rcl_action_get_zero_initialized_server(); rcl_action_server_t invalid_action_server = rcl_action_get_zero_initialized_server();
ret = rcl_action_send_result_response(&invalid_action_server, &result_response); ret = rcl_action_send_result_response(&invalid_action_server, &response_header, &result_response);
EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID); EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID);
rcl_reset_error(); rcl_reset_error();
// Send with valid arguments // Send with valid arguments
// TODO(jacobperron): Check with client on receiving end // TODO(jacobperron): Check with client on receiving end
ret = rcl_action_send_result_response(&this->action_server, &result_response); ret = rcl_action_send_result_response(&this->action_server, &response_header, &result_response);
EXPECT_EQ(ret, RCL_RET_OK); EXPECT_EQ(ret, RCL_RET_OK);
test_msgs__action__Fibonacci_Result_Response__fini(&result_response); test_msgs__action__Fibonacci_Result_Response__fini(&result_response);