Program Listing for File executor.h

Return to documentation for file (include/rclc/executor.h)

// Copyright (c) 2020 - for information on the respective copyright owner
// see the NOTICE file and/or the repository https://github.com/ros2/rclc.
// Copyright 2014 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 RCLC__EXECUTOR_H_
#define RCLC__EXECUTOR_H_

#if __cplusplus
extern "C"
{
#endif

#include <stdio.h>
#include <stdarg.h>

#include <rcl/error_handling.h>
#include <rcutils/logging_macros.h>

#include "rclc/executor_handle.h"
#include "rclc/types.h"
#include "rclc/sleep.h"
#include "rclc/visibility_control.h"

#include "rclc/action_client.h"
#include "rclc/action_server.h"

/* defines the semantics of data communication
   RCLCPP_EXECUTOR - same semantics as in the rclcpp Executor ROS2(Eloquent)
   LET             - logical execution time
*/
typedef enum
{
  RCLCPP_EXECUTOR,
  LET
} rclc_executor_semantics_t;

typedef bool (* rclc_executor_trigger_t)(rclc_executor_handle_t *, unsigned int, void *);

typedef struct
{
  rcl_context_t * context;
  rclc_executor_handle_t * handles;
  size_t max_handles;
  size_t index;
  const rcl_allocator_t * allocator;
  rcl_wait_set_t wait_set;
  rclc_executor_handle_counters_t info;
  uint64_t timeout_ns;
  rcutils_time_point_value_t invocation_time;
  rclc_executor_trigger_t trigger_function;
  void * trigger_object;
  rclc_executor_semantics_t data_comm_semantics;
} rclc_executor_t;

RCLC_PUBLIC
rclc_executor_t
rclc_executor_get_zero_initialized_executor(void);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_init(
  rclc_executor_t * executor,
  rcl_context_t * context,
  const size_t number_of_handles,
  const rcl_allocator_t * allocator);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_set_timeout(
  rclc_executor_t * executor,
  const uint64_t timeout_ns);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_set_semantics(
  rclc_executor_t * executor,
  rclc_executor_semantics_t semantics);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_fini(rclc_executor_t * executor);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_add_subscription(
  rclc_executor_t * executor,
  rcl_subscription_t * subscription,
  void * msg,
  rclc_subscription_callback_t callback,
  rclc_executor_handle_invocation_t invocation);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_add_subscription_with_context(
  rclc_executor_t * executor,
  rcl_subscription_t * subscription,
  void * msg,
  rclc_subscription_callback_with_context_t callback,
  void * context,
  rclc_executor_handle_invocation_t invocation);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_add_timer(
  rclc_executor_t * executor,
  rcl_timer_t * timer);


RCLC_PUBLIC
rcl_ret_t
rclc_executor_add_client(
  rclc_executor_t * executor,
  rcl_client_t * client,
  void * response_msg,
  rclc_client_callback_t callback);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_add_client_with_request_id(
  rclc_executor_t * executor,
  rcl_client_t * client,
  void * response_msg,
  rclc_client_callback_with_request_id_t callback);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_add_service(
  rclc_executor_t * executor,
  rcl_service_t * service,
  void * request_msg,
  void * response_msg,
  rclc_service_callback_t callback);

rcl_ret_t
rclc_executor_add_action_client(
  rclc_executor_t * executor,
  rclc_action_client_t * action_client,
  size_t handles_number,
  void * ros_result_response,
  void * ros_feedback,
  rclc_action_client_goal_callback_t goal_callback,
  rclc_action_client_feedback_callback_t feedback_callback,
  rclc_action_client_result_callback_t result_callback,
  rclc_action_client_cancel_callback_t cancel_callback,
  void * context);

rcl_ret_t
rclc_executor_add_action_server(
  rclc_executor_t * executor,
  rclc_action_server_t * action_server,
  size_t handles_number,
  void * ros_goal_request,
  size_t ros_goal_request_size,
  rclc_action_server_handle_goal_callback_t goal_callback,
  rclc_action_server_handle_cancel_callback_t cancel_callback,
  void * context);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_add_service_with_request_id(
  rclc_executor_t * executor,
  rcl_service_t * service,
  void * request_msg,
  void * response_msg,
  rclc_service_callback_with_request_id_t callback);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_add_service_with_context(
  rclc_executor_t * executor,
  rcl_service_t * service,
  void * request_msg,
  void * response_msg,
  rclc_service_callback_with_context_t callback,
  void * context);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_add_guard_condition(
  rclc_executor_t * executor,
  rcl_guard_condition_t * gc,
  rclc_gc_callback_t callback);


RCLC_PUBLIC
rcl_ret_t
rclc_executor_remove_subscription(
  rclc_executor_t * executor,
  const rcl_subscription_t * subscription);


RCLC_PUBLIC
rcl_ret_t
rclc_executor_remove_timer(
  rclc_executor_t * executor,
  const rcl_timer_t * timer);


RCLC_PUBLIC
rcl_ret_t
rclc_executor_remove_client(
  rclc_executor_t * executor,
  const rcl_client_t * client);


RCLC_PUBLIC
rcl_ret_t
rclc_executor_remove_service(
  rclc_executor_t * executor,
  const rcl_service_t * service);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_remove_guard_condition(
  rclc_executor_t * executor,
  const rcl_guard_condition_t * guard_condition);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_prepare(
  rclc_executor_t * executor);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_spin_some(
  rclc_executor_t * executor,
  const uint64_t timeout_ns);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_spin(rclc_executor_t * executor);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_spin_period(
  rclc_executor_t * executor,
  const uint64_t period);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_spin_one_period(
  rclc_executor_t * executor,
  const uint64_t period);

RCLC_PUBLIC
rcl_ret_t
rclc_executor_set_trigger(
  rclc_executor_t * executor,
  rclc_executor_trigger_t trigger_function,
  void * trigger_object);

RCLC_PUBLIC
bool
rclc_executor_trigger_all(
  rclc_executor_handle_t * handles,
  unsigned int size,
  void * obj);

RCLC_PUBLIC
bool
rclc_executor_trigger_any(
  rclc_executor_handle_t * handles,
  unsigned int size,
  void * obj);

RCLC_PUBLIC
bool
rclc_executor_trigger_always(
  rclc_executor_handle_t * handles,
  unsigned int size,
  void * obj);

RCLC_PUBLIC
bool
rclc_executor_trigger_one(
  rclc_executor_handle_t * handles,
  unsigned int size,
  void * obj);

#if __cplusplus
}
#endif

#endif  // RCLC__EXECUTOR_H_