Function rcl_action_send_result_response
Defined in File action_server.h
Function Documentation
-
rcl_ret_t rcl_action_send_result_response(const rcl_action_server_t *action_server, rmw_request_id_t *response_header, void *ros_result_response)
Send a result response using an action server.
This is a non-blocking call.
The caller is responsible for ensuring that the type of
ros_result_response
and the type associate with the client (via the type support) match. Passing a different type produces undefined behavior and cannot be checked by this function and therefore no deliberate error will occur.Before calling this function, the caller should use rcl_action_update_goal_state() to update the goals state to the appropriate terminal state.
Attribute
Adherence
Allocates Memory
No
Thread-Safe
No
Uses Atomics
No
Lock-Free
Yes
- Parameters:
action_server – [in] handle to the action server that will send the result response
response_header – [in] pointer to the result response header
ros_result_response – [in] a ROS result response message to send
- Returns:
RCL_RET_OK
if the response was sent successfully, or- Returns:
RCL_RET_INVALID_ARGUMENT
if any arguments are invalid, or- Returns:
RCL_RET_ACTION_SERVER_INVALID
if the action server is invalid, or- Returns:
RCL_RET_TIMEOUT
if a result response reader is not ready yet, or- Returns:
RCL_RET_ERROR
if an unspecified error occurs.