Add action server implementation (#323)
* Implement action server init, fini, and is_valid functions * Add macros for initializing services and publishers * Implement rcl_action_server_get_default_options() * Implement rcl_action_accept_new_goal() * Add function, rcl_action_server_goal_exists(), for checking if goal is already being tracked by an action server * Add unit tests * Implement rcl_action_server_get_goal_handles() * Implement rcl_action_server_get_options() * Implement rcl_action_server_get_action_name() * Implement rcl_action_get_goal_status_array() * Bugfix: reset pointers and size in type finalize functions Also let finalize functions be called on already finalized objects * Implement send/take functions for action server services * Implement action server publishers for feedback and status * Implement rcl_action_process_cancel_request() * Add partial communication tests * Define UUID_SIZE * Use type-erased pointer for rcl_action_publish_status() * Implement rcl_action_clear_expired_goals() Introduce rcl_clock_t to action server implementation. * Change internal goal handle array to be an array of pointers. * Add check for invalid action names * Do heap allocation of temporary array to satisfy MSVC compiler * Bugfix: finalize node in test tear downs and reset expected errors * Update documentation * Update package.xml * Pass in rcl_clock_t to action server Rather than initializing internally. * Do not finalize goal handles in expire function Instead, leave it up to the caller to finalize goal handles. Renamed the function to rcl_action_expire_goals.
This commit is contained in:
parent
d86d1c4135
commit
acc974e43b
11 changed files with 1879 additions and 94 deletions
|
@ -27,6 +27,7 @@ extern "C"
|
|||
#include "rcl/node.h"
|
||||
#include "rcl/time.h"
|
||||
|
||||
#include "rosidl_generator_c/action_type_support_struct.h"
|
||||
|
||||
/// Internal rcl_action implementation struct.
|
||||
struct rcl_action_server_impl_t;
|
||||
|
@ -42,13 +43,15 @@ typedef struct rcl_action_server_options_t
|
|||
{
|
||||
/// Middleware quality of service settings for the action server.
|
||||
rmw_qos_profile_t goal_service_qos;
|
||||
rmw_qos_profile_t result_service_qos;
|
||||
rmw_qos_profile_t cancel_service_qos;
|
||||
rmw_qos_profile_t result_service_qos;
|
||||
rmw_qos_profile_t feedback_topic_qos;
|
||||
rmw_qos_profile_t status_topic_qos;
|
||||
/// Custom allocator for the action server, used for incidental allocations.
|
||||
/** For default behavior (malloc/free), see: rcl_get_default_allocator() */
|
||||
rcl_allocator_t allocator;
|
||||
/// Clock type used for checking result timeouts.
|
||||
rcl_clock_type_t clock_type;
|
||||
/// Goal handles that have results longer than this time are deallocated.
|
||||
rcl_duration_t result_timeout;
|
||||
} rcl_action_server_options_t;
|
||||
|
@ -63,7 +66,7 @@ RCL_WARN_UNUSED
|
|||
rcl_action_server_t
|
||||
rcl_action_get_zero_initialized_server(void);
|
||||
|
||||
/// Initialize a rcl_action_server_t.
|
||||
/// Initialize an action server.
|
||||
/**
|
||||
* After calling this function on a rcl_action_server_t, it can be used to take
|
||||
* goals of the given type for the given action name using rcl_action_take_goal_request()
|
||||
|
@ -78,6 +81,9 @@ rcl_action_get_zero_initialized_server(void);
|
|||
* The given rcl_node_t must be valid and the resulting rcl_action_server_t is
|
||||
* only valid as long as the given rcl_node_t remains valid.
|
||||
*
|
||||
* The give rcl_clock_t must be valid and the resulting rcl_ction_server_t is
|
||||
* only valid as long ast he given rcl_clock_t remains valid.
|
||||
*
|
||||
* The rosidl_action_type_support_t is obtained on a per .action type basis.
|
||||
* When the user defines a ROS action, code is generated which provides the
|
||||
* required rosidl_action_type_support_t object.
|
||||
|
@ -147,9 +153,10 @@ rcl_action_get_zero_initialized_server(void);
|
|||
* Uses Atomics | No
|
||||
* Lock-Free | Yes
|
||||
*
|
||||
* \param[out] action_server a preallocated, zero-initialized action server structure
|
||||
* \param[out] action_server handle to a preallocated, zero-initialized action server structure
|
||||
* to be initialized.
|
||||
* \param[in] node valid rcl node handle
|
||||
* \param[in] node valid node handle
|
||||
* \param[in] clock valid clock handle
|
||||
* \param[in] type_support type support object for the action's type
|
||||
* \param[in] action_name the name of the action
|
||||
* \param[in] options action_server options, including quality of service settings
|
||||
|
@ -165,14 +172,15 @@ RCL_WARN_UNUSED
|
|||
rcl_ret_t
|
||||
rcl_action_server_init(
|
||||
rcl_action_server_t * action_server,
|
||||
const rcl_node_t * node,
|
||||
rcl_node_t * node,
|
||||
rcl_clock_t * clock,
|
||||
const rosidl_action_type_support_t * type_support,
|
||||
const char * action_name,
|
||||
const rcl_action_server_options_t * options);
|
||||
|
||||
/// Finalize a rcl_action_server_t.
|
||||
/// Finalize an action server.
|
||||
/**
|
||||
* After calling, the node will no longer listen for goals for this action server.
|
||||
* After calling, the node will no longer listen to services and topics for this action server.
|
||||
* (assuming this is the only action server of this type in this node).
|
||||
*
|
||||
* After calling, calls to rcl_wait(), rcl_action_take_goal_request(),
|
||||
|
@ -193,7 +201,7 @@ rcl_action_server_init(
|
|||
* \param[inout] action_server handle to the action_server to be deinitialized
|
||||
* \param[in] node handle to the node used to create the action server
|
||||
* \return `RCL_RET_OK` if the action server was deinitialized successfully, or
|
||||
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||
* \return `RCL_RET_ACTION_SERVER_INVALID` if the action server pointer is null, or
|
||||
* \return `RCL_RET_NODE_INVALID` if the node is invalid, or
|
||||
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||
*/
|
||||
|
@ -207,19 +215,19 @@ rcl_action_server_fini(rcl_action_server_t * action_server, rcl_node_t * node);
|
|||
* The defaults are:
|
||||
*
|
||||
* - goal_service_qos = rmw_qos_profile_services_default;
|
||||
* - result_service_qos = rmw_qos_profile_services_default;
|
||||
* - cancel_service_qos = rmw_qos_profile_services_default;
|
||||
* - result_service_qos = rmw_qos_profile_services_default;
|
||||
* - feedback_topic_qos = rmw_qos_profile_default;
|
||||
* - status_topic_qos = rcl_action_qos_profile_status_default;
|
||||
* - allocator = rcl_get_default_allocator()
|
||||
- result_timeout = 9e+11; // 15 minutes
|
||||
* - allocator = rcl_get_default_allocator();
|
||||
* - result_timeout = RCUTILS_S_TO_NS(15 * 60); // 15 minutes
|
||||
*/
|
||||
RCL_ACTION_PUBLIC
|
||||
RCL_WARN_UNUSED
|
||||
rcl_action_server_options_t
|
||||
rcl_action_server_get_default_options(void);
|
||||
|
||||
/// Take a pending ROS goal using a rcl_action_server_t.
|
||||
/// Take a pending ROS goal using an action server.
|
||||
/**
|
||||
* \todo TODO(jacobperron) blocking of take?
|
||||
*
|
||||
|
@ -249,7 +257,7 @@ rcl_action_server_get_default_options(void);
|
|||
* Lock-Free | Yes
|
||||
* <i>[1] only if required when filling the request, avoided for fixed sizes</i>
|
||||
*
|
||||
* \param[in] action_server the action server that will take the request
|
||||
* \param[in] action_server handle to the action server that will take the request
|
||||
* \param[out] ros_goal_request a preallocated, zero-initialized, ROS goal request message
|
||||
* where the request is copied
|
||||
* \return `RCL_RET_OK` if the request was taken, or
|
||||
|
@ -267,7 +275,7 @@ rcl_action_take_goal_request(
|
|||
const rcl_action_server_t * action_server,
|
||||
void * ros_goal_request);
|
||||
|
||||
/// Send a response for a goal request to an action client using a rcl_action_server_t.
|
||||
/// Send a response for a goal request to an action client using an action server.
|
||||
/**
|
||||
* This is a non-blocking call.
|
||||
*
|
||||
|
@ -311,19 +319,27 @@ RCL_WARN_UNUSED
|
|||
rcl_ret_t
|
||||
rcl_action_send_goal_response(
|
||||
const rcl_action_server_t * action_server,
|
||||
const void * ros_goal_response);
|
||||
void * ros_goal_response);
|
||||
|
||||
/// Accept a new goal using a rcl_action_server_t.
|
||||
/// Accept a new goal using an action server.
|
||||
/**
|
||||
* This is a non-blocking call.
|
||||
*
|
||||
* Creates and returns a pointer to a goal handle for a newly accepted goal.
|
||||
* Creates and returns a new goal handle.
|
||||
* The action server starts tracking it internally.
|
||||
* If a failure occurs, `NULL` is returned and an error message is set.
|
||||
* Possible reasons for failure:
|
||||
* - action server is invalid
|
||||
* - goal info is invalid
|
||||
* - goal ID is already being tracked by the action server
|
||||
* - memory allocation failure
|
||||
*
|
||||
* This function should be called after receiving a new goal request with
|
||||
* rcl_action_take_goal_request() and before sending a response with
|
||||
* rcl_action_send_goal_response().
|
||||
*
|
||||
* After calling this function, the action server will start tracking the goal.
|
||||
*
|
||||
* Example usage:
|
||||
*
|
||||
* ```c
|
||||
|
@ -354,9 +370,8 @@ rcl_action_send_goal_response(
|
|||
* Uses Atomics | No
|
||||
* Lock-Free | Yes
|
||||
*
|
||||
* \param[in] action_server the action server that is accepting the goal
|
||||
* \param[in] action_server handle to the action server that is accepting the goal
|
||||
* \param[in] goal_info a message containing info about the goal being accepted
|
||||
* \param[in] error_msg_allocator a valid allocator or `NULL`
|
||||
* \return a pointer to a new goal handle representing the accepted goal, or
|
||||
* \return `NULL` if a failure occured.
|
||||
*/
|
||||
|
@ -364,11 +379,10 @@ RCL_ACTION_PUBLIC
|
|||
RCL_WARN_UNUSED
|
||||
rcl_action_goal_handle_t *
|
||||
rcl_action_accept_new_goal(
|
||||
const rcl_action_server_t * action_server,
|
||||
const rcl_action_goal_info_t * goal_info,
|
||||
rcl_allocator_t * error_msg_allocator);
|
||||
rcl_action_server_t * action_server,
|
||||
const rcl_action_goal_info_t * goal_info);
|
||||
|
||||
/// Publish a ROS feedback message for an active goal using a rcl_action_server_t.
|
||||
/// Publish a ROS feedback message for an active goal using an action server.
|
||||
/**
|
||||
* The caller is responsible for ensuring that the type of `ros_feedback`
|
||||
* and the type associate with the client (via the type support) match.
|
||||
|
@ -416,7 +430,7 @@ rcl_action_publish_feedback(
|
|||
const rcl_action_server_t * action_server,
|
||||
void * ros_feedback);
|
||||
|
||||
/// Get a status array message for accepted goals associated with a rcl_action_server_t.
|
||||
/// Get a status array message for accepted goals associated with an action server.
|
||||
/**
|
||||
* The provided `status_message` should be zero-initialized with
|
||||
* rcl_action_get_zero_initialized_goal_status_array() before calling this function.
|
||||
|
@ -443,9 +457,9 @@ rcl_action_get_goal_status_array(
|
|||
const rcl_action_server_t * action_server,
|
||||
rcl_action_goal_status_array_t * status_message);
|
||||
|
||||
/// Publish a status array message for accepted goals associated with a rcl_action_server_t.
|
||||
/// Publish a status array message for accepted goals associated with an action server.
|
||||
/**
|
||||
* This function acts like a ROS publisher and is potntially a blocking call.
|
||||
* This function acts like a ROS publisher and is potentially a blocking call.
|
||||
* \see rcl_publish()
|
||||
*
|
||||
* A status array message associated with the action server can be created with
|
||||
|
@ -471,9 +485,9 @@ RCL_WARN_UNUSED
|
|||
rcl_ret_t
|
||||
rcl_action_publish_status(
|
||||
const rcl_action_server_t * action_server,
|
||||
const rcl_action_goal_status_array_t * status_message);
|
||||
const void * status_message);
|
||||
|
||||
/// Take a pending result request using a rcl_action_server_t.
|
||||
/// Take a pending result request using an action server.
|
||||
/**
|
||||
* \todo TODO(jacobperron) blocking of take?
|
||||
*
|
||||
|
@ -511,7 +525,7 @@ rcl_action_take_result_request(
|
|||
const rcl_action_server_t * action_server,
|
||||
void * ros_result_request);
|
||||
|
||||
/// Send a result response using a rcl_action_server_t.
|
||||
/// Send a result response using an action server.
|
||||
/**
|
||||
* This is a non-blocking call.
|
||||
*
|
||||
|
@ -543,38 +557,54 @@ RCL_WARN_UNUSED
|
|||
rcl_ret_t
|
||||
rcl_action_send_result_response(
|
||||
const rcl_action_server_t * action_server,
|
||||
const void * ros_result_response);
|
||||
void * ros_result_response);
|
||||
|
||||
/// Clear all expired goals associated with a rcl_action_server_t.
|
||||
/// Expires goals associated with an action server.
|
||||
/**
|
||||
* A goal is 'expired' if it has been in a terminal state (has a result) for more
|
||||
* A goal is 'expired' if it has been in a terminal state (has a result) for longer
|
||||
* than some duration.
|
||||
* The timeout duration is set as part of the action server options.
|
||||
*
|
||||
* If a negative timeout value if provided, then goal results never expire (kept forever).
|
||||
* If a timeout of zero is set, then goal results are discarded immediately (ie. goal
|
||||
* results are discarded whenever this function is called).
|
||||
*
|
||||
* Expired goals are removed from the internal array of goal handles.
|
||||
* rcl_action_server_goal_exists() will return false for any goals that have expired.
|
||||
*
|
||||
* \attention If one or more goals are expired then a previously returned goal handle
|
||||
* array from rcl_action_server_get_goal_handles() becomes invalid.
|
||||
*
|
||||
* `num_expired` is an optional argument. If it is not `NULL`, then it is set to the
|
||||
* number of goals that were expired.
|
||||
*
|
||||
* <hr>
|
||||
* Attribute | Adherence
|
||||
* ------------------ | -------------
|
||||
* Allocates Memory | No
|
||||
* Allocates Memory | Maybe[1]
|
||||
* Thread-Safe | No
|
||||
* Uses Atomics | No
|
||||
* Lock-Free | Yes
|
||||
* <i>[1] if one or more goals expires, then the internal goal handle array may be
|
||||
* resized or deallocated</i>
|
||||
*
|
||||
* \param[in] action_server handle to the action server from which expired goals
|
||||
* will be cleared.
|
||||
* \param[out] num_expired the number of expired goals cleared. If `NULL` then the
|
||||
* number is not set.
|
||||
* \param[out] num_expired the number of expired goals, or set to `NULL` if unused
|
||||
* \return `RCL_RET_OK` if the response was sent successfully, or
|
||||
* \return `RCL_RET_ACTION_SERVER_INVALID` if the action server is invalid, or
|
||||
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||
*/
|
||||
RCL_ACTION_PUBLIC
|
||||
RCL_WARN_UNUSED
|
||||
rcl_ret_t
|
||||
rcl_action_clear_expired_goals(
|
||||
rcl_action_expire_goals(
|
||||
const rcl_action_server_t * action_server,
|
||||
uint32_t * num_expired);
|
||||
size_t * num_expired);
|
||||
|
||||
/// Take a pending cancel request using a rcl_action_server_t.
|
||||
/// Take a pending cancel request using an action server.
|
||||
/**
|
||||
* \todo TODO(jacobperron) blocking of take?
|
||||
*
|
||||
|
@ -615,7 +645,7 @@ rcl_action_take_cancel_request(
|
|||
const rcl_action_server_t * action_server,
|
||||
void * ros_cancel_request);
|
||||
|
||||
/// Process a cancel request using a rcl_action_server_t.
|
||||
/// Process a cancel request using an action server.
|
||||
/**
|
||||
* This is a non-blocking call.
|
||||
*
|
||||
|
@ -641,7 +671,7 @@ rcl_action_take_cancel_request(
|
|||
*
|
||||
* \param[in] action_server handle to the action server that will process the cancel request
|
||||
* \param[in] cancel_request a C-typed ROS cancel request to process
|
||||
* \param[out] cancel_reponse a preallocated, zero-initialized, C-typed ROS cancel response
|
||||
* \param[out] cancel_reponse a zero-initialized cancel response struct
|
||||
* where the response is copied
|
||||
* \return `RCL_RET_OK` if the response was sent successfully, or
|
||||
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||
|
@ -659,7 +689,7 @@ rcl_action_process_cancel_request(
|
|||
const rcl_action_cancel_request_t * cancel_request,
|
||||
rcl_action_cancel_response_t * cancel_response);
|
||||
|
||||
/// Send a cancel response using a rcl action server.
|
||||
/// Send a cancel response using an action server.
|
||||
/**
|
||||
* This is a non-blocking call.
|
||||
*
|
||||
|
@ -671,7 +701,7 @@ rcl_action_process_cancel_request(
|
|||
* Uses Atomics | No
|
||||
* Lock-Free | Yes
|
||||
*
|
||||
* \param[in] action_server the 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] ros_cancel_response a ROS cancel response to send
|
||||
* \return `RCL_RET_OK` if the request was taken, or
|
||||
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||
|
@ -683,14 +713,14 @@ RCL_WARN_UNUSED
|
|||
rcl_ret_t
|
||||
rcl_action_send_cancel_response(
|
||||
const rcl_action_server_t * action_server,
|
||||
const void * ros_cancel_response);
|
||||
void * ros_cancel_response);
|
||||
|
||||
/// Get the name of the action for a rcl_action_server_t.
|
||||
/// Get the action name for an action server.
|
||||
/**
|
||||
* This function returns the action server's internal topic name string.
|
||||
* This function can fail, and therefore return `NULL`, if the:
|
||||
* - action server is `NULL`
|
||||
* - action server is invalid (never called init, called fini, or invalid)
|
||||
* - action server is invalid (e.g. never called init or called fini)
|
||||
*
|
||||
* The returned string is only valid as long as the action server is valid.
|
||||
* The value of the string may change if the topic name changes, and therefore
|
||||
|
@ -704,20 +734,21 @@ rcl_action_send_cancel_response(
|
|||
* Uses Atomics | No
|
||||
* Lock-Free | Yes
|
||||
*
|
||||
* \param[in] action_server the pointer to the action server
|
||||
* \return name string if successful, otherwise `NULL`
|
||||
* \param[in] action_server pointer to the action server
|
||||
* \return name string if successful, or
|
||||
* \return `NULL` otherwise.
|
||||
*/
|
||||
RCL_ACTION_PUBLIC
|
||||
RCL_WARN_UNUSED
|
||||
const char *
|
||||
rcl_action_server_get_action_name(const rcl_action_server_t * action_server);
|
||||
|
||||
/// Return the rcl_action_server_options_t for a rcl_action_server_t.
|
||||
/// Return the rcl_action_server_options_t for an action server.
|
||||
/**
|
||||
* This function returns the action server's internal options struct.
|
||||
* This function can fail, and therefore return `NULL`, if the:
|
||||
* - action server is `NULL`
|
||||
* - action server is invalid (never called init, called fini, or invalid)
|
||||
* - action server is invalid (e.g. never called init or called fini)
|
||||
*
|
||||
* The returned struct is only valid as long as the action server is valid.
|
||||
* The values in the struct may change if the action server's options change,
|
||||
|
@ -731,27 +762,23 @@ rcl_action_server_get_action_name(const rcl_action_server_t * action_server);
|
|||
* Uses Atomics | No
|
||||
* Lock-Free | Yes
|
||||
*
|
||||
* \param[in] action_server pointer to the action server
|
||||
* \return options struct if successful, otherwise `NULL`
|
||||
* \param[in] action_server handle to the action server
|
||||
* \return options struct if successful, or
|
||||
* \return `NULL` otherwise.
|
||||
*/
|
||||
RCL_ACTION_PUBLIC
|
||||
RCL_WARN_UNUSED
|
||||
const rcl_action_server_options_t *
|
||||
rcl_action_server_get_options(const rcl_action_server_t * action_server);
|
||||
|
||||
/// Return the goal handles for all active or terminated goals.
|
||||
/// Get the goal handles for all goals an action server is tracking.
|
||||
/**
|
||||
* A pointer to the internally held array of goal handle structs is returned
|
||||
* A pointer to the internally held array of pointers to goal handle structs is returned
|
||||
* along with the number of items in the array.
|
||||
* Goals that have terminated, successfully responded to a client with a
|
||||
* result, and have expired (timed out) are not present in the array.
|
||||
*
|
||||
* This function can fail, and therefore return `NULL`, if the:
|
||||
* - action server is `NULL`
|
||||
* - action server is invalid (never called init, called fini, or invalid)
|
||||
*
|
||||
* The returned handle is made invalid if the action server is finalized or if
|
||||
* rcl_shutdown() is called.
|
||||
* The returned handle is made invalid if the action server is finalized, if
|
||||
* rcl_shutdown() is called, or if rcl_action_expire_goals() is called and one or more
|
||||
* goals are expired.
|
||||
* The returned handle is not guaranteed to be valid for the life time of the
|
||||
* action server as it may be finalized and recreated itself.
|
||||
* Therefore, it is recommended to get the handle from the action server using
|
||||
|
@ -766,24 +793,53 @@ rcl_action_server_get_options(const rcl_action_server_t * action_server);
|
|||
* Uses Atomics | No
|
||||
* Lock-Free | Yes
|
||||
*
|
||||
* \param[in] action_server pointer to the rcl action server
|
||||
* \param[in] action_server handle to the action server
|
||||
* \param[out] goal_handles is set to the array of pointers to goal handles if successful.
|
||||
* \param[out] num_goals is set to the number of goals in the returned array if successful,
|
||||
* not set otherwise.
|
||||
* \return pointer to an array goal handles if successful, otherwise `NULL`
|
||||
* \return `RCL_RET_OK` if successful, or
|
||||
* \return `RCL_RET_ACTION_SERVER_INVALID` if the action server is invalid, or
|
||||
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||
*/
|
||||
RCL_ACTION_PUBLIC
|
||||
RCL_WARN_UNUSED
|
||||
const rcl_action_goal_handle_t *
|
||||
rcl_ret_t
|
||||
rcl_action_server_get_goal_handles(
|
||||
const rcl_action_server_t * action_server,
|
||||
uint32_t * num_goals);
|
||||
rcl_action_goal_handle_t *** goal_handles,
|
||||
size_t * num_goals);
|
||||
|
||||
/// Check that the action server is valid.
|
||||
/// Check if a goal is already being tracked by an action server.
|
||||
/**
|
||||
* The bool returned is `false` if `action_server` is invalid.
|
||||
* The bool returned is `true` otherwise.
|
||||
* In the case where `false` is to be returned, an
|
||||
* error message is set.
|
||||
* Checks whether or not a goal is being tracked in the internal goal array.
|
||||
* The goal state has no effect on the return value.
|
||||
*
|
||||
* <hr>
|
||||
* Attribute | Adherence
|
||||
* ------------------ | -------------
|
||||
* Allocates Memory | No
|
||||
* Thread-Safe | No
|
||||
* Uses Atomics | No
|
||||
* Lock-Free | Yes
|
||||
*
|
||||
* \param[in] action_server handle to the action server
|
||||
* \param[in] goal_info handle to a struct containing the goal ID to check for
|
||||
* \return `true` if `action_server` is currently tracking a goal with the provided goal ID, or
|
||||
* \return `false` otherwise.
|
||||
*/
|
||||
RCL_ACTION_PUBLIC
|
||||
RCL_WARN_UNUSED
|
||||
bool
|
||||
rcl_action_server_goal_exists(
|
||||
const rcl_action_server_t * action_server,
|
||||
const rcl_action_goal_info_t * goal_info);
|
||||
|
||||
/// Check if an action server is valid.
|
||||
/**
|
||||
* In the case where `false` is returned (ie. the action server is invalid),
|
||||
* an error message is set.
|
||||
*
|
||||
* This function cannot fail.
|
||||
*
|
||||
* <hr>
|
||||
|
@ -794,15 +850,14 @@ rcl_action_server_get_goal_handles(
|
|||
* Uses Atomics | No
|
||||
* Lock-Free | Yes
|
||||
*
|
||||
* \param[in] action_server pointer to the rcl action server
|
||||
* \param[in] error_msg_allocator a valid allocator or `NULL`
|
||||
* \return `true` if `action_server` is valid, otherwise `false`
|
||||
* \param[in] action_server handle to the action server
|
||||
* \return `true` if `action_server` is valid, or
|
||||
* \return `false` otherwise.
|
||||
*/
|
||||
RCL_ACTION_PUBLIC
|
||||
RCL_WARN_UNUSED
|
||||
bool
|
||||
rcl_action_server_is_valid(
|
||||
const rcl_action_server_t * action_server,
|
||||
rcl_allocator_t * error_msg_allocator);
|
||||
rcl_action_server_is_valid(const rcl_action_server_t * action_server);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
|
|
@ -82,7 +82,7 @@ RCL_WARN_UNUSED
|
|||
rcl_ret_t
|
||||
rcl_action_goal_handle_init(
|
||||
rcl_action_goal_handle_t * goal_handle,
|
||||
rcl_action_goal_info_t * goal_info,
|
||||
const rcl_action_goal_info_t * goal_info,
|
||||
rcl_allocator_t allocator);
|
||||
|
||||
/// Finalize a rcl_action_goal_handle_t.
|
||||
|
|
|
@ -53,6 +53,12 @@ extern "C"
|
|||
/// Action invalid event return code.
|
||||
#define RCL_RET_ACTION_GOAL_EVENT_INVALID 2301
|
||||
|
||||
// TODO(jacobperron): Move these to a common place for UUIDs
|
||||
#define UUID_SIZE 16
|
||||
#define uuidcmp(uuid0, uuid1) (0 == memcmp(uuid0, uuid1, UUID_SIZE))
|
||||
#define zerouuid (uint8_t[UUID_SIZE]) {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
|
||||
#define uuidcmpzero(uuid) uuidcmp(uuid, zerouuid)
|
||||
|
||||
// Forward declare
|
||||
typedef struct rcl_action_server_t rcl_action_server_t;
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue