Add ROS Action Documentation/References

This commit is contained in:
John Ring 2022-02-01 13:50:16 +01:00
parent 84220120e5
commit 45556ab136
4 changed files with 281 additions and 10 deletions

View File

@ -98,9 +98,12 @@
* Convert ROS MSG and SRV files to IDL files * Convert ROS MSG and SRV files to IDL files
ros2 run rosidl_adapter msg2idl.py *.msg ros2 run rosidl_adapter msg2idl.py *.msg
ros2 run rosidl_adapter srv2idl.py *.srv ros2 run rosidl_adapter srv2idl.py *.srv
ros2 run rosidl_adapter action2idl.py *.action
NOTE: According to a PR, you can also do 'rosidl translate --to idl path/to/my.action'
* The publication_handle of the DDS Specification (e.g. the one returned in the Sample Info) is an implementation specific ID that can identify local and remote DDS Entities LOCALY. * The publication_handle of the DDS Specification (e.g. the one returned in the Sample Info) is an implementation specific ID that can identify local and remote DDS Entities LOCALY.
* Testbench did not catch Bug, where the Pub ACKNACK was sent to as Sub ACKNACK (ACKNACK Destinations were flipped). Extend testbench to catch this case. * Testbench did not catch Bug, where the Pub ACKNACK was sent to as Sub ACKNACK (ACKNACK Destinations were flipped). Extend testbench to catch this case.
* Testbench did not catch rtps_writer not sending HEARTBEATS if PUSH_MODE=FALSE & DURABILITY=TRANSIENT_LOCAL * Testbench did not catch rtps_writer not sending HEARTBEATS if PUSH_MODE=FALSE & DURABILITY=TRANSIENT_LOCAL
* DATA sent before first HEARTBEAT: https://github.com/ros2/rmw_cyclonedds/issues/367
* Fast-RTPS does not follow DDSI-RTPS Specification * Fast-RTPS does not follow DDSI-RTPS Specification
- Open Github Issue - Open Github Issue
@ -416,6 +419,14 @@ DESIGN DECISIONS
This means that a Reliable RTPS Writer in PUSH_MODE = FALSE cannot communicate with Best Effort Readers. This means that a Reliable RTPS Writer in PUSH_MODE = FALSE cannot communicate with Best Effort Readers.
Historical Data is also only sent out on request (But NACKed in the HC, until the remote Reader ACKs them). Historical Data is also only sent out on request (But NACKed in the HC, until the remote Reader ACKs them).
* Where as the DDS Writer/Reader are flexible in the handling of variable sized Payloads - they write the
payload in multiple memory slots, effectively eating away from the MAX_SAMPLES limit, since there are
only MAX_SAMPLES memory slots avialable - the decoding in TYPENAME_interface requires and explicitly
enforces absolute maximums for all Type members. Those upper bounds are either explicitly defined in
the IDL Type definition file, or implicit system default upper bound defined in a package. Encoding
does enforce those limits implicitly, since it encodes the memory/registers that are physically limited
to those specified upper bounds during static generation.
BRAINSTORMING BRAINSTORMING
------------- -------------

View File

@ -2,7 +2,7 @@
int32 order int32 order
--- ---
# Result # Result
int32[] sequence int32[] seq
--- ---
# Feedback # Feedback
int32[] sequence int32[] seq

View File

@ -0,0 +1,24 @@
// generated from rosidl_adapter/resource/action.idl.em
// with input from example_interfaces/action/Fibonacci.action
// generated code does not contain a copyright notice
module example_interfaces {
module action {
@verbatim (language="comment", text=
"Goal")
struct Fibonacci_Goal {
int32 order;
};
@verbatim (language="comment", text=
"Result")
struct Fibonacci_Result {
sequence<int32> seq;
};
@verbatim (language="comment", text=
"Feedback")
struct Fibonacci_Feedback {
sequence<int32> seq;
};
};
};

View File

@ -94,6 +94,234 @@ rcl_timer_reset (timer) [RET]
rcl_timer_get_allocator (timer) [ALLOCATOR] rcl_timer_get_allocator (timer) [ALLOCATOR]
rcl_timer_get_guard_condition (timer) [GUARD CONDITION] rcl_timer_get_guard_condition (timer) [GUARD CONDITION]
rcl_action_get_zero_initialized_client() [ACTION_CLIENT]
rcl_action_client_init(action_client, node, type_support, action_name, action_client_options) [RET]
* After calling this function on a rcl_action_client_t, it can be used to send
* goals of the given type to the given topic using rcl_action_send_goal_request().
* If a goal request is sent to a (possibly remote) server and if the server
* sends a response, the client can access the response with
* rcl_take_goal_response() once the response is available.
*
* After a goal request has been accepted, the rcl_action_client_t associated with the
* goal can perform the following operations:
*
* - Send a request for the result with rcl_action_send_result_request().
* If the server sends a response when the goal terminates, the result can be accessed
* with rcl_action_take_result_response(), once the response is available.
* - Send a cancel request for the goal with rcl_action_send_cancel_request().
* If the server sends a response to a cancel request, the client can access the
* response with rcl_action_take_cancel_response() once the response is available.
* - Take feedback about the goal with rcl_action_take_feedback().
*
* A rcl_action_client_t can be used to access the current status of all accepted goals
* communicated by the action server with rcl_action_take_status().
rcl_action_client_fini(action_client, node) [RET]
rcl_action_client_get_default_options() [ACTION_CLIENT_OPTIONS]
{rmw_qos_profile_services_default, rmw_qos_profile_services_default, rmw_qos_profile_services_default, rmw_qos_profile_default, rcl_action_qos_profile_status_default, rcl_get_default_allocator()}
rcl_action_server_is_available(node, action_client, is_available^) [RET]
rcl_action_send_goal_request(action_client, ros_goal_request, sequence_number^) [RET]
rcl_action_take_goal_response(action_client, response_header^, ros_goal_response^) [RET]
rcl_action_take_feedback(action_client, ros_feedback^) [RET]
rcl_action_take_status(action_client, ros_status_array^) [RET]
rcl_action_send_result_request(action_client, ros_result_request, sequence_number^) [RET]
rcl_action_take_result_response(action_client, response_header^, ros_result^) [RET]
rcl_action_send_cancel_request(action_client, ros_cancel_request, sequence_number^) [RET]
* The following cancel policy applies based on the goal ID and the timestamp provided
* by the `ros_cancel_request` message:
*
* - If the goal ID is zero and timestamp is zero, cancel all goals.
* - If the goal ID is zero and timestamp is not zero, cancel all goals accepted
* at or before the timestamp.
* - If the goal ID is not zero and timestamp is zero, cancel the goal with the
* given ID regardless of the time it was accepted.
* - If the goal ID is not zero and timestamp is not zero, cancel the goal with the
* given ID and all goals accepted at or before the timestamp.
rcl_action_take_cancel_response(action_client, response_header^, ros_cancel_response^) [RET]
rcl_action_client_get_action_name(action_client) [ACTION_NAME]
rcl_action_client_get_options(action_client) [ACTION_CLIENT_OPTIONS]
rcl_action_client_is_valid (action_client) [IS_VALID]
rcl_action_get_zero_initialized_server() [ACTION_SERVER]
rcl_action_server_init(action_server, node, clock, type_support, action_name, action_server_options) [RET]
* 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()
* and take cancel requests with rcl_action_take_cancel_request().
* It can also send a result for a request using rcl_action_send_result() or
* rcl_action_send_cancel_response().
*
* After accepting a goal with rcl_action_take_goal_request(), the action server can
* be used to send feedback with rcl_action_publish_feedback() and send status
* messages with rcl_action_publish_status().
rcl_action_server_fini(action_server, node) [RET]
rcl_action_server_get_default_options() [ACTION_SERVER_OPTIONS]
* The defaults are:
*
* - goal_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 = RCUTILS_S_TO_NS(15 * 60); // 15 minutes
rcl_action_take_goal_request(action_server, request_header^, ros_goal_request^) [RET]
rcl_action_send_goal_response(action_server, response_header, ros_goal_response) [RET]
rcl_action_accept_new_goal(action_server, goal_info) [ACTION_GOAL_HANDLE]
* 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
rcl_action_publish_feedback(action_server, ros_feedback) [RET]
rcl_action_get_goal_status_array(action_server, action_goal_status_array)
rcl_action_publish_status(action_server, status_message) [RET]
rcl_action_take_result_request(action_server, request_header^, ros_result_request^) [RET]
rcl_action_send_result_response(action_server, response_header, ros_result_response) [RET]
rcl_action_expire_goals(action_server, expired_goals^, expired_goals_capacity, num_expired^) [RET]
* 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.
*
* `expired_goals`, `expired_goals_capacity` and `num_expired` are optional arguments.
* If set to (`NULL`, 0u, `NULL`) then they are not used.
* To use them allocate an array with size equal to the maximum number of goals that you want to
* expire.
* Pass the number of goals the array can hold in as `expired_goals_capacity`.
* This function will set `num_expired` to the number of goals that were expired.
rcl_action_notify_goal_done(action_server) [RET]
* Notifies action server that a goal handle reached a terminal state.
rcl_action_take_cancel_request(action_server, request_header^, ros_cancel_request^) [RET]
rcl_action_process_cancel_request(action_server, cancel_request, cancel_response^) [RET]
* This function will compute a list of goals that a cancelation request is attempting to cancel.
* It does not change the state of any goal.
* The following cancel policy applies based on the goal ID and the timestamp
* contained in the cancel request:
*
* - If the goal ID is zero and timestamp is zero, cancel all goals.
* - If the goal ID is zero and timestamp is not zero, cancel all goals accepted
* at or before the timestamp.
* - If the goal ID is not zero and timestamp is zero, cancel the goal with the
* given ID regardless of the time it was accepted.
* - If the goal ID is not zero and timestamp is not zero, cancel the goal with the
* given ID and all goals accepted at or before the timestamp.
rcl_action_send_cancel_response(action_server, response_header, ros_cancel_response) [RET]
rcl_action_server_get_action_name(action_server) [ACTION_NAME]
rcl_action_server_get_options(action_server) [ACTION_SERVER_OPTIONS]
rcl_action_server_get_goal_handles(action_server, goal_handles^, num_goals^) [RET]
* A pointer to the internally held array of pointers to goal handle structs is returned
* along with the number of items in the array.
*
* 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
* this function each time it is needed and avoid use of the handle
* concurrently with functions that might change it.
rcl_action_server_goal_exists(action_server, goal_info) [BOOL]
* Checks whether or not a goal is being tracked in the internal goal array.
* The goal state has no effect on the return value.
rcl_action_server_is_valid(action_server) [BOOL]
* In the case where `false` is returned (ie. the action server is invalid),
* an error message is set.
rcl_action_server_is_valid_except_context(action_server) [BOOL]
rcl_action_get_zero_initialized_goal_handle() [GOAL_HANDLE]
rcl_action_goal_handle_init(goal_handle^, goal_info, allocator) [RET]
* After calling this function on a rcl_action_goal_handle_t, it can be used to update the
* goals state with rcl_action_update_goal_state().
* It can also be used to query the state of the goal with
* rcl_action_goal_handle_get_message() and rcl_action_goal_handle_is_active().
* Goal information can be accessed with rcl_action_goal_handle_get_message() and
* rcl_action_goal_handle_get_info().
*
* Goal handles are typically initialized and finalized by action servers.
* I.e. The allocator should be provided by the action server.
* Goal handles are created with rcl_action_accept_new_goal() and destroyed with
* rcl_action_clear_expired_goals() or rcl_action_server_fini().
rcl_action_goal_handle_fini(goal_handle) [RET]
rcl_action_update_goal_state(goal_handle, goal_event) [RET]
* Update a goal state with a rcl_action_goal_handle_t and an event.
rcl_action_goal_handle_get_info(goal_handle, goal_info^) [RET]
rcl_action_goal_handle_get_status(goal_handle, goal_state^) [RET]
rcl_action_goal_handle_is_active(goal_handle) [BOOL]
* \return `true` if the goal is in one of the following states: ACCEPTED, EXECUTING, or CANCELING, or
* \return `false` if the goal handle pointer is invalid, or
* \return `false` otherwise
rcl_action_goal_handle_is_cancelable(goal_handle) [BOOL]
* \return `true` if the goal can be transitioned to CANCELING from its current state, or
* \return `false` if the goal handle pointer is invalid, or
* \return `false` otherwise
rcl_action_goal_handle_is_valid(goal_handle) [BOOL]
* A goal handle is invalid if:
* - the implementation is `NULL` (rcl_action_goal_handle_init() not called or failed)
* - rcl_shutdown() has been called since the goal handle has been initialized
* - the goal handle has been finalized with rcl_action_goal_handle_fini()
rcl_action_transition_goal_state(goal_state, goal_event) [GOAL_STATE]
* Given a goal state and a goal event, return the next state.
rcl_action_get_client_names_and_types_by_node(node, allocator, node_name, node_namespace, action_names_and_types^) [RET]
rcl_action_get_server_names_and_types_by_node(node, allocator, node_name, node_namespace, action_names_and_types^) [RET]
rcl_action_get_names_and_types(node, allocator, action_names_and_types^) [RET]
rcl_action_get_goal_service_name(action_name, allocator, goal_service_name^) [RET]
rcl_action_get_cancel_service_name(action_name, allocator, cancel_service_name^) [RET]
rcl_action_get_result_service_name(action_name, allocator, result_service_name^) [RET]
rcl_action_get_feedback_topic_name(action_name, allocator, feedback_topic_name^) [RET]
rcl_action_get_status_topic_name(action_name, allocator, status_topic_name^) [RET]
rcl_action_wait_set_add_action_client(wait_set, action_client, client_index^, subscription_index^) [RET]
rcl_action_wait_set_add_action_server(wait_set, action_server, service_index^) [RET]
rcl_action_client_wait_set_get_num_entities(action_client, num_subscriptions^, num_guard_conditions^, num_timers^, num_clients^, num_services^) [RET]
rcl_action_server_wait_set_get_num_entities(action_server, num_subscriptions^, num_guard_conditions^, num_timers^, num_clients^, num_services^) [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^) [RET]
rcl_action_server_wait_set_get_entities_ready(wait_set, action_client, is_goal_request_ready^, is_cancel_request_ready^, is_result_request_ready^, is_goal_expired^) [RET]
ACTION_CLIENT_OPTIONS
---------------------
goal_service_qos, result_service_qos, cancel_service_qos, feedback_topic_qos, status_topic_qos, rcl_allocator
ACTION_SERVER_OPTIONS
---------------------
goal_service_qos, result_service_qos, cancel_service_qos, feedback_topic_qos, status_topic_qos, rcl_allocator, result_timeout
RESPONSE_HEADER
---------------
request_id
REQUEST_HEADER
--------------
request_id
GOAL_EVENT
----------
GOAL_EVENT_EXECUTE = 0,GOAL_EVENT_CANCEL_GOAL,GOAL_EVENT_SUCCEED,GOAL_EVENT_ABORT,GOAL_EVENT_CANCELED,GOAL_EVENT_NUM_EVENTS
GOAL_HANDLE
-----------
goal_info, goal_state, allocator
GOAL_STATE
----------
rcl_interfaces/action_msgs/GoalStatus {UNKNOWN, ACCEPTED, EXECUTING, CANCELING, SUCCEEDED, CANCELED, ABOTED}
RMW RMW
=== ===
@ -169,19 +397,19 @@ OPTIONS
------- -------
instance_id, implementation_identifier, domain_id, security_options, localhost_only, enclave, allocator, impl instance_id, implementation_identifier, domain_id, security_options, localhost_only, enclave, allocator, impl
SECURITY OPTIONS SECURITY_OPTIONS
---------------- ----------------
enforce_security, security_root_path enforce_security, security_root_path
GUARD CONDITION GUARD_CONDITION
--------------- ---------------
implementation_identifier, data, context implementation_identifier, data, context
SERVICE INFO SERVICE_INFO
------------ ------------
source_timestamp, received_timestamp, request_id source_timestamp, received_timestamp, request_id
REQUEST ID REQUEST_ID
---------- ----------
writer_guid, sequence_number writer_guid, sequence_number
@ -221,12 +449,20 @@ ACTION
====== ======
http://design.ros2.org/articles/actions.html http://design.ros2.org/articles/actions.html
REF: https://github.com/ros2/rclcpp.git [/rlcpp_action] REF: https://github.com/ros2/rclcpp.git [/rlcpp_action]
REF: https://github.com/ros2/rosidl.git [rosidl_parser/definition.py]
SERVICE: '<ACTIONNAME>/_action/send_goal' [1st section of .action Definition] SERVICE: '<ACTIONNAME>/_action/send_goal'
SERVICE: '<ACTIONNAME>/_action/cancel_goal' [rcl_interfaces/action_msgs/CancelGoal.srv] REQUEST: [unique_identifier_msgs/UUID goal_id, 1st section of .action Definition]
SERVICE: '<ACTIONNAME>/_action/get_result' [2nd section of .action Definition] RESPONSE: [boolean accepted, builtin_interfaces/Time stamp]
TOPIC: '<ACTIONNAME>/_action/feedback' [3rd section of .action Definition] SERVICE: '<ACTIONNAME>/_action/cancel_goal'
rcl_interfaces/action_msgs/CancelGoal.srv
SERVICE: '<ACTIONNAME>/_action/get_result'
REQUEST: [unique_identifier_msgs/UUID goal_id]
RESPONSE: [int8 status, 2nd section of .action Definition]
TOPIC: '<ACTIONNAME>/_action/feedback'
[unique_identifier_msgs/UUID goal_id, 3rd section of .action Definition]
TOPIC: '<ACTIONNAME>/_action/status' TOPIC: '<ACTIONNAME>/_action/status'
rcl_interfaces/action_msgs/GoalStatusArray.msg
PARAMETER PARAMETER