Add rcl_action package and headers (#307)
* Create rcl_action package with proposed headers for: - Action client - Action server - Goal handle - Goal state machine - Types * Add rcl_action.h and Doxyfile * Add functions for adding action clients and action servers to a wait set * Add default QoS profile for status topic and document default options for action clients/servers * Include all headers in a .c file for testing compilation
This commit is contained in:
parent
5e3d4be720
commit
451bf4a1a4
12 changed files with 2832 additions and 0 deletions
110
rcl_action/CMakeLists.txt
Normal file
110
rcl_action/CMakeLists.txt
Normal file
|
@ -0,0 +1,110 @@
|
||||||
|
cmake_minimum_required(VERSION 3.5)
|
||||||
|
|
||||||
|
project(rcl_action)
|
||||||
|
|
||||||
|
find_package(ament_cmake_ros REQUIRED)
|
||||||
|
|
||||||
|
find_package(action_msgs REQUIRED)
|
||||||
|
find_package(rcl REQUIRED)
|
||||||
|
find_package(rcutils REQUIRED)
|
||||||
|
# find_package(rmw REQUIRED)
|
||||||
|
|
||||||
|
include_directories(
|
||||||
|
include
|
||||||
|
${action_msgs_INCLUDE_DIRS}
|
||||||
|
${rcl_INCLUDE_DIRS}
|
||||||
|
${rcutils_INCLUDE_DIRS}
|
||||||
|
)
|
||||||
|
|
||||||
|
# Default to C11
|
||||||
|
if(NOT CMAKE_C_STANDARD)
|
||||||
|
set(CMAKE_C_STANDARD 11)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# Default to C++14
|
||||||
|
if(NOT CMAKE_CXX_STANDARD)
|
||||||
|
set(CMAKE_CXX_STANDARD 14)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
|
||||||
|
add_compile_options(-Wall -Wextra -Wpedantic)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
add_executable(test_compile_headers
|
||||||
|
src/test_compile_headers.c
|
||||||
|
)
|
||||||
|
|
||||||
|
# set(rcl_action_sources
|
||||||
|
# src/action_server.c
|
||||||
|
# src/action_client.c
|
||||||
|
# src/action_goal.c
|
||||||
|
# src/transition_map.c
|
||||||
|
# )
|
||||||
|
# set_source_files_properties(
|
||||||
|
# ${rcl_action_sources}
|
||||||
|
# PROPERTIES language "C"
|
||||||
|
# )
|
||||||
|
|
||||||
|
### C-Library depending only on RCL
|
||||||
|
# add_library(
|
||||||
|
# ${PROJECT_NAME}
|
||||||
|
# ${rcl_action_sources}
|
||||||
|
# )
|
||||||
|
|
||||||
|
# specific order: dependents before dependencies
|
||||||
|
# ament_target_dependencies(${PROJECT_NAME}
|
||||||
|
# "rcl"
|
||||||
|
# "action_msgs"
|
||||||
|
# "rosidl_generator_c"
|
||||||
|
# "rcutils"
|
||||||
|
# )
|
||||||
|
|
||||||
|
# Causes the visibility macros to use dllexport rather than dllimport,
|
||||||
|
# which is appropriate when building the dll but not consuming it.
|
||||||
|
# target_compile_definitions(${PROJECT_NAME} PRIVATE "RCL_ACTION_BUILDING_DLL")
|
||||||
|
|
||||||
|
# install(TARGETS ${PROJECT_NAME}
|
||||||
|
# ARCHIVE DESTINATION lib
|
||||||
|
# LIBRARY DESTINATION lib
|
||||||
|
# RUNTIME DESTINATION bin
|
||||||
|
# )
|
||||||
|
|
||||||
|
if(BUILD_TESTING)
|
||||||
|
find_package(ament_cmake_gtest REQUIRED)
|
||||||
|
find_package(ament_lint_auto REQUIRED)
|
||||||
|
ament_lint_auto_find_test_dependencies()
|
||||||
|
|
||||||
|
# Gtests
|
||||||
|
# ament_add_gtest(test_action_server
|
||||||
|
# test/test_action_server.cpp
|
||||||
|
# )
|
||||||
|
# if(TARGET test_action_server)
|
||||||
|
# target_include_directories(test_action_server PUBLIC
|
||||||
|
# ${rcl_INCLUDE_DIRS}
|
||||||
|
# )
|
||||||
|
# target_link_libraries(test_action_server ${PROJECT_NAME})
|
||||||
|
# endif()
|
||||||
|
# ament_add_gtest(test_action_client
|
||||||
|
# test/test_action_client.cpp
|
||||||
|
# )
|
||||||
|
# if(TARGET test_action_client)
|
||||||
|
# target_include_directories(test_action_client PUBLIC
|
||||||
|
# ${rcl_INCLUDE_DIRS}
|
||||||
|
# )
|
||||||
|
# target_link_libraries(test_action_client ${PROJECT_NAME})
|
||||||
|
# endif()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# specific order: dependents before dependencies
|
||||||
|
ament_export_include_directories(include)
|
||||||
|
# ament_export_libraries(${PROJECT_NAME})
|
||||||
|
ament_export_dependencies(ament_cmake)
|
||||||
|
ament_export_dependencies(rcl)
|
||||||
|
# ament_export_dependencies(action_msgs)
|
||||||
|
ament_export_dependencies(rcutils)
|
||||||
|
ament_package()
|
||||||
|
|
||||||
|
install(
|
||||||
|
DIRECTORY include/
|
||||||
|
DESTINATION include
|
||||||
|
)
|
32
rcl_action/Doxyfile
Normal file
32
rcl_action/Doxyfile
Normal file
|
@ -0,0 +1,32 @@
|
||||||
|
# All settings not listed here will use the Doxygen default values.
|
||||||
|
|
||||||
|
PROJECT_NAME = "rcl_action"
|
||||||
|
PROJECT_NUMBER = master
|
||||||
|
PROJECT_BRIEF = "C API providing common functionality for ROS actions."
|
||||||
|
|
||||||
|
INPUT = ./include
|
||||||
|
RECURSIVE = YES
|
||||||
|
OUTPUT_DIRECTORY = doc_output
|
||||||
|
|
||||||
|
EXTRACT_ALL = YES
|
||||||
|
SORT_MEMBER_DOCS = NO
|
||||||
|
|
||||||
|
GENERATE_LATEX = NO
|
||||||
|
|
||||||
|
ENABLE_PREPROCESSING = YES
|
||||||
|
MACRO_EXPANSION = YES
|
||||||
|
EXPAND_ONLY_PREDEF = YES
|
||||||
|
PREDEFINED += RCL_PUBLIC=
|
||||||
|
PREDEFINED += RCL_WARN_UNUSED=
|
||||||
|
|
||||||
|
# Uncomment to generate internal documentation.
|
||||||
|
ENABLED_SECTIONS = INTERNAL
|
||||||
|
INPUT += ./src/rcl/arguments.c
|
||||||
|
|
||||||
|
# Tag files that do not exist will produce a warning and cross-project linking will not work.
|
||||||
|
TAGFILES += "../../../../doxygen_tag_files/cppreference-doxygen-web.tag.xml=http://en.cppreference.com/w/"
|
||||||
|
# Consider changing "latest" to the version you want to reference (e.g. beta1 or 1.0.0)
|
||||||
|
TAGFILES += "../../../../doxygen_tag_files/rmw.tag=http://docs.ros2.org/latest/api/rmw/"
|
||||||
|
TAGFILES += "../../../../doxygen_tag_files/rcutils.tag=http://docs.ros2.org/latest/api/rcutils/"
|
||||||
|
# Uncomment to generate tag files for cross-project linking.
|
||||||
|
#GENERATE_TAGFILE = "../../../../doxygen_tag_files/rcl.tag"
|
693
rcl_action/include/rcl_action/action_client.h
Normal file
693
rcl_action/include/rcl_action/action_client.h
Normal file
|
@ -0,0 +1,693 @@
|
||||||
|
// Copyright 2018 Open Source Robotics Foundation, Inc.
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#ifndef RCL_ACTION__ACTION_CLIENT_H_
|
||||||
|
#define RCL_ACTION__ACTION_CLIENT_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// TODO(jacobperron): replace type support typedef with one defined in rosdl_generator_c
|
||||||
|
// #include "rosidl_generator_c/action_type_support_struct.h"
|
||||||
|
typedef struct rosidl_action_type_support_t rosidl_action_type_support_t;
|
||||||
|
|
||||||
|
#include "rcl_action/types.h"
|
||||||
|
#include "rcl/macros.h"
|
||||||
|
#include "rcl/node.h"
|
||||||
|
#include "rcl/visibility_control.h"
|
||||||
|
|
||||||
|
|
||||||
|
/// Internal action client implementation struct.
|
||||||
|
struct rcl_action_client_impl_t;
|
||||||
|
|
||||||
|
/// Structure which encapsulates a ROS action client.
|
||||||
|
typedef struct rcl_action_client_t
|
||||||
|
{
|
||||||
|
struct rcl_action_client_impl_t * impl;
|
||||||
|
} rcl_action_client_t;
|
||||||
|
|
||||||
|
/// Options available for a rcl_action_client_t.
|
||||||
|
typedef struct rcl_action_client_options_t
|
||||||
|
{
|
||||||
|
/// Middleware quality of service settings for the action client.
|
||||||
|
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 feedback_topic_qos;
|
||||||
|
rmw_qos_profile_t status_topic_qos;
|
||||||
|
/// Custom allocator for the action client, used for incidental allocations.
|
||||||
|
/** For default behavior (malloc/free), see: rcl_get_default_allocator() */
|
||||||
|
rcl_allocator_t allocator;
|
||||||
|
} rcl_action_client_options_t;
|
||||||
|
|
||||||
|
/// Return a rcl_action_client_t struct with members set to `NULL`.
|
||||||
|
/**
|
||||||
|
* Should be called to get a null rcl_action_client_t before passing to
|
||||||
|
* rcl_action_client_init().
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_action_client_t
|
||||||
|
rcl_action_get_zero_initialized_client(void);
|
||||||
|
|
||||||
|
/// Initialize a rcl_action_client_t.
|
||||||
|
/**
|
||||||
|
* 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().
|
||||||
|
*
|
||||||
|
* The given rcl_node_t must be valid and the resulting rcl_action_client_t is
|
||||||
|
* only valid as long as the given rcl_node_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.
|
||||||
|
* This object can be obtained using a language appropriate mechanism.
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) write these instructions once and link to it instead
|
||||||
|
*
|
||||||
|
* For C, a macro can be used (for example `example_interfaces/Fibonacci`):
|
||||||
|
*
|
||||||
|
* ```c
|
||||||
|
* #include <rosidl_generator_c/action_type_support_struct.h>
|
||||||
|
* #include <example_interfaces/action/fibonacci.h>
|
||||||
|
* const rosidl_action_type_support_t * ts =
|
||||||
|
* ROSIDL_GET_ACTION_TYPE_SUPPORT(example_interfaces, Fibonacci);
|
||||||
|
* ```
|
||||||
|
*
|
||||||
|
* For C++, a template function is used:
|
||||||
|
*
|
||||||
|
* ```cpp
|
||||||
|
* #include <rosidl_generator_cpp/action_type_support.hpp>
|
||||||
|
* #include <example_interfaces/action/fibonacci.h>
|
||||||
|
* using rosidl_typesupport_cpp::get_action_type_support_handle;
|
||||||
|
* const rosidl_action_type_support_t * ts =
|
||||||
|
* get_action_type_support_handle<example_interfaces::action::Fibonacci>();
|
||||||
|
* ```
|
||||||
|
*
|
||||||
|
* The rosidl_action_type_support_t object contains action type specific
|
||||||
|
* information used to send or take goals, results, and feedback.
|
||||||
|
*
|
||||||
|
* The topic name must be a c string that follows the topic and service name
|
||||||
|
* format rules for unexpanded names, also known as non-fully qualified names:
|
||||||
|
*
|
||||||
|
* \see rcl_expand_topic_name
|
||||||
|
*
|
||||||
|
* The options struct allows the user to set the quality of service settings as
|
||||||
|
* well as a custom allocator that is used when initializing/finalizing the
|
||||||
|
* client to allocate space for incidentals, e.g. the action client name string.
|
||||||
|
*
|
||||||
|
* Expected usage (for C action clients):
|
||||||
|
*
|
||||||
|
* ```c
|
||||||
|
* #include <rcl/rcl.h>
|
||||||
|
* #include <rcl_action/action_client.h>
|
||||||
|
* #include <rosidl_generator_c/action_type_support_struct.h>
|
||||||
|
* #include <example_interfaces/action/fibonacci.h>
|
||||||
|
*
|
||||||
|
* rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
|
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
||||||
|
* rcl_ret_t ret = rcl_node_init(&node, "node_name", "/my_namespace", &node_ops);
|
||||||
|
* // ... error handling
|
||||||
|
* const rosidl_action_type_support_t * ts =
|
||||||
|
* ROSIDL_GET_ACTION_TYPE_SUPPORT(example_interfaces, Fibonacci);
|
||||||
|
* rcl_action_client_t action_client = rcl_action_get_zero_initialized_client();
|
||||||
|
* rcl_action_client_options_t action_client_ops = rcl_action_client_get_default_options();
|
||||||
|
* ret = rcl_action_client_init(&action_client, &node, ts, "fibonacci", &action_client_ops);
|
||||||
|
* // ... error handling, and on shutdown do finalization:
|
||||||
|
* ret = rcl_action_client_fini(&action_client, &node);
|
||||||
|
* // ... error handling for rcl_action_client_fini()
|
||||||
|
* ret = rcl_node_fini(&node);
|
||||||
|
* // ... error handling for rcl_node_fini()
|
||||||
|
* ```
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[out] action_client a preallocated, zero-initialized action client structure
|
||||||
|
* to be initialized
|
||||||
|
* \param[in] node valid rcl node 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_client options, including quality of service settings
|
||||||
|
* \return `RCL_RET_OK` if action_client was initialized successfully, or
|
||||||
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
|
* \return `RCL_RET_NODE_INVALID` if the node is invalid, or
|
||||||
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
|
* \return `RCL_RET_ACTION_NAME_INVALID` if the given action name is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_client_init(
|
||||||
|
rcl_action_client_t * action_client,
|
||||||
|
const rcl_node_t * node,
|
||||||
|
const rosidl_action_type_support_t * type_support,
|
||||||
|
const char * action_name,
|
||||||
|
const rcl_action_client_options_t * options);
|
||||||
|
|
||||||
|
/// Finalize a rcl_action_client_t.
|
||||||
|
/**
|
||||||
|
* After calling, the node will no longer listen for goals for this action client
|
||||||
|
* (assuming this is the only action client of this type in this node).
|
||||||
|
*
|
||||||
|
* After calling, calls to rcl_wait(), rcl_action_send_goal_request(),
|
||||||
|
* rcl_action_take_goal_response(), rcl_action_send_cancel_request(),
|
||||||
|
* rcl_action_take_cancel_response(), rcl_action_send_result_request(),
|
||||||
|
* rcl_action_take_result_response(), rcl_action_take_feedback(), and
|
||||||
|
* rcl_action_take_status(), will fail when using this action client.
|
||||||
|
*
|
||||||
|
* Additionally, rcl_wait() will be interrupted if currently blocking.
|
||||||
|
*
|
||||||
|
* The given node handle is still valid.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[inout] action_client handle to the action_client to be deinitialized
|
||||||
|
* \param[in] node handle to the node used to create the action client
|
||||||
|
* \return `RCL_RET_OK` if the action client was deinitialized successfully, or
|
||||||
|
* \return `RCL_RET_ACTION_CLIENT_INVALID` if the action client is invalid, or
|
||||||
|
* \return `RCL_RET_NODE_INVALID` if the node is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_client_fini(rcl_action_client_t * action_client, rcl_node_t * node);
|
||||||
|
|
||||||
|
/// Return the default action client options in a rcl_action_client_options_t.
|
||||||
|
/**
|
||||||
|
* 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;
|
||||||
|
* - feedback_topic_qos = rmw_qos_profile_default;
|
||||||
|
* - status_topic_qos = rcl_action_qos_profile_status_default;
|
||||||
|
* - allocator = rcl_get_default_allocator()
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_action_client_options_t
|
||||||
|
rcl_action_client_get_default_options(void);
|
||||||
|
|
||||||
|
/// Send a ROS goal using a rcl_action_client_t.
|
||||||
|
/**
|
||||||
|
* This is a non-blocking call.
|
||||||
|
*
|
||||||
|
* The caller is responsible for ensuring that the type of `ros_goal_request`
|
||||||
|
* 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.
|
||||||
|
*
|
||||||
|
* The ROS goal message given by the `ros_goal_request` void pointer is always
|
||||||
|
* owned by the calling code, but should remain constant during execution of this
|
||||||
|
* function. i.e. Before and after calling rcl_action_send_goal_request() the
|
||||||
|
* `ros_goal_request` message can change, but it cannot be changed during the call to
|
||||||
|
* rcl_action_send_goal_request().
|
||||||
|
* The same `ros_goal_request` can be passed to multiple calls of this function
|
||||||
|
* simultaneously, even if the action clients differ.
|
||||||
|
*
|
||||||
|
* This function is thread safe so long as access to both the rcl_action_client_t
|
||||||
|
* and the `ros_goal_request` are synchronized.
|
||||||
|
* That means that calling rcl_action_send_goal_request() from multiple threads is allowed,
|
||||||
|
* but calling rcl_action_send_goal_request() at the same time as non-thread safe action
|
||||||
|
* client functions is not, e.g. calling rcl_action_send_goal_request() and
|
||||||
|
* rcl_action_client_fini() concurrently is not allowed.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes [1]
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
* <i>[1] for unique pairs of clients and goals, see above for more</i>
|
||||||
|
*
|
||||||
|
* \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
|
||||||
|
* \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_ACTION_CLIENT_INVALID` if the client is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_send_goal_request(
|
||||||
|
const rcl_action_client_t * action_client,
|
||||||
|
const void * ros_goal_request);
|
||||||
|
|
||||||
|
/// Take a response for a goal request from an action server using a rcl_action_client_t.
|
||||||
|
/**
|
||||||
|
* \todo TODO(jacobperron) blocking of take?
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) pre-, during-, and post-conditions for message ownership?
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) is this thread-safe?
|
||||||
|
*
|
||||||
|
* The caller is responsible for ensuring that the type of `ros_goal_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.
|
||||||
|
*
|
||||||
|
* The caller must provide a pointer to an allocated message for the `ros_goal_response`.
|
||||||
|
* If the take is successful, this function will populate the fields of `ros_goal_response`.
|
||||||
|
* The ROS message given by the `ros_goal_response` void pointer is always
|
||||||
|
* owned by the calling code, but should remain constant during execution of this
|
||||||
|
* function. i.e. Before and after calling rcl_action_send_goal_response() the
|
||||||
|
* `ros_goal_response` message can change, but it cannot be changed during the call to
|
||||||
|
* rcl_action_send_goal_response().
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_client handle to the client that will take the goal response
|
||||||
|
* \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_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_TAKE_FAILED` if take failed but no error occurred
|
||||||
|
* in the middleware, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_take_goal_response(
|
||||||
|
const rcl_action_client_t * action_client,
|
||||||
|
void * ros_goal_response);
|
||||||
|
|
||||||
|
/// Take a ROS feedback message for an active goal associated with a rcl_action_client_t.
|
||||||
|
/**
|
||||||
|
* The caller is responsible for ensuring that the type of `ros_feedback`
|
||||||
|
* 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.
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) blocking of take?
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) pre-, during-, and post-conditions for message ownership?
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) is this thread-safe?
|
||||||
|
*
|
||||||
|
* `ros_feedback` should point to a preallocated ROS message struct of the
|
||||||
|
* correct type.
|
||||||
|
* If feedback is successfully taken, the feedback message is copied to into the
|
||||||
|
* `ros_feedback` struct.
|
||||||
|
*
|
||||||
|
* If allocation is required when taking the feedback, e.g. if space needs to
|
||||||
|
* be allocated for a dynamically sized array in the target message, then the
|
||||||
|
* allocator given in the action client options is used.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Maybe [1]
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
* <i>[1] only if required when filling the feedback message, avoided for fixed sizes</i>
|
||||||
|
*
|
||||||
|
* \param[in] action_client handle to the client that will take the goal response
|
||||||
|
* \param[out] goal_info pointer to a struct for meta-data about the goal associated
|
||||||
|
* with taken feedback
|
||||||
|
* \param[out] ros_feedback pointer to the ROS feedback message.
|
||||||
|
* \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_ACTION_CLIENT_INVALID` if the action client is invalid, or
|
||||||
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
|
* \return `RCL_RET_ACTION_CLIENT_TAKE_FAILED` if take failed but no error occurred
|
||||||
|
* in the middleware, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_take_feedback(
|
||||||
|
const rcl_action_client_t * action_client,
|
||||||
|
void * ros_feedback);
|
||||||
|
|
||||||
|
/// Take a ROS status message using a rcl_action_client_t.
|
||||||
|
/**
|
||||||
|
* The caller is responsible for ensuring that the type of `ros_status_array`
|
||||||
|
* 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.
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) blocking of take?
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) pre-, during-, and post-conditions for message ownership?
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) is this thread-safe?
|
||||||
|
*
|
||||||
|
* The caller is responsible for allocating the `ros_status_array` struct with a
|
||||||
|
* zero-initialization (the internal array should not be allocated).
|
||||||
|
* If there is a successful take, then `ros_status_array` is populated
|
||||||
|
* with the allocator given in the action client options.
|
||||||
|
* It is the callers responsibility to deallocate the `ros_status_array` struct using
|
||||||
|
* the allocator given in the action client options.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_client handle to the client that will take status message
|
||||||
|
* \param[out] ros_status_array pointer to ROS aciton_msgs/StatusArray message that
|
||||||
|
* will be populated with information about goals that have accepted the cancel request.
|
||||||
|
* \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_ACTION_CLIENT_INVALID` if the action client is invalid, or
|
||||||
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
|
* \return `RCL_RET_ACTION_CLIENT_TAKE_FAILED` if take failed but no error occurred
|
||||||
|
* in the middleware, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_take_status(
|
||||||
|
const rcl_action_client_t * action_client,
|
||||||
|
void * ros_status_array);
|
||||||
|
|
||||||
|
/// Send a request for the result of a completed goal associated with a rcl_action_client_t.
|
||||||
|
/**
|
||||||
|
* This is a non-blocking call.
|
||||||
|
*
|
||||||
|
* The caller is responsible for ensuring that the type of `ros_result_request`
|
||||||
|
* 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.
|
||||||
|
*
|
||||||
|
* The ROS message given by the `ros_result_request` void pointer is always
|
||||||
|
* owned by the calling code, but should remain constant during execution of this
|
||||||
|
* function. i.e. Before and after calling rcl_action_send_result_request() the
|
||||||
|
* `ros_result_request` message can change, but it cannot be changed during the call to
|
||||||
|
* rcl_action_send_result_request().
|
||||||
|
* The same `ros_result_request` can be passed to multiple calls of this function
|
||||||
|
* simultaneously, even if the action clients differ.
|
||||||
|
*
|
||||||
|
* This function is thread safe so long as access to both the rcl_action_client_t
|
||||||
|
* and the `ros_result_request` are synchronized.
|
||||||
|
* That means that calling rcl_action_send_result_request() from multiple threads is allowed,
|
||||||
|
* but calling rcl_action_send_result_request() at the same time as non-thread safe action
|
||||||
|
* client functions is not, e.g. calling rcl_action_send_result_request() and
|
||||||
|
* rcl_action_client_fini() concurrently is not allowed.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes [1]
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
* <i>[1] for unique pairs of clients and result requests, see above for more</i>
|
||||||
|
|
||||||
|
* \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
|
||||||
|
* \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_ACTION_CLIENT_INVALID` if the action client is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_send_result_request(
|
||||||
|
const rcl_action_client_t * action_client,
|
||||||
|
const void * ros_result_request);
|
||||||
|
|
||||||
|
/// Take a ROS result message for a completed goal associated with a rcl_action_client_t.
|
||||||
|
/**
|
||||||
|
* \todo TODO(jacobperron) blocking of take?
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) pre-, during-, and post-conditions for message ownership?
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) is this thread-safe?
|
||||||
|
*
|
||||||
|
* 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.
|
||||||
|
*
|
||||||
|
* The caller must provide a pointer to an allocated message for the `ros_result_response`.
|
||||||
|
* If the take is successful, this function will populate the fields of `ros_result_response`.
|
||||||
|
* The ROS message given by the `ros_result_response` void pointer is always
|
||||||
|
* owned by the calling code, but should remain constant during execution of this
|
||||||
|
* function. i.e. Before and after calling rcl_action_take_result_response() the
|
||||||
|
* `ros_result_response` message can change, but it cannot be changed during the call to
|
||||||
|
* rcl_action_take_result_response().
|
||||||
|
*
|
||||||
|
* If allocation is required when taking the result, e.g. if space needs to
|
||||||
|
* be allocated for a dynamically sized array in the target message, then the
|
||||||
|
* allocator given in the action client options is used.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Maybe [1]
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
* <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[out] ros_result_response preallocated, zero-initialized, struct where the ROS
|
||||||
|
* result message is copied.
|
||||||
|
* \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_ACTION_CLIENT_INVALID` if the action client is invalid, or
|
||||||
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
|
* \return `RCL_RET_ACTION_CLIENT_TAKE_FAILED` if take failed but no error occurred
|
||||||
|
* in the middleware, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_take_result_response(
|
||||||
|
const rcl_action_client_t * action_client,
|
||||||
|
void * ros_result);
|
||||||
|
|
||||||
|
/// Send a cancel request for a goal using a rcl_action_client_t.
|
||||||
|
/**
|
||||||
|
* This is a non-blocking call.
|
||||||
|
*
|
||||||
|
* The caller is responsible for ensuring that the type of `ros_cancel_request`
|
||||||
|
* 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.
|
||||||
|
*
|
||||||
|
* 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.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \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
|
||||||
|
* \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_ACTION_CLIENT_INVALID` if the action client is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_send_cancel_request(
|
||||||
|
const rcl_action_client_t * action_client,
|
||||||
|
const void * ros_cancel_request);
|
||||||
|
|
||||||
|
/// Take a cancel response using a rcl_action_client_t.
|
||||||
|
/**
|
||||||
|
* \todo TODO(jacobperron) blocking of take?
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) pre-, during-, and post-conditions for message ownership?
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) is this thread-safe?
|
||||||
|
*
|
||||||
|
* The caller is responsible for ensuring that the type of `ros_cancel_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.
|
||||||
|
|
||||||
|
* The caller is responsible for allocating the `ros_cancel_response` message
|
||||||
|
* with a zero-initialization (the internal array should not be allocated).
|
||||||
|
* If a successful response is taken, then `ros_cancel_response` is populated
|
||||||
|
* using the allocator given in the action client options.
|
||||||
|
* It is the callers responsibility to deallocate `ros_cancel_response` using
|
||||||
|
* the allocator given in the action client options.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_client handle to the client that will take the cancel response
|
||||||
|
* \param[out] ros_cancel_response a zero-initialized ROS cancel response message where
|
||||||
|
* the cancel response is copied.
|
||||||
|
* \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_ACTION_CLIENT_INVALID` if the action client is invalid, or
|
||||||
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
|
* \return `RCL_RET_ACTION_CLIENT_TAKE_FAILED` if take failed but no error occurred
|
||||||
|
* in the middleware, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_take_cancel_response(
|
||||||
|
const rcl_action_client_t * action_client,
|
||||||
|
void * ros_cancel_response);
|
||||||
|
|
||||||
|
/// Get the name of the action for a rcl_action_client_t.
|
||||||
|
/**
|
||||||
|
* This function returns the action client's name string.
|
||||||
|
* This function can fail, and therefore return `NULL`, if the:
|
||||||
|
* - action client is `NULL`
|
||||||
|
* - action client is invalid (never called init, called fini, or invalid)
|
||||||
|
*
|
||||||
|
* The returned string is only valid as long as the action client is valid.
|
||||||
|
* The value of the string may change if the topic name changes, and therefore
|
||||||
|
* copying the string is recommended if this is a concern.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_client the pointer to the action client
|
||||||
|
* \return name string if successful, otherwise `NULL`
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
const char *
|
||||||
|
rcl_action_client_get_action_name(const rcl_action_client_t * action_client);
|
||||||
|
|
||||||
|
/// Return the options for a rcl_action_client_t.
|
||||||
|
/**
|
||||||
|
* This function returns the action client's internal options struct.
|
||||||
|
* This function can fail, and therefore return `NULL`, if the:
|
||||||
|
* - action client is `NULL`
|
||||||
|
* - action client is invalid (never called init, called fini, or invalid)
|
||||||
|
*
|
||||||
|
* The returned struct is only valid as long as the action client is valid.
|
||||||
|
* The values in the struct may change if the action client's options change,
|
||||||
|
* and therefore copying the struct is recommended if this is a concern.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_client pointer to the action client
|
||||||
|
* \return options struct if successful, otherwise `NULL`
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
const rcl_action_client_options_t *
|
||||||
|
rcl_action_client_get_options(const rcl_action_client_t * action_client);
|
||||||
|
|
||||||
|
/// Check that a rcl_action_clieint_t is valid.
|
||||||
|
/**
|
||||||
|
* The bool returned is `false` if `action_client` is invalid.
|
||||||
|
* The bool returned is `true` otherwise.
|
||||||
|
* In the case where `false` is to be returned, an error message is set.
|
||||||
|
* This function cannot fail.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_client pointer to the rcl action client
|
||||||
|
* \param[in] error_msg_allocator a valid allocator or `NULL`
|
||||||
|
* \return `true` if `action_client` is valid, otherwise `false`
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
bool
|
||||||
|
rcl_action_client_is_valid(
|
||||||
|
const rcl_action_client_t * action_client,
|
||||||
|
rcl_allocator_t * error_msg_allocator);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // RCL_ACTION__ACTION_CLIENT_H_
|
815
rcl_action/include/rcl_action/action_server.h
Normal file
815
rcl_action/include/rcl_action/action_server.h
Normal file
|
@ -0,0 +1,815 @@
|
||||||
|
// Copyright 2018 Open Source Robotics Foundation, Inc.
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#ifndef RCL_ACTION__ACTION_SERVER_H_
|
||||||
|
#define RCL_ACTION__ACTION_SERVER_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// TODO(jacobperron): replace type support typedef with one defined in rosdl_generator_c
|
||||||
|
// #include "rosidl_generator_c/action_type_support_struct.h"
|
||||||
|
typedef struct rosidl_action_type_support_t rosidl_action_type_support_t;
|
||||||
|
|
||||||
|
#include "rcl_action/goal_handle.h"
|
||||||
|
#include "rcl_action/types.h"
|
||||||
|
#include "rcl/macros.h"
|
||||||
|
#include "rcl/node.h"
|
||||||
|
#include "rcl/time.h"
|
||||||
|
#include "rcl/visibility_control.h"
|
||||||
|
|
||||||
|
|
||||||
|
/// Internal rcl_action implementation struct.
|
||||||
|
struct rcl_action_server_impl_t;
|
||||||
|
|
||||||
|
/// Structure which encapsulates a ROS Action Server.
|
||||||
|
typedef struct rcl_action_server_t
|
||||||
|
{
|
||||||
|
struct rcl_action_server_impl_t * impl;
|
||||||
|
} rcl_action_server_t;
|
||||||
|
|
||||||
|
/// Options available for a rcl_action_server_t.
|
||||||
|
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 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;
|
||||||
|
/// Goal handles that have results longer than this time are deallocated.
|
||||||
|
rcl_duration_t result_timeout;
|
||||||
|
} rcl_action_server_options_t;
|
||||||
|
|
||||||
|
/// Return a rcl_action_server_t struct with members set to `NULL`.
|
||||||
|
/**
|
||||||
|
* Should be called to get a null rcl_action_server_t before passing to
|
||||||
|
* rcl_action_server_init().
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_action_server_t
|
||||||
|
rcl_action_get_zero_initialized_server(void);
|
||||||
|
|
||||||
|
/// Initialize a rcl_action_server_t.
|
||||||
|
/**
|
||||||
|
* 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().
|
||||||
|
*
|
||||||
|
* 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 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.
|
||||||
|
* This object can be obtained using a language appropriate mechanism.
|
||||||
|
* \todo TODO(jacobperron) write these instructions once and link to it instead
|
||||||
|
*
|
||||||
|
* For C, a macro can be used (for example `example_interfaces/Fibonacci`):
|
||||||
|
*
|
||||||
|
* ```c
|
||||||
|
* #include <rosidl_generator_c/action_type_support_struct.h>
|
||||||
|
* #include <example_interfaces/action/fibonacci.h>
|
||||||
|
* const rosidl_action_type_support_t * ts =
|
||||||
|
* ROSIDL_GET_ACTION_TYPE_SUPPORT(example_interfaces, Fibonacci);
|
||||||
|
* ```
|
||||||
|
*
|
||||||
|
* For C++, a template function is used:
|
||||||
|
*
|
||||||
|
* ```cpp
|
||||||
|
* #include <rosidl_generator_cpp/action_type_support.hpp>
|
||||||
|
* #include <example_interfaces/action/fibonacci.h>
|
||||||
|
* using rosidl_typesupport_cpp::get_action_type_support_handle;
|
||||||
|
* const rosidl_action_type_support_t * ts =
|
||||||
|
* get_action_type_support_handle<example_interfaces::action::Fibonacci>();
|
||||||
|
* ```
|
||||||
|
*
|
||||||
|
* The rosidl_action_type_support_t object contains action type specific
|
||||||
|
* information used to send or take goals, results, and feedback.
|
||||||
|
*
|
||||||
|
* The topic name must be a c string that follows the topic and service name
|
||||||
|
* format rules for unexpanded names, also known as non-fully qualified names:
|
||||||
|
*
|
||||||
|
* \see rcl_expand_topic_name
|
||||||
|
*
|
||||||
|
* The options struct allows the user to set the quality of service settings as
|
||||||
|
* well as a custom allocator that is used when initializing/finalizing the
|
||||||
|
* client to allocate space for incidentals, e.g. the action server name string.
|
||||||
|
*
|
||||||
|
* Expected usage (for C action servers):
|
||||||
|
*
|
||||||
|
* ```c
|
||||||
|
* #include <rcl/rcl.h>
|
||||||
|
* #include <rcl_action/rcl_action.h>
|
||||||
|
* #include <rosidl_generator_c/action_type_support_struct.h>
|
||||||
|
* #include <example_interfaces/action/fibonacci.h>
|
||||||
|
*
|
||||||
|
* rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
|
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
||||||
|
* rcl_ret_t ret = rcl_node_init(&node, "node_name", "/my_namespace", &node_ops);
|
||||||
|
* // ... error handling
|
||||||
|
* const rosidl_action_type_support_t * ts =
|
||||||
|
* ROSIDL_GET_ACTION_TYPE_SUPPORT(example_interfaces, Fibonacci);
|
||||||
|
* rcl_action_server_t action_server = rcl_action_get_zero_initialized_server();
|
||||||
|
* rcl_action_server_options_t action_server_ops = rcl_action_server_get_default_options();
|
||||||
|
* ret = rcl_action_server_init(&action_server, &node, ts, "fibonacci", &action_server_ops);
|
||||||
|
* // ... error handling, and on shutdown do finalization:
|
||||||
|
* ret = rcl_action_server_fini(&action_server, &node);
|
||||||
|
* // ... error handling for rcl_action_server_fini()
|
||||||
|
* ret = rcl_node_fini(&node);
|
||||||
|
* // ... error handling for rcl_node_fini()
|
||||||
|
* ```
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[out] action_server a preallocated, zero-initialized action server structure
|
||||||
|
* to be initialized.
|
||||||
|
* \param[in] node valid rcl node 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
|
||||||
|
* \return `RCL_RET_OK` if action_server was initialized successfully, or
|
||||||
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
|
* \return `RCL_RET_NODE_INVALID` if the node is invalid, or
|
||||||
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
|
* \return `RCL_RET_ACTION_NAME_INVALID` if the given action name is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_server_init(
|
||||||
|
rcl_action_server_t * action_server,
|
||||||
|
const rcl_node_t * node,
|
||||||
|
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.
|
||||||
|
/**
|
||||||
|
* After calling, the node will no longer listen for goals 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(),
|
||||||
|
* rcl_action_take_cancel_request(), rcl_action_publish_feedback(),
|
||||||
|
* rcl_action_publish_status(), rcl_action_send_result(), and
|
||||||
|
* rcl_action_send_cancel_response() will fail when using this action server.
|
||||||
|
* Additionally, rcl_wait() will be interrupted if currently blocking.
|
||||||
|
* However, the given node handle is still valid.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \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_NODE_INVALID` if the node is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_server_fini(rcl_action_server_t * action_server, rcl_node_t * node);
|
||||||
|
|
||||||
|
/// Return the default action server options in a rcl_action_server_options_t.
|
||||||
|
/**
|
||||||
|
* 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;
|
||||||
|
* - 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
|
||||||
|
*/
|
||||||
|
RCL_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.
|
||||||
|
/**
|
||||||
|
* \todo TODO(jacobperron) blocking of take?
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) pre-, during-, and post-conditions for message ownership?
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) is this thread-safe?
|
||||||
|
*
|
||||||
|
* The caller is responsible for ensuring that the type of `ros_goal_request`
|
||||||
|
* 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.
|
||||||
|
*
|
||||||
|
* `ros_goal_request` should point to a preallocated, zero-initialized,
|
||||||
|
* ROS goal message.
|
||||||
|
* If a goal request is taken successfully, it will be copied into `ros_goal_request`.
|
||||||
|
*
|
||||||
|
* If allocation is required when taking the request, e.g. if space needs to
|
||||||
|
* be allocated for a dynamically sized array in the target message, then the
|
||||||
|
* allocator given in the action server options is used.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Maybe [1]
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* 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[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
|
||||||
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
|
* \return `RCL_RET_ACTION_SERVER_INVALID` if the action server is invalid, or
|
||||||
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
|
* \return `RCL_RET_ACTION_SERVER_TAKE_FAILED` if take failed but no error occurred
|
||||||
|
* in the middleware, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
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.
|
||||||
|
/**
|
||||||
|
* This is a non-blocking call.
|
||||||
|
*
|
||||||
|
* The caller is responsible for ensuring that the type of `ros_goal_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.
|
||||||
|
*
|
||||||
|
* If the caller intends to send an 'accepted' response, before calling this function
|
||||||
|
* the caller should use rcl_action_accept_new_goal() to get a rcl_action_goal_handle_t
|
||||||
|
* for future interaction with the goal (e.g. publishing feedback and canceling the goal).
|
||||||
|
*
|
||||||
|
* This function is thread safe so long as access to both the action server and the
|
||||||
|
* `ros_goal_response` are synchronized.
|
||||||
|
* That means that calling rcl_action_send_goal_response() from multiple threads is
|
||||||
|
* allowed, but calling rcl_action_send_goal_response() at the same time as non-thread safe
|
||||||
|
* action server functions is not, e.g. calling rcl_action_send_goal_response() and
|
||||||
|
* rcl_action_server_fini() concurrently is not allowed.
|
||||||
|
* Before calling rcl_action_send_goal_response() the `ros_goal_request` can change and
|
||||||
|
* after calling rcl_action_send_goal_response() the `ros_goal_request` can change, but it
|
||||||
|
* cannot be changed during the rcl_action_send_goal_response() call.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes [1]
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
* <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] ros_goal_response a ROS goal response message to send
|
||||||
|
* \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_ACTION_SERVER_INVALID` if the action server is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_send_goal_response(
|
||||||
|
const rcl_action_server_t * action_server,
|
||||||
|
const void * ros_goal_response);
|
||||||
|
|
||||||
|
/// Accept a new goal using a rcl_action_server_t.
|
||||||
|
/**
|
||||||
|
* This is a non-blocking call.
|
||||||
|
*
|
||||||
|
* Creates and returns a pointer to a goal handle for a newly accepted goal.
|
||||||
|
* If a failure occurs, `NULL` is returned and an error message is set.
|
||||||
|
*
|
||||||
|
* 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().
|
||||||
|
*
|
||||||
|
* Example usage:
|
||||||
|
*
|
||||||
|
* ```c
|
||||||
|
* #include <rcl/rcl_action.h>
|
||||||
|
*
|
||||||
|
* // ... init an action server
|
||||||
|
* // Take a goal request (client library type)
|
||||||
|
* rcl_ret_t ret = rcl_action_take_goal_request(&action_server, &goal_request);
|
||||||
|
* // ... error handling
|
||||||
|
* // If the goal is accepted, then tell the action server
|
||||||
|
* // First, create and populate a goal info message (rcl type)
|
||||||
|
* rcl_action_goal_info_t goal_info = rcl_action_get_zero_initialized_goal_info();
|
||||||
|
* ret = rcl_action_goal_info_init(&goal_info, &action_server);
|
||||||
|
* // ... error handling, and populate with goal ID and timestamp
|
||||||
|
* ret = rcl_action_accept_new_goal(&action_server, &goal_info, NULL);
|
||||||
|
* // ... error_handling
|
||||||
|
* // ... Populate goal response (client library type)
|
||||||
|
* ret = rcl_action_send_goal_response(&action_server, &goal_response);
|
||||||
|
* // ... error handling, and sometime before shutdown finalize goal info message
|
||||||
|
* ret = rcl_action_goal_info_fini(&goal_info, &action_server);
|
||||||
|
* ```
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | Yes
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_server 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.
|
||||||
|
*/
|
||||||
|
RCL_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);
|
||||||
|
|
||||||
|
/// Publish a ROS feedback message for an active goal using a rcl_action_server_t.
|
||||||
|
/**
|
||||||
|
* The caller is responsible for ensuring that the type of `ros_feedback`
|
||||||
|
* 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.
|
||||||
|
*
|
||||||
|
* This function acts like a ROS publisher and is potentially a blocking call.
|
||||||
|
* \see rcl_publish()
|
||||||
|
*
|
||||||
|
* This function is thread safe so long as access to both the action server and
|
||||||
|
* `ros_feedback` is synchronized.
|
||||||
|
* That means that calling rcl_action_publish_feedback() from multiple threads
|
||||||
|
* is allowed, but calling rcl_action_publish_feedback() at the same time as
|
||||||
|
* non-thread safe action server functions is not, e.g. calling
|
||||||
|
* rcl_action_publish_feedback() and rcl_action_server_fini() concurrently is not
|
||||||
|
* allowed.
|
||||||
|
*
|
||||||
|
* Before calling rcl_action_publish_feedback() the `ros_feedback` message ca
|
||||||
|
* change and after calling rcl_action_publish_feedback() the `ros_feedback` message
|
||||||
|
* can change, but it cannot be changed during the publish call.
|
||||||
|
* The same `ros_feedback` can be passed to multiple calls of
|
||||||
|
* rcl_action_publish_feedback() simultaneously, even if the action servers differ.
|
||||||
|
* `ros_feedback` is unmodified by rcl_action_publish_feedback().
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes [1]
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
* <i>[1] for unique pairs of action servers and feedback, see above for more</i>
|
||||||
|
*
|
||||||
|
* \param[in] action_server handle to the action server that will publish the feedback
|
||||||
|
* \param[in] ros_feedback a ROS message containing the goal feedback
|
||||||
|
* \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_ACTION_SERVER_INVALID` if the action server is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs. *
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
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.
|
||||||
|
/**
|
||||||
|
* The provided `status_message` should be zero-initialized with
|
||||||
|
* rcl_action_get_zero_initialized_goal_status_array() before calling this function.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_server handle to the action server that will publish the status message
|
||||||
|
* \param[out] status_message an action_msgs/StatusArray ROS message
|
||||||
|
* \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_ACTION_SERVER_INVALID` if the action server is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
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.
|
||||||
|
/**
|
||||||
|
* This function acts like a ROS publisher and is potntially a blocking call.
|
||||||
|
* \see rcl_publish()
|
||||||
|
*
|
||||||
|
* A status array message associated with the action server can be created with
|
||||||
|
* rcl_action_get_goal_status_array().
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_server handle to the action server that will publish the status message
|
||||||
|
* \param[in] status_message an action_msgs/StatusArray ROS message to publish
|
||||||
|
* \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_ACTION_SERVER_INVALID` if the action server is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
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);
|
||||||
|
|
||||||
|
/// Take a pending result request using a rcl_action_server_t.
|
||||||
|
/**
|
||||||
|
* \todo TODO(jacobperron) blocking of take?
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) pre-, during-, and post-conditions for message ownership?
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) is this thread-safe?
|
||||||
|
*
|
||||||
|
* The caller is responsible for ensuring that the type of `ros_result_request`
|
||||||
|
* 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.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_server handle to the action server that will take the result request
|
||||||
|
* \param[out] ros_result_request a preallocated ROS result request message where the
|
||||||
|
* request is copied.
|
||||||
|
* \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_ACTION_SERVER_INVALID` if the action server is invalid, or
|
||||||
|
* \return `RCL_RET_ACTION_SERVER_TAKE_FAILED` if take failed but no error occurred
|
||||||
|
* in the middleware, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
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.
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_server handle to the action server that will send the result response
|
||||||
|
* \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_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
|
* \return `RCL_RET_ACTION_SERVER_INVALID` if the action server is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_send_result_response(
|
||||||
|
const rcl_action_server_t * action_server,
|
||||||
|
const void * ros_result_response);
|
||||||
|
|
||||||
|
/// Clear all expired goals associated with a rcl_action_server_t.
|
||||||
|
/**
|
||||||
|
* A goal is 'expired' if it has been in a terminal state (has a result) for more
|
||||||
|
* than some duration.
|
||||||
|
* The timeout duration is set as part of the action server options.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \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.
|
||||||
|
* \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_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_clear_expired_goals(
|
||||||
|
const rcl_action_server_t * action_server,
|
||||||
|
uint32_t * num_expired);
|
||||||
|
|
||||||
|
/// Take a pending cancel request using a rcl_action_server_t.
|
||||||
|
/**
|
||||||
|
* \todo TODO(jacobperron) blocking of take?
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) pre-, during-, and post-conditions for message ownership?
|
||||||
|
*
|
||||||
|
* \todo TODO(jacobperron) is this thread-safe?
|
||||||
|
*
|
||||||
|
* The caller is responsible for ensuring that the type of `ros_cancel_request`_
|
||||||
|
* 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.
|
||||||
|
*
|
||||||
|
* After receiving a successful cancel request, the appropriate goals can be
|
||||||
|
* transitioned to the state CANCELING using rcl_action_process_cancel_request().
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_server handle to the action server that will take the cancel request
|
||||||
|
* \param[out] ros_cancel_request a preallocated ROS cancel request where the request
|
||||||
|
* message is copied
|
||||||
|
* \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_ACTION_SERVER_INVALID` if the action server is invalid, or
|
||||||
|
* \return `RCL_RET_ACTION_SERVER_TAKE_FAILED` if take failed but no error occurred
|
||||||
|
* in the middleware, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
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.
|
||||||
|
/**
|
||||||
|
* This is a non-blocking call.
|
||||||
|
*
|
||||||
|
* This function will transition one or more active goals to the state CANCELING.
|
||||||
|
* 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.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \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
|
||||||
|
* 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
|
||||||
|
* \return `RCL_RET_ACTION_SERVER_INVALID` if the action server is invalid, or
|
||||||
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
|
* \return `RCL_RET_ACTION_SERVER_TAKE_FAILED` if take failed but no error occurred
|
||||||
|
* in the middleware, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_process_cancel_request(
|
||||||
|
const rcl_action_server_t * action_server,
|
||||||
|
const rcl_action_cancel_request_t * cancel_request,
|
||||||
|
rcl_action_cancel_response_t * cancel_response);
|
||||||
|
|
||||||
|
/// Send a cancel response using a rcl action server.
|
||||||
|
/**
|
||||||
|
* This is a non-blocking call.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_server the 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
|
||||||
|
* \return `RCL_RET_ACTION_SERVER_INVALID` if the action server is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_send_cancel_response(
|
||||||
|
const rcl_action_server_t * action_server,
|
||||||
|
const void * ros_cancel_response);
|
||||||
|
|
||||||
|
/// Get the name of the action for a rcl_action_server_t.
|
||||||
|
/**
|
||||||
|
* 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)
|
||||||
|
*
|
||||||
|
* 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
|
||||||
|
* copying the string is recommended if this is a concern.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_server the pointer to the action server
|
||||||
|
* \return name string if successful, otherwise `NULL`
|
||||||
|
*/
|
||||||
|
RCL_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.
|
||||||
|
/**
|
||||||
|
* 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)
|
||||||
|
*
|
||||||
|
* 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,
|
||||||
|
* and therefore copying the struct is recommended if this is a concern.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_server pointer to the action server
|
||||||
|
* \return options struct if successful, otherwise `NULL`
|
||||||
|
*/
|
||||||
|
RCL_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.
|
||||||
|
/**
|
||||||
|
* A pointer to the internally held array of 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 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.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_server pointer to the rcl action server
|
||||||
|
* \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`
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
const rcl_action_goal_handle_t *
|
||||||
|
rcl_action_server_get_goal_handles(
|
||||||
|
const rcl_action_server_t * action_server,
|
||||||
|
uint32_t * num_goals);
|
||||||
|
|
||||||
|
/// Check that the action server is valid.
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
* This function cannot fail.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* 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`
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
bool
|
||||||
|
rcl_action_server_is_valid(
|
||||||
|
const rcl_action_server_t * action_server,
|
||||||
|
rcl_allocator_t * error_msg_allocator);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // RCL_ACTION__ACTION_SERVER_H_
|
39
rcl_action/include/rcl_action/default_qos.h
Normal file
39
rcl_action/include/rcl_action/default_qos.h
Normal file
|
@ -0,0 +1,39 @@
|
||||||
|
// Copyright 2018 Open Source Robotics Foundation, Inc.
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#ifndef RCL_ACTION__DEFAULT_QOS_H_
|
||||||
|
#define RCL_ACTION__DEFAULT_QOS_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "rmw/types.h"
|
||||||
|
|
||||||
|
|
||||||
|
static const rmw_qos_profile_t rcl_action_qos_profile_status_default =
|
||||||
|
{
|
||||||
|
RMW_QOS_POLICY_HISTORY_KEEP_LAST,
|
||||||
|
1,
|
||||||
|
RMW_QOS_POLICY_RELIABILITY_RELIABLE,
|
||||||
|
RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL,
|
||||||
|
false
|
||||||
|
};
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // RCL_ACTION__DEFAULT_QOS_H_
|
284
rcl_action/include/rcl_action/goal_handle.h
Normal file
284
rcl_action/include/rcl_action/goal_handle.h
Normal file
|
@ -0,0 +1,284 @@
|
||||||
|
// Copyright 2018 Open Source Robotics Foundation, Inc.
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#ifndef RCL_ACTION__GOAL_HANDLE_H_
|
||||||
|
#define RCL_ACTION__GOAL_HANDLE_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "rcl_action/goal_state_machine.h"
|
||||||
|
#include "rcl_action/types.h"
|
||||||
|
#include "rcl/visibility_control.h"
|
||||||
|
|
||||||
|
// Forward declare
|
||||||
|
typedef struct rcl_action_server_t rcl_action_server_t;
|
||||||
|
|
||||||
|
/// Internal rcl action goal implementation struct.
|
||||||
|
struct rcl_action_goal_handle_impl_t;
|
||||||
|
|
||||||
|
/// Goal handle for an action.
|
||||||
|
typedef struct rcl_action_goal_handle_t
|
||||||
|
{
|
||||||
|
struct rcl_action_goal_handle_impl_t * impl;
|
||||||
|
} rcl_action_goal_handle_t;
|
||||||
|
|
||||||
|
/// Return a rcl_action_goal_handle_t struct with members set to `NULL`.
|
||||||
|
/**
|
||||||
|
* Should be called to get a null rcl_action_goal_handle_t before passing to
|
||||||
|
* rcl_action_goal_handle_init().
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_action_goal_handle_t
|
||||||
|
rcl_action_get_zero_initialized_goal_handle(void);
|
||||||
|
|
||||||
|
/// Initialize a rcl_action_goal_handle_t.
|
||||||
|
/**
|
||||||
|
* 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().
|
||||||
|
*
|
||||||
|
* The given rcl_action_server_t must be valid and the resulting rcl_action_goal_handle_t is
|
||||||
|
* only valid as long as the given rcl_action_server_t remains valid.
|
||||||
|
*
|
||||||
|
* Expected usage:
|
||||||
|
*
|
||||||
|
* ```c
|
||||||
|
* #include <rcl/rcl.h>
|
||||||
|
* #include <rcl_action/rcl_action.h>
|
||||||
|
* #include <rosidl_generator_c/action_type_support_struct.h>
|
||||||
|
* #include <example_interfaces/action/fibonacci.h>
|
||||||
|
*
|
||||||
|
* // ... initialize node
|
||||||
|
* const rosidl_action_type_support_t * ts =
|
||||||
|
* ROSIDL_GET_ACTION_TYPE_SUPPORT(example_interfaces, Fibonacci);
|
||||||
|
* rcl_action_server_t action_server = rcl_action_get_zero_initialized_server();
|
||||||
|
* rcl_action_server_options_t action_server_ops = rcl_action_server_get_default_options();
|
||||||
|
* ret = rcl_action_server_init(&action_server, &node, ts, "fibonacci", &action_server_ops);
|
||||||
|
* // ... error handling
|
||||||
|
* rcl_action_goal_handle_t goal_handle = rcl_action_get_zero_initialized_goal_handle();
|
||||||
|
* ret = rcl_action_goal_handle_init(&goal_handle, &action_server);
|
||||||
|
* // ... error handling, and on shutdown do finalization:
|
||||||
|
* ret = rcl_action_goal_handle_fini(&goal_handle);
|
||||||
|
* // ... error handling for rcl_goal_handle_fini()
|
||||||
|
* ret = rcl_action_server_fini(&action_server, &node);
|
||||||
|
* // ... error handling for rcl_action_server_fini()
|
||||||
|
* // ... finalize and error handling for node
|
||||||
|
* ```
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[out] goal_handle preallocated, zero-initialized, goal handle structure
|
||||||
|
* to be initialized
|
||||||
|
* \param[in] action_server valid rcl action server
|
||||||
|
* \param[in] type_support type support object for the action's type
|
||||||
|
* \return `RCL_RET_OK` if goal_handle was initialized successfully, or
|
||||||
|
* \return `RCL_RET_ACTION_GOAL_HANDLE_INVALID` if the goal handle is invalid, or
|
||||||
|
* \return `RCL_RET_ACTION_SERVER_INVALID` if the action server is invalid, or
|
||||||
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_goal_handle_init(
|
||||||
|
rcl_action_goal_handle_t * goal_handle,
|
||||||
|
const rcl_action_server_t * action_server);
|
||||||
|
|
||||||
|
/// Finalize a rcl_action_goal_handle_t.
|
||||||
|
/**
|
||||||
|
* After calling, rcl_action_goal_handle_t will no longer be valid and
|
||||||
|
* rcl_action_server_t will no longer track the goal associated with the goal handle.
|
||||||
|
*
|
||||||
|
* After calling, calls to rcl_action_publish_feedback(), rcl_action_publish_status(),
|
||||||
|
* rcl_action_update_goal_state(), rcl_action_goal_handle_get_status(),
|
||||||
|
* rcl_action_goal_handle_is_active(), rcl_action_goal_handle_get_message(), and
|
||||||
|
* rcl_action_goal_handle_get_info() will fail when using this goal handle.
|
||||||
|
*
|
||||||
|
* However, the given action server is still valid.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] goal_handle struct to be deinitialized
|
||||||
|
* \param[in] action_server used to create the goal handle
|
||||||
|
* \return `RCL_RET_OK` if the goal handle was deinitialized successfully, or
|
||||||
|
* \return `RCL_RET_ACTION_GOAL_HANDLE_INVALID` if the goal handle is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_goal_handle_fini(rcl_action_goal_handle_t * goal_handle);
|
||||||
|
|
||||||
|
/// Update a goal state with a rcl_action_goal_handle_t and an event.
|
||||||
|
/**
|
||||||
|
* This is a non-blocking call.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[inout] goal_handle struct containing goal state to transition
|
||||||
|
* \param[in] goal_event the event used to transition the goal state
|
||||||
|
* \return `RCL_RET_OK` if the goal state was updated successfully, or
|
||||||
|
* \return `RCL_RET_ACTION_GOAL_EVENT_INVALID` if the goal event is invalid, or
|
||||||
|
* \return `RCL_RET_ACTION_GOAL_HANDLE_INVALID` if the goal handle is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_update_goal_state(
|
||||||
|
rcl_action_goal_handle_t * goal_handle,
|
||||||
|
const rcl_action_goal_event_t goal_event);
|
||||||
|
|
||||||
|
/// Get the ID of a goal using a rcl_action_goal_handle_t.
|
||||||
|
/**
|
||||||
|
* This is a non-blocking call.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] goal_handle struct containing the goal and meta
|
||||||
|
* \param[out] goal_info a preallocated struct where the goal info is copied
|
||||||
|
* \return `RCL_RET_OK` if the goal ID was accessed successfully, or
|
||||||
|
* \return `RCL_RET_ACTION_GOAL_HANDLE_INVALID` if the goal handle is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_goal_handle_get_info(
|
||||||
|
const rcl_action_goal_handle_t * goal_handle,
|
||||||
|
rcl_action_goal_info_t * goal_info);
|
||||||
|
|
||||||
|
/// Get the status of a goal.
|
||||||
|
/**
|
||||||
|
* This is a non-blocking call.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] goal_handle struct containing the goal and metadata
|
||||||
|
* \param[out] status a preallocated struct where the goal status is copied
|
||||||
|
* \return `RCL_RET_OK` if the goal ID was accessed successfully, or
|
||||||
|
* \return `RCL_RET_ACTION_GOAL_HANDLE_INVALID` if the goal handle is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_goal_handle_get_status(
|
||||||
|
const rcl_action_goal_handle_t * goal_handle,
|
||||||
|
rcl_action_goal_state_t * status);
|
||||||
|
|
||||||
|
/// Check if a goal is active using a rcl_action_goal_handle_t.
|
||||||
|
/**
|
||||||
|
* This is a non-blocking call.
|
||||||
|
*
|
||||||
|
* The allocator needs to either be a valid allocator or `NULL`, in which case
|
||||||
|
* the default allocator will be used.
|
||||||
|
* The allocator is used when allocation is needed for an error message.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] goal_handle struct containing the goal and metadata
|
||||||
|
* \param[in] error_msg_allocator a valid allocator or `NULL`
|
||||||
|
* \return `true` if a goal is in one of the following states: ACCEPTED, EXECUTING, or CANCELING, or
|
||||||
|
* \return `false` otherwise, also
|
||||||
|
* \return `false` if the goal handle pointer is invalid or the allocator is invalid
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
bool
|
||||||
|
rcl_action_goal_handle_is_active(
|
||||||
|
const rcl_action_goal_handle_t * goal_handle,
|
||||||
|
rcl_allocator_t * error_msg_allocator);
|
||||||
|
|
||||||
|
/// Check if a rcl_action_goal_handle_t is valid.
|
||||||
|
/**
|
||||||
|
* This is a non-blocking call.
|
||||||
|
*
|
||||||
|
* The allocator needs to either be a valid allocator or `NULL`, in which case
|
||||||
|
* the default allocator will be used.
|
||||||
|
* The allocator is used when allocation is needed for an error message.
|
||||||
|
*
|
||||||
|
* 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()
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] goal_handle struct to evaluate as valid or not
|
||||||
|
* \param[in] error_msg_allocator a valid allocator or `NULL`
|
||||||
|
* \return `true` if the goal handle is valid, `false` otherwise, also
|
||||||
|
* \return `false` if the allocator is invalid
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
bool
|
||||||
|
rcl_action_goal_handle_is_valid(
|
||||||
|
const rcl_action_goal_handle_t * goal_handle,
|
||||||
|
rcl_allocator_t * error_msg_allocator);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // RCL_ACTION__GOAL_HANDLE_H_
|
132
rcl_action/include/rcl_action/goal_state_machine.h
Normal file
132
rcl_action/include/rcl_action/goal_state_machine.h
Normal file
|
@ -0,0 +1,132 @@
|
||||||
|
// Copyright 2018 Open Source Robotics Foundation, Inc.
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#ifndef RCL_ACTION__GOAL_STATE_MACHINE_H_
|
||||||
|
#define RCL_ACTION__GOAL_STATE_MACHINE_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "rcl_action/types.h"
|
||||||
|
#include "rcl/visibility_control.h"
|
||||||
|
|
||||||
|
|
||||||
|
typedef rcl_action_goal_state_t
|
||||||
|
(* rcl_action_goal_event_handler)(rcl_action_goal_state_t, rcl_action_goal_event_t);
|
||||||
|
|
||||||
|
// Transition event handlers
|
||||||
|
static inline rcl_action_goal_state_t
|
||||||
|
_execute_event_handler(rcl_action_goal_state_t state, rcl_action_goal_event_t event)
|
||||||
|
{
|
||||||
|
if (GOAL_STATE_ACCEPTED != state || GOAL_EVENT_EXECUTE != event) {
|
||||||
|
return GOAL_STATE_UNKNOWN;
|
||||||
|
}
|
||||||
|
return GOAL_STATE_EXECUTING;
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline rcl_action_goal_state_t
|
||||||
|
_cancel_event_handler(rcl_action_goal_state_t state, rcl_action_goal_event_t event)
|
||||||
|
{
|
||||||
|
if (GOAL_STATE_ACCEPTED != state ||
|
||||||
|
GOAL_STATE_EXECUTING != state ||
|
||||||
|
GOAL_EVENT_CANCEL != event)
|
||||||
|
{
|
||||||
|
return GOAL_STATE_UNKNOWN;
|
||||||
|
}
|
||||||
|
return GOAL_STATE_CANCELING;
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline rcl_action_goal_state_t
|
||||||
|
_set_succeeded_event_handler(rcl_action_goal_state_t state, rcl_action_goal_event_t event)
|
||||||
|
{
|
||||||
|
if (GOAL_STATE_EXECUTING != state ||
|
||||||
|
GOAL_STATE_CANCELING != state ||
|
||||||
|
GOAL_EVENT_SET_SUCCEEDED != event)
|
||||||
|
{
|
||||||
|
return GOAL_STATE_UNKNOWN;
|
||||||
|
}
|
||||||
|
return GOAL_STATE_SUCCEEDED;
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline rcl_action_goal_state_t
|
||||||
|
_set_aborted_event_handler(rcl_action_goal_state_t state, rcl_action_goal_event_t event)
|
||||||
|
{
|
||||||
|
if (GOAL_STATE_EXECUTING != state ||
|
||||||
|
GOAL_STATE_CANCELING != state ||
|
||||||
|
GOAL_EVENT_SET_ABORTED != event)
|
||||||
|
{
|
||||||
|
return GOAL_STATE_UNKNOWN;
|
||||||
|
}
|
||||||
|
return GOAL_STATE_ABORTED;
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline rcl_action_goal_state_t
|
||||||
|
_set_canceled_event_handler(rcl_action_goal_state_t state, rcl_action_goal_event_t event)
|
||||||
|
{
|
||||||
|
if (GOAL_STATE_CANCELING != state || GOAL_EVENT_SET_CANCELED != event) {
|
||||||
|
return GOAL_STATE_UNKNOWN;
|
||||||
|
}
|
||||||
|
return GOAL_STATE_CANCELED;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Transition map
|
||||||
|
rcl_action_goal_event_handler
|
||||||
|
_goal_state_transition_map[GOAL_STATE_NUM_STATES][GOAL_EVENT_NUM_EVENTS] = {
|
||||||
|
[GOAL_STATE_ACCEPTED] = {
|
||||||
|
[GOAL_EVENT_EXECUTE] = _execute_event_handler,
|
||||||
|
[GOAL_EVENT_CANCEL] = _cancel_event_handler,
|
||||||
|
},
|
||||||
|
[GOAL_STATE_EXECUTING] = {
|
||||||
|
[GOAL_EVENT_CANCEL] = _cancel_event_handler,
|
||||||
|
[GOAL_EVENT_SET_SUCCEEDED] = _set_succeeded_event_handler,
|
||||||
|
[GOAL_EVENT_SET_ABORTED] = _set_aborted_event_handler,
|
||||||
|
},
|
||||||
|
[GOAL_STATE_CANCELING] = {
|
||||||
|
[GOAL_EVENT_SET_SUCCEEDED] = _set_succeeded_event_handler,
|
||||||
|
[GOAL_EVENT_SET_ABORTED] = _set_aborted_event_handler,
|
||||||
|
[GOAL_EVENT_SET_CANCELED] = _set_canceled_event_handler,
|
||||||
|
},
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Transition a goal from one state to the next.
|
||||||
|
/**
|
||||||
|
* Given a goal state and a goal event, return the next state.
|
||||||
|
*
|
||||||
|
* \param[in] state the state to transition from
|
||||||
|
* \param[in] event the event triggering a transition
|
||||||
|
* \return the next goal state if the transition is valid, or
|
||||||
|
* \return `GOAl_STATE_UNKNOWN` if the transition is invalid or an error occured
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
inline rcl_action_goal_state_t
|
||||||
|
rcl_action_transition_goal_state(
|
||||||
|
const rcl_action_goal_state_t state,
|
||||||
|
const rcl_action_goal_event_t event)
|
||||||
|
{
|
||||||
|
// rcl_action_goal_event_handler ** transition_map = get_state_transition_map();
|
||||||
|
rcl_action_goal_event_handler handler = _goal_state_transition_map[state][event];
|
||||||
|
if (NULL == handler) {
|
||||||
|
return GOAL_STATE_UNKNOWN;
|
||||||
|
}
|
||||||
|
return handler(state, event);
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // RCL_ACTION__GOAL_STATE_MACHINE_H_
|
62
rcl_action/include/rcl_action/rcl_action.h
Normal file
62
rcl_action/include/rcl_action/rcl_action.h
Normal file
|
@ -0,0 +1,62 @@
|
||||||
|
// Copyright 2018 Open Source Robotics Foundation, Inc.
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
/** \mainpage rcl: Common functionality ROS actions
|
||||||
|
*
|
||||||
|
* `rcl_action` provides a pure C implementation of the ROS concept an \b action.
|
||||||
|
* It builds on top of the implementation of topics and services in `rcl`.
|
||||||
|
*
|
||||||
|
* `rcl_action` consists of functions and structs following ROS action entities:
|
||||||
|
*
|
||||||
|
* - Action client
|
||||||
|
* - rcl_action/action_client.h
|
||||||
|
* - Action server
|
||||||
|
* - rcl_action/action_server.h
|
||||||
|
* - Goal handle
|
||||||
|
* - rcl_action/goal_handle.h
|
||||||
|
* - Goal state machine
|
||||||
|
* - rcl_action/goal_state_machine.h
|
||||||
|
*
|
||||||
|
* It also has some machinery that is necessary to wait on and act on these entities:
|
||||||
|
*
|
||||||
|
* - Wait sets for waiting on actions clients and action servers to be ready
|
||||||
|
* - rcl_action/wait.h
|
||||||
|
*
|
||||||
|
* Some useful abstractions and utilities:
|
||||||
|
*
|
||||||
|
* - Return codes and other types
|
||||||
|
* - rcl_action/types.h
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef RCL_ACTION__RCL_ACTION_H_
|
||||||
|
#define RCL_ACTION__RCL_ACTION_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "rcl_action/action_client.h"
|
||||||
|
#include "rcl_action/action_server.h"
|
||||||
|
#include "rcl_action/default_qos.h"
|
||||||
|
#include "rcl_action/goal_handle.h"
|
||||||
|
#include "rcl_action/goal_state_machine.h"
|
||||||
|
#include "rcl_action/types.h"
|
||||||
|
#include "rcl_action/wait.h"
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // RCL_ACTION__RCL_ACTION_H_
|
356
rcl_action/include/rcl_action/types.h
Normal file
356
rcl_action/include/rcl_action/types.h
Normal file
|
@ -0,0 +1,356 @@
|
||||||
|
// Copyright 2018 Open Source Robotics Foundation, Inc.
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#ifndef RCL_ACTION__TYPES_H_
|
||||||
|
#define RCL_ACTION__TYPES_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "action_msgs/msg/goal_info.h"
|
||||||
|
#include "action_msgs/msg/goal_status.h"
|
||||||
|
#include "action_msgs/msg/goal_status_array.h"
|
||||||
|
#include "action_msgs/srv/cancel_goal.h"
|
||||||
|
|
||||||
|
#include "rcl/macros.h"
|
||||||
|
#include "rcl/types.h"
|
||||||
|
#include "rcl/visibility_control.h"
|
||||||
|
|
||||||
|
|
||||||
|
// rcl action specific ret codes in 2XXX
|
||||||
|
/// Action name does not pass validation return code.
|
||||||
|
#define RCL_RET_ACTION_NAME_INVALID 2000
|
||||||
|
/// Action goal accepted return code.
|
||||||
|
#define RCL_RET_ACTION_GOAL_ACCEPTED 2100
|
||||||
|
/// Action goal rejected return code.
|
||||||
|
#define RCL_RET_ACTION_GOAL_REJECTED 2101
|
||||||
|
/// Action client is invalid return code.
|
||||||
|
#define RCL_RET_ACTION_CLIENT_INVALID 2102
|
||||||
|
/// Action client failed to take response return code.
|
||||||
|
#define RCL_RET_ACTION_CLIENT_TAKE_FAILED 2103
|
||||||
|
/// Action server is invalid return code.
|
||||||
|
#define RCL_RET_ACTION_SERVER_INVALID 2200
|
||||||
|
/// Action server failed to take request return code.
|
||||||
|
#define RCL_RET_ACTION_SERVER_TAKE_FAILED 2201
|
||||||
|
/// Action goal handle invalid return code.
|
||||||
|
#define RCL_RET_ACTION_GOAL_HANDLE_INVALID 2300
|
||||||
|
/// Action invalid event return code.
|
||||||
|
#define RCL_RET_ACTION_GOAL_EVENT_INVALID 2301
|
||||||
|
|
||||||
|
// Forward declare
|
||||||
|
typedef struct rcl_action_server_t rcl_action_server_t;
|
||||||
|
|
||||||
|
// Typedef generated messages for convenience
|
||||||
|
typedef action_msgs__msg__GoalInfo rcl_action_goal_info_t;
|
||||||
|
typedef action_msgs__msg__GoalStatusArray rcl_action_goal_status_array_t;
|
||||||
|
typedef action_msgs__srv__CancelGoal_Request rcl_action_cancel_request_t;
|
||||||
|
typedef action_msgs__srv__CancelGoal_Response rcl_action_cancel_response_t;
|
||||||
|
|
||||||
|
/// Goal states
|
||||||
|
// TODO(jacobperron): Let states be defined by action_msgs/msg/goal_status.h
|
||||||
|
// Ideally, we could use an enum type directly from the message when the feature
|
||||||
|
// is available. Issue: https://github.com/ros2/rosidl/issues/260
|
||||||
|
typedef int8_t rcl_action_goal_state_t;
|
||||||
|
#define GOAL_STATE_UNKNOWN action_msgs__msg__GoalStatus__STATUS_UNKNOWN
|
||||||
|
#define GOAL_STATE_ACCEPTED action_msgs__msg__GoalStatus__STATUS_ACCEPTED
|
||||||
|
#define GOAL_STATE_EXECUTING action_msgs__msg__GoalStatus__STATUS_EXECUTING
|
||||||
|
#define GOAL_STATE_CANCELING action_msgs__msg__GoalStatus__STATUS_CANCELING
|
||||||
|
#define GOAL_STATE_SUCCEEDED action_msgs__msg__GoalStatus__STATUS_SUCCEEDED
|
||||||
|
#define GOAL_STATE_CANCELED action_msgs__msg__GoalStatus__STATUS_CANCELED
|
||||||
|
#define GOAL_STATE_ABORTED action_msgs__msg__GoalStatus__STATUS_ABORTED
|
||||||
|
#define GOAL_STATE_NUM_STATES 6 // not counting `UNKNOWN`
|
||||||
|
|
||||||
|
/// Goal state transition events
|
||||||
|
typedef enum rcl_action_goal_event_t
|
||||||
|
{
|
||||||
|
GOAL_EVENT_EXECUTE = 0,
|
||||||
|
GOAL_EVENT_CANCEL,
|
||||||
|
GOAL_EVENT_SET_SUCCEEDED,
|
||||||
|
GOAL_EVENT_SET_ABORTED,
|
||||||
|
GOAL_EVENT_SET_CANCELED,
|
||||||
|
GOAL_EVENT_NUM_EVENTS
|
||||||
|
} rcl_action_goal_event_t;
|
||||||
|
|
||||||
|
/// Return a rcl_action_goal_info_t with members set to `NULL`.
|
||||||
|
/**
|
||||||
|
* Should be called to get a null rcl_action_goal_info_t before passing to
|
||||||
|
* rcl_action_goal_info_init().
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_action_goal_info_t
|
||||||
|
rcl_action_get_zero_initialized_goal_info(void);
|
||||||
|
|
||||||
|
/// Initialize a rcl_action_goal_info_t.
|
||||||
|
/**
|
||||||
|
* After calling this function on a rcl_action_goal_info_t, it can be populated
|
||||||
|
* and used to accept goal requests with rcl_action_accept_new_goal().
|
||||||
|
*
|
||||||
|
* The given rcl_action_server_t must be valid and the resulting
|
||||||
|
* rcl_action_goal_info_t is only valid as long as the given rcl_action_server_t
|
||||||
|
* remains valid.
|
||||||
|
*
|
||||||
|
* Expected usage (for C action servers):
|
||||||
|
*
|
||||||
|
* ```c
|
||||||
|
* #include <rcl_action/rcl_action.h>
|
||||||
|
*
|
||||||
|
* // ... init action server
|
||||||
|
* rcl_action_goal_info_t goal_info = rcl_action_get_zero_initialized_goal_info();
|
||||||
|
* ret = rcl_action_goal_info_init(&goal_info, &action_server);
|
||||||
|
* // ... error handling, and when done with the goal info message, finalize
|
||||||
|
* ret = rcl_action_goal_info_fini(&goal_info, &action_server);
|
||||||
|
* // ... error handling
|
||||||
|
* ```
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[out] goal_info a preallocated, zero-initialized, goal info message
|
||||||
|
* to be initialized.
|
||||||
|
* \param[in] action_server a valid action server handle
|
||||||
|
* \return `RCL_RET_OK` if goal info was initialized successfully, or
|
||||||
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
|
* \return `RCL_RET_ACTION_SERVER_INVALID` if the action server is invalid, or
|
||||||
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_goal_info_init(
|
||||||
|
rcl_action_goal_info_t * goal_info,
|
||||||
|
const rcl_action_server_t * action_server);
|
||||||
|
|
||||||
|
/// Finalize a rcl_action_goal_info_t.
|
||||||
|
/**
|
||||||
|
* After calling, the goal info message will no longer be valid.
|
||||||
|
* However, the given action server handle is still valid.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[inout] goal_info the goal info message to be deinitialized
|
||||||
|
* \param[in] action_server handle to the action sever used to create the goal info message
|
||||||
|
* \return `RCL_RET_OK` if the goal info message 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 is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_goal_info_fini(
|
||||||
|
rcl_action_goal_info_t * goal_info,
|
||||||
|
const rcl_action_server_t * action_server);
|
||||||
|
|
||||||
|
/// Return a rcl_action_goal_status_array_t with members set to `NULL`.
|
||||||
|
/**
|
||||||
|
* Should be called to get a null rcl_action_goal_status_array_t before passing to
|
||||||
|
* rcl_action_server_get_goal_status_array().
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_action_goal_status_array_t
|
||||||
|
rcl_action_get_zero_initialized_goal_status_array(void);
|
||||||
|
|
||||||
|
/// Return a rcl_action_cancel_request_t with members set to `NULL`.
|
||||||
|
/**
|
||||||
|
* Should be called to get a null rcl_action_cancel_request_t before passing to
|
||||||
|
*
|
||||||
|
* rcl_action_cancel_request_init().
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_action_cancel_request_t
|
||||||
|
rcl_action_get_zero_initialized_cancel_request(void);
|
||||||
|
|
||||||
|
/// Initialize a rcl_action_cancel_request_t.
|
||||||
|
/**
|
||||||
|
* After calling this function on a rcl_action_cancel_request_t, it can be populated
|
||||||
|
* and used to process cancel requests with an action server using
|
||||||
|
* rcl_action_process_cancel_request().
|
||||||
|
*
|
||||||
|
* The given rcl_action_server_t must be valid and the resulting
|
||||||
|
* rcl_action_cancel_request_t is only valid as long as the given rcl_action_server_t
|
||||||
|
* remains valid.
|
||||||
|
*
|
||||||
|
* Expected usage (for C action servers):
|
||||||
|
*
|
||||||
|
* ```c
|
||||||
|
* #include <rcl/rcl.h>
|
||||||
|
* #include <rcl_action/rcl_action.h>
|
||||||
|
*
|
||||||
|
* // ... init action server
|
||||||
|
* rcl_action_cancel_request_t cancel_request = rcl_action_get_zero_initialized_cancel_request();
|
||||||
|
* ret = rcl_action_cancel_request_init(&cancel_request, &action_server);
|
||||||
|
* // ... error handling, and when done processing request, finalize
|
||||||
|
* ret = rcl_action_cancel_request_fini(&cancel_request, &action_server);
|
||||||
|
* // ... error handling
|
||||||
|
* ```
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[out] cancel_request a preallocated, zero-initialized, cancel request message
|
||||||
|
* to be initialized.
|
||||||
|
* \param[in] action_server a valid action server handle
|
||||||
|
* \return `RCL_RET_OK` if cancel request was initialized successfully, or
|
||||||
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
|
* \return `RCL_RET_ACTION_SERVER_INVALID` if the action server is invalid, or
|
||||||
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_cancel_request_init(
|
||||||
|
rcl_action_cancel_request_t * cancel_request,
|
||||||
|
const rcl_action_server_t * action_server);
|
||||||
|
|
||||||
|
/// Finalize a rcl_action_cancel_request_t.
|
||||||
|
/**
|
||||||
|
* After calling, the cancel request message will no longer be valid.
|
||||||
|
* However, the given action server handle is still valid.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[inout] cancel_request the cancel request message to be deinitialized
|
||||||
|
* \param[in] action_server handle to the action sever used to create the cancel request
|
||||||
|
* \return `RCL_RET_OK` if the cancel request 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 is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_cancel_request_fini(
|
||||||
|
rcl_action_cancel_request_t * cancel_request,
|
||||||
|
const rcl_action_server_t * action_server);
|
||||||
|
|
||||||
|
/// Return a rcl_action_cancel_response_t with members set to `NULL`.
|
||||||
|
/**
|
||||||
|
* Should be called to get a null rcl_action_cancel_response_t before passing to
|
||||||
|
* rcl_action_cancel_response_init().
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_action_cancel_response_t
|
||||||
|
rcl_action_get_zero_initialized_cancel_response(void);
|
||||||
|
|
||||||
|
/// Initialize a rcl_action_cancel_response_t.
|
||||||
|
/**
|
||||||
|
* After calling this function on a rcl_action_cancel_response_t, it can be populated
|
||||||
|
* and used to process cancel requests with an action server using
|
||||||
|
* rcl_action_process_cancel_request().
|
||||||
|
*
|
||||||
|
* The given rcl_action_server_t must be valid and the resulting
|
||||||
|
* rcl_action_cancel_response_t is only valid as long as the given rcl_action_server_t
|
||||||
|
* remains valid.
|
||||||
|
*
|
||||||
|
* Expected usage (for C action servers):
|
||||||
|
*
|
||||||
|
* ```c
|
||||||
|
* #include <rcl/rcl.h>
|
||||||
|
* #include <rcl_action/rcl_action.h>
|
||||||
|
*
|
||||||
|
* // ... init action server
|
||||||
|
* rcl_action_cancel_response_t cancel_response =
|
||||||
|
* rcl_action_get_zero_initialized_cancel_response();
|
||||||
|
* ret = rcl_action_cancel_response_init(&cancel_response, &action_server);
|
||||||
|
* // ... error handling, and when done processing response, finalize
|
||||||
|
* ret = rcl_action_cancel_response_fini(&cancel_response, &action_server);
|
||||||
|
* // ... error handling
|
||||||
|
* ```
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[out] cancel_response a preallocated, zero-initialized, cancel response message
|
||||||
|
* to be initialized.
|
||||||
|
* \param[in] action_server a valid action server handle
|
||||||
|
* \return `RCL_RET_OK` if cancel response was initialized successfully, or
|
||||||
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
|
* \return `RCL_RET_ACTION_SERVER_INVALID` if the action server is invalid, or
|
||||||
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_cancel_response_init(
|
||||||
|
rcl_action_cancel_response_t * cancel_response,
|
||||||
|
const rcl_action_server_t * action_server);
|
||||||
|
|
||||||
|
/// Finalize a rcl_action_cancel_response_t.
|
||||||
|
/**
|
||||||
|
* After calling, the cancel response message will no longer be valid.
|
||||||
|
* However, the given action server handle is still valid.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[inout] cancel_response the cancel response message to be deinitialized
|
||||||
|
* \param[in] action_server handle to the action sever used to create the cancel response
|
||||||
|
* \return `RCL_RET_OK` if the cancel response 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 is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_cancel_response_fini(
|
||||||
|
rcl_action_cancel_response_t * cancel_response,
|
||||||
|
rcl_action_server_t * action_server);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // RCL_ACTION__TYPES_H_
|
257
rcl_action/include/rcl_action/wait.h
Normal file
257
rcl_action/include/rcl_action/wait.h
Normal file
|
@ -0,0 +1,257 @@
|
||||||
|
// Copyright 2018 Open Source Robotics Foundation, Inc.
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#ifndef RCL_ACTION__WAIT_H_
|
||||||
|
#define RCL_ACTION__WAIT_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "rcl_action/action_client.h"
|
||||||
|
#include "rcl_action/action_server.h"
|
||||||
|
#include "rcl/wait.h"
|
||||||
|
|
||||||
|
|
||||||
|
/// Add a rcl_action_client_t to a wait set.
|
||||||
|
/**
|
||||||
|
* This function will add the underlying service clients and subscriber to the wait set.
|
||||||
|
*
|
||||||
|
* This function behaves similar to adding subscriptions to the wait set, but will add
|
||||||
|
* four elements:
|
||||||
|
*
|
||||||
|
* - Three service clients
|
||||||
|
* - One subscriber
|
||||||
|
*
|
||||||
|
* \see rcl_wait_set_add_subscription
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[inout] wait_set struct where action client service client and subscription
|
||||||
|
* are to be stored
|
||||||
|
* \param[in] action_client the action client to be added to the wait set
|
||||||
|
* \return `RCL_RET_OK` if added successfully, or
|
||||||
|
* \return `RCL_RET_WAIT_SET_INVALID` if the wait set is zero initialized, or
|
||||||
|
* \return `RCL_RET_WAIT_SET_FULL` if the subscription set is full, or
|
||||||
|
* \return `RCL_RET_ACTION_CLIENT_INVALID` if the action client is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_wait_set_add_action_client(
|
||||||
|
rcl_wait_set_t * wait_set,
|
||||||
|
const rcl_action_client_t * action_client);
|
||||||
|
|
||||||
|
/// Add a rcl_action_server_t to a wait set.
|
||||||
|
/**
|
||||||
|
* This function will add the underlying services to the wait set.
|
||||||
|
*
|
||||||
|
* This function behaves similar to adding services to the wait set, but will add
|
||||||
|
* three services.
|
||||||
|
*
|
||||||
|
* \see rcl_wait_set_add_service
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[inout] wait_set struct where action server services are to be stored
|
||||||
|
* \param[in] action_server the action server to be added to the wait set
|
||||||
|
* \return `RCL_RET_OK` if added successfully, or
|
||||||
|
* \return `RCL_RET_WAIT_SET_INVALID` if the wait set is zero initialized, or
|
||||||
|
* \return `RCL_RET_WAIT_SET_FULL` if the subscription set is full, or
|
||||||
|
* \return `RCL_RET_ACTION_SERVER_INVALID` if the action server is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_wait_set_add_action_server(
|
||||||
|
rcl_wait_set_t * wait_set,
|
||||||
|
const rcl_action_server_t * action_server);
|
||||||
|
|
||||||
|
/// Get the number of wait set entities associated with a rcl_action_client_t.
|
||||||
|
/**
|
||||||
|
* Returns the number of entities that are added to the wait set if
|
||||||
|
* rcl_action_wait_set_add_action_client() is called.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_client an action client to query
|
||||||
|
* \param[out] num_subscriptions the number of subscriptions added when the action client
|
||||||
|
* is added to the wait set
|
||||||
|
* \param[out] num_guard_conditions the number of guard conditions added when the action client
|
||||||
|
* is added to the wait set
|
||||||
|
* \param[out] num_timers the number of timers added when the action client
|
||||||
|
* is added to the wait set
|
||||||
|
* \param[out] num_clients the number of clients added when the action client
|
||||||
|
* is added to the wait set
|
||||||
|
* \param[out] num_services the number of services added when the action client
|
||||||
|
* is added to the wait set
|
||||||
|
* \return `RCL_RET_OK` if call is successful, 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_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_client_wait_set_get_num_entities(
|
||||||
|
const rcl_action_client_t * action_client,
|
||||||
|
size_t * num_subscriptions,
|
||||||
|
size_t * num_guard_conditions,
|
||||||
|
size_t * num_timers,
|
||||||
|
size_t * num_clients,
|
||||||
|
size_t * num_services);
|
||||||
|
|
||||||
|
/// Get the number of wait set entities associated with a rcl_action_server_t.
|
||||||
|
/**
|
||||||
|
* Returns the number of entities that are added to the wait set if
|
||||||
|
* rcl_action_wait_set_add_action_server() is called.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_server an action server to query
|
||||||
|
* \param[out] num_subscriptions the number of subscriptions added when the action server
|
||||||
|
* is added to the wait set
|
||||||
|
* \param[out] num_guard_conditions the number of guard conditions added when the action server
|
||||||
|
* is added to the wait set
|
||||||
|
* \param[out] num_timers the number of timers added when the action server
|
||||||
|
* is added to the wait set
|
||||||
|
* \param[out] num_clients the number of clients added when the action server
|
||||||
|
* is added to the wait set
|
||||||
|
* \param[out] num_services the number of services added when the action server
|
||||||
|
* is added to the wait set
|
||||||
|
* \return `RCL_RET_OK` if call is successful, or
|
||||||
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
|
* \return `RCL_RET_ACTION_SERVER_INVALID` if the action server is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_server_wait_set_get_num_entities(
|
||||||
|
const rcl_action_server_t * action_server,
|
||||||
|
size_t * num_subscriptions,
|
||||||
|
size_t * num_guard_conditions,
|
||||||
|
size_t * num_timers,
|
||||||
|
size_t * num_clients,
|
||||||
|
size_t * num_services);
|
||||||
|
|
||||||
|
/// Get the wait set entities that are ready for a rcl_action_client_t.
|
||||||
|
/**
|
||||||
|
* The caller can use this function to determine the relevant action client functions
|
||||||
|
* to call: rcl_action_take_feedback(), rcl_action_take_status(),
|
||||||
|
* rcl_action_take_goal_response(), rcl_action_take_cancel_response(), or
|
||||||
|
* rcl_action_take_result_response().
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_client an action client to query
|
||||||
|
* \param[out] is_feedback_ready `true` if there is a feedback message ready to take,
|
||||||
|
* `false` otherwise
|
||||||
|
* \param[out] is_status_message `true` if there is a status message ready to take,
|
||||||
|
* `false` otherwise
|
||||||
|
* \param[out] is_goal_response_ready `true` if there is a goal response message ready
|
||||||
|
* to take, `false` otherwise
|
||||||
|
* \param[out] is_cancel_response_ready `true` if there is a cancel response message ready
|
||||||
|
* to take, `false` otherwise
|
||||||
|
* \param[out] is_result_response_ready `true` if there is a result response message ready
|
||||||
|
* to take, `false` otherwise
|
||||||
|
* \return `RCL_RET_OK` if call is successful, 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_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_client_wait_set_get_entities_ready(
|
||||||
|
const rcl_wait_set_t * wait_set,
|
||||||
|
const rcl_action_client_t * action_client,
|
||||||
|
bool * is_feedback_ready,
|
||||||
|
bool * is_status_ready,
|
||||||
|
bool * is_goal_response_ready,
|
||||||
|
bool * is_cancel_response_ready,
|
||||||
|
bool * is_result_response_ready);
|
||||||
|
|
||||||
|
/// Get the wait set entities that are ready for a rcl_action_server_t.
|
||||||
|
/**
|
||||||
|
* The caller can use this function to determine the relevant action server functions
|
||||||
|
* to call: rcl_action_take_goal_request(), rcl_action_take_cancel_request(), or
|
||||||
|
* rcl_action_take_result_request().
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] action_server an action server to query
|
||||||
|
* \param[out] is_goal_request_ready `true` if there is a goal request message ready
|
||||||
|
* to take, `false` otherwise
|
||||||
|
* \param[out] is_cancel_request_ready `true` if there is a cancel request message ready
|
||||||
|
* to take, `false` otherwise
|
||||||
|
* \param[out] is_result_request_ready `true` if there is a result request message ready
|
||||||
|
* to take, `false` otherwise
|
||||||
|
* \return `RCL_RET_OK` if call is successful, or
|
||||||
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
|
* \return `RCL_RET_ACTION_CLIENT_INVALID` if the action server is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_action_server_wait_set_get_entities_ready(
|
||||||
|
const rcl_wait_set_t * wait_set,
|
||||||
|
const rcl_action_server_t * action_server,
|
||||||
|
bool * is_goal_request_ready,
|
||||||
|
bool * is_cancel_request_ready,
|
||||||
|
bool * is_result_request_ready);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // RCL_ACTION__WAIT_H_
|
31
rcl_action/package.xml
Normal file
31
rcl_action/package.xml
Normal file
|
@ -0,0 +1,31 @@
|
||||||
|
<?xml version="1.0"?>
|
||||||
|
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||||
|
<package format="2">
|
||||||
|
<name>rcl_action</name>
|
||||||
|
<version>0.5.0</version>
|
||||||
|
<description>Package containing a C-based ROS action implementation</description>
|
||||||
|
<maintainer email="jacob@openrobotics.org">Jacob Perron</maintainer>
|
||||||
|
<license>Apache License 2.0</license>
|
||||||
|
|
||||||
|
<buildtool_depend>ament_cmake_ros</buildtool_depend>
|
||||||
|
|
||||||
|
<build_depend>action_msgs</build_depend>
|
||||||
|
<build_depend>rcl</build_depend>
|
||||||
|
<build_depend>rcutils</build_depend>
|
||||||
|
<build_depend>rmw_implementation</build_depend>
|
||||||
|
<build_depend>rosidl_generator_c</build_depend>
|
||||||
|
|
||||||
|
<exec_depend>action_msgs</exec_depend>
|
||||||
|
<exec_depend>rcl</exec_depend>
|
||||||
|
<exec_depend>rcutils</exec_depend>
|
||||||
|
<exec_depend>rmw_implementation</exec_depend>
|
||||||
|
<exec_depend>rosidl_generator_c</exec_depend>
|
||||||
|
|
||||||
|
<test_depend>ament_cmake_gtest</test_depend>
|
||||||
|
<test_depend>ament_lint_common</test_depend>
|
||||||
|
<test_depend>ament_lint_auto</test_depend>
|
||||||
|
|
||||||
|
<export>
|
||||||
|
<build_type>ament_cmake</build_type>
|
||||||
|
</export>
|
||||||
|
</package>
|
21
rcl_action/src/test_compile_headers.c
Normal file
21
rcl_action/src/test_compile_headers.c
Normal file
|
@ -0,0 +1,21 @@
|
||||||
|
// Copyright 2018 Open Source Robotics Foundation, Inc.
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#include "rcl_action/rcl_action.h"
|
||||||
|
|
||||||
|
|
||||||
|
int main(void)
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
Loading…
Add table
Add a link
Reference in a new issue