rename {c_}utilities to rcutils (#130)
This commit is contained in:
parent
f9e03e51bb
commit
bed40d3d40
10 changed files with 55 additions and 50 deletions
|
@ -3,8 +3,9 @@ cmake_minimum_required(VERSION 3.5)
|
||||||
project(rcl)
|
project(rcl)
|
||||||
|
|
||||||
find_package(ament_cmake_ros REQUIRED)
|
find_package(ament_cmake_ros REQUIRED)
|
||||||
find_package(c_utilities REQUIRED)
|
|
||||||
find_package(rcl_interfaces REQUIRED)
|
find_package(rcl_interfaces REQUIRED)
|
||||||
|
find_package(rcutils REQUIRED)
|
||||||
find_package(rmw REQUIRED)
|
find_package(rmw REQUIRED)
|
||||||
find_package(rmw_implementation REQUIRED)
|
find_package(rmw_implementation REQUIRED)
|
||||||
find_package(rosidl_generator_c REQUIRED)
|
find_package(rosidl_generator_c REQUIRED)
|
||||||
|
@ -41,8 +42,8 @@ set(${PROJECT_NAME}_sources
|
||||||
|
|
||||||
add_library(${PROJECT_NAME} ${${PROJECT_NAME}_sources})
|
add_library(${PROJECT_NAME} ${${PROJECT_NAME}_sources})
|
||||||
ament_target_dependencies(${PROJECT_NAME}
|
ament_target_dependencies(${PROJECT_NAME}
|
||||||
"c_utilities"
|
|
||||||
"rcl_interfaces"
|
"rcl_interfaces"
|
||||||
|
"rcutils"
|
||||||
"rmw"
|
"rmw"
|
||||||
"rmw_implementation"
|
"rmw_implementation"
|
||||||
"rosidl_generator_c"
|
"rosidl_generator_c"
|
||||||
|
@ -65,8 +66,8 @@ install(
|
||||||
set(rcl_lib_dir "$<TARGET_FILE_DIR:${PROJECT_NAME}>")
|
set(rcl_lib_dir "$<TARGET_FILE_DIR:${PROJECT_NAME}>")
|
||||||
|
|
||||||
ament_export_dependencies(ament_cmake)
|
ament_export_dependencies(ament_cmake)
|
||||||
ament_export_dependencies(c_utilities)
|
|
||||||
ament_export_dependencies(rcl_interfaces)
|
ament_export_dependencies(rcl_interfaces)
|
||||||
|
ament_export_dependencies(rcutils)
|
||||||
ament_export_dependencies(rmw)
|
ament_export_dependencies(rmw)
|
||||||
ament_export_dependencies(rmw_implementation)
|
ament_export_dependencies(rmw_implementation)
|
||||||
ament_export_dependencies(rosidl_generator_c)
|
ament_export_dependencies(rosidl_generator_c)
|
||||||
|
|
|
@ -20,13 +20,13 @@ extern "C"
|
||||||
{
|
{
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "c_utilities/allocator.h"
|
#include "rcutils/allocator.h"
|
||||||
|
|
||||||
typedef utilities_allocator_t rcl_allocator_t;
|
typedef rcutils_allocator_t rcl_allocator_t;
|
||||||
|
|
||||||
#define rcl_get_default_allocator utilities_get_default_allocator
|
#define rcl_get_default_allocator rcutils_get_default_allocator
|
||||||
|
|
||||||
#define rcl_reallocf utilities_reallocf
|
#define rcl_reallocf rcutils_reallocf
|
||||||
|
|
||||||
#if __cplusplus
|
#if __cplusplus
|
||||||
}
|
}
|
||||||
|
|
|
@ -15,9 +15,9 @@
|
||||||
#ifndef RCL__ERROR_HANDLING_H_
|
#ifndef RCL__ERROR_HANDLING_H_
|
||||||
#define RCL__ERROR_HANDLING_H_
|
#define RCL__ERROR_HANDLING_H_
|
||||||
|
|
||||||
#include "c_utilities/error_handling.h"
|
#include "rcutils/error_handling.h"
|
||||||
|
|
||||||
/// The error handling in RCL is just an alias to the error handling in c_utilities.
|
/// The error handling in RCL is just an alias to the error handling in rcutils.
|
||||||
/**
|
/**
|
||||||
* Allocators given to functions in rcl are passed along to the error handling
|
* Allocators given to functions in rcl are passed along to the error handling
|
||||||
* on a "best effort" basis.
|
* on a "best effort" basis.
|
||||||
|
@ -29,20 +29,20 @@
|
||||||
* occur during normal runtime, is should be okay to use the default allocator.
|
* occur during normal runtime, is should be okay to use the default allocator.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
typedef utilities_error_state_t rcl_error_state_t;
|
typedef rcutils_error_state_t rcl_error_state_t;
|
||||||
|
|
||||||
#define rcl_set_error_state utilities_set_error_state
|
#define rcl_set_error_state rcutils_set_error_state
|
||||||
|
|
||||||
#define RCL_SET_ERROR_MSG(msg, allocator) UTILITIES_SET_ERROR_MSG(msg, allocator)
|
#define RCL_SET_ERROR_MSG(msg, allocator) RCUTILS_SET_ERROR_MSG(msg, allocator)
|
||||||
|
|
||||||
#define rcl_error_is_set utilities_error_is_set
|
#define rcl_error_is_set rcutils_error_is_set
|
||||||
|
|
||||||
#define rcl_get_error_state utilities_get_error_state
|
#define rcl_get_error_state rcutils_get_error_state
|
||||||
|
|
||||||
#define rcl_get_error_string utilities_get_error_string
|
#define rcl_get_error_string rcutils_get_error_string
|
||||||
|
|
||||||
#define rcl_get_error_string_safe utilities_get_error_string_safe
|
#define rcl_get_error_string_safe rcutils_get_error_string_safe
|
||||||
|
|
||||||
#define rcl_reset_error utilities_reset_error
|
#define rcl_reset_error rcutils_reset_error
|
||||||
|
|
||||||
#endif // RCL__ERROR_HANDLING_H_
|
#endif // RCL__ERROR_HANDLING_H_
|
||||||
|
|
|
@ -23,7 +23,7 @@ extern "C"
|
||||||
#include <rmw/rmw.h>
|
#include <rmw/rmw.h>
|
||||||
#include <rmw/types.h>
|
#include <rmw/types.h>
|
||||||
|
|
||||||
#include "c_utilities/types.h"
|
#include "rcutils/types.h"
|
||||||
|
|
||||||
#include "rosidl_generator_c/service_type_support.h"
|
#include "rosidl_generator_c/service_type_support.h"
|
||||||
|
|
||||||
|
@ -112,24 +112,24 @@ rcl_destroy_topic_names_and_types(
|
||||||
* The node_names parameter must be allocated and zero initialized.
|
* The node_names parameter must be allocated and zero initialized.
|
||||||
* The node_names is the output for this function, and contains
|
* The node_names is the output for this function, and contains
|
||||||
* allocated memory.
|
* allocated memory.
|
||||||
* Use utilities_get_zero_initialized_string_array() for initializing an empty
|
* Use rcutils_get_zero_initialized_string_array() for initializing an empty
|
||||||
* utilities_string_array_t struct.
|
* rcutils_string_array_t struct.
|
||||||
* This node_names struct should therefore be passed to utilities_string_array_fini()
|
* This node_names struct should therefore be passed to rcutils_string_array_fini()
|
||||||
* when it is no longer needed.
|
* when it is no longer needed.
|
||||||
* Failing to do so will result in leaked memory.
|
* Failing to do so will result in leaked memory.
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
*
|
*
|
||||||
* ```c
|
* ```c
|
||||||
* utilities_string_array_t node_names =
|
* rcutils_string_array_t node_names =
|
||||||
* utilities_get_zero_initialized_string_array();
|
* rcutils_get_zero_initialized_string_array();
|
||||||
* rcl_ret_t ret = rcl_get_node_names(node, &node_names);
|
* rcl_ret_t ret = rcl_get_node_names(node, &node_names);
|
||||||
* if (ret != RCL_RET_OK) {
|
* if (ret != RCL_RET_OK) {
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
* }
|
* }
|
||||||
* // ... use the node_names struct, and when done:
|
* // ... use the node_names struct, and when done:
|
||||||
* utilitiest_ret_t utilities_ret = utilities_string_array_fini(&node_names);
|
* rcutilst_ret_t rcutils_ret = rcutils_string_array_fini(&node_names);
|
||||||
* if (utilities_ret != UTILITIES_RET_OK) {
|
* if (rcutils_ret != RCUTILS_RET_OK) {
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
* }
|
* }
|
||||||
* ```
|
* ```
|
||||||
|
@ -154,7 +154,7 @@ rcl_ret_t
|
||||||
rcl_get_node_names(
|
rcl_get_node_names(
|
||||||
const rcl_node_t * node,
|
const rcl_node_t * node,
|
||||||
rcl_allocator_t allocator,
|
rcl_allocator_t allocator,
|
||||||
utilities_string_array_t * node_names);
|
rcutils_string_array_t * node_names);
|
||||||
|
|
||||||
/// Return the number of publishers on a given topic.
|
/// Return the number of publishers on a given topic.
|
||||||
/**
|
/**
|
||||||
|
|
|
@ -13,15 +13,16 @@
|
||||||
|
|
||||||
<build_export_depend>rmw</build_export_depend>
|
<build_export_depend>rmw</build_export_depend>
|
||||||
|
|
||||||
<build_depend>c_utilities</build_depend>
|
|
||||||
<build_depend>rcl_interfaces</build_depend>
|
<build_depend>rcl_interfaces</build_depend>
|
||||||
|
<build_depend>rcutils</build_depend>
|
||||||
<build_depend>rosidl_generator_c</build_depend>
|
<build_depend>rosidl_generator_c</build_depend>
|
||||||
<build_export_depend>c_utilities</build_export_depend>
|
|
||||||
<build_export_depend>rcl_interfaces</build_export_depend>
|
<build_export_depend>rcl_interfaces</build_export_depend>
|
||||||
|
<build_export_depend>rcutils</build_export_depend>
|
||||||
<build_export_depend>rosidl_generator_c</build_export_depend>
|
<build_export_depend>rosidl_generator_c</build_export_depend>
|
||||||
|
|
||||||
<exec_depend>ament_cmake</exec_depend>
|
<exec_depend>ament_cmake</exec_depend>
|
||||||
<exec_depend>c_utilities</exec_depend>
|
<exec_depend>rcutils</exec_depend>
|
||||||
<exec_depend>rosidl_default_runtime</exec_depend>
|
<exec_depend>rosidl_default_runtime</exec_depend>
|
||||||
|
|
||||||
<depend>rmw_implementation</depend>
|
<depend>rmw_implementation</depend>
|
||||||
|
|
|
@ -17,7 +17,7 @@ extern "C"
|
||||||
{
|
{
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "c_utilities/types.h"
|
#include "rcutils/types.h"
|
||||||
|
|
||||||
#include "rcl/graph.h"
|
#include "rcl/graph.h"
|
||||||
|
|
||||||
|
@ -72,7 +72,7 @@ rcl_ret_t
|
||||||
rcl_get_node_names(
|
rcl_get_node_names(
|
||||||
const rcl_node_t * node,
|
const rcl_node_t * node,
|
||||||
rcl_allocator_t allocator,
|
rcl_allocator_t allocator,
|
||||||
utilities_string_array_t * node_names)
|
rcutils_string_array_t * node_names)
|
||||||
{
|
{
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, allocator);
|
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, allocator);
|
||||||
if (!rcl_node_is_valid(node)) {
|
if (!rcl_node_is_valid(node)) {
|
||||||
|
|
|
@ -17,7 +17,7 @@
|
||||||
#include <chrono>
|
#include <chrono>
|
||||||
#include <thread>
|
#include <thread>
|
||||||
|
|
||||||
#include "c_utilities/types.h"
|
#include "rcutils/types.h"
|
||||||
|
|
||||||
#include "rcl/graph.h"
|
#include "rcl/graph.h"
|
||||||
#include "rcl/rcl.h"
|
#include "rcl/rcl.h"
|
||||||
|
@ -77,16 +77,16 @@ TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names)
|
||||||
|
|
||||||
std::this_thread::sleep_for(1s);
|
std::this_thread::sleep_for(1s);
|
||||||
|
|
||||||
utilities_string_array_t node_names = utilities_get_zero_initialized_string_array();
|
rcutils_string_array_t node_names = rcutils_get_zero_initialized_string_array();
|
||||||
ret = rcl_get_node_names(node1_ptr, node1_options.allocator, &node_names);
|
ret = rcl_get_node_names(node1_ptr, node1_options.allocator, &node_names);
|
||||||
ASSERT_EQ(UTILITIES_RET_OK, ret) << rcl_get_error_string_safe();
|
ASSERT_EQ(RCUTILS_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
|
|
||||||
EXPECT_EQ(size_t(2), node_names.size);
|
EXPECT_EQ(size_t(2), node_names.size);
|
||||||
EXPECT_EQ(0, strcmp(node1_name, node_names.data[0]));
|
EXPECT_EQ(0, strcmp(node1_name, node_names.data[0]));
|
||||||
EXPECT_EQ(0, strcmp(node2_name, node_names.data[1]));
|
EXPECT_EQ(0, strcmp(node2_name, node_names.data[1]));
|
||||||
|
|
||||||
ret = utilities_string_array_fini(&node_names);
|
ret = rcutils_string_array_fini(&node_names);
|
||||||
ASSERT_EQ(UTILITIES_RET_OK, ret);
|
ASSERT_EQ(RCUTILS_RET_OK, ret);
|
||||||
|
|
||||||
ret = rcl_node_fini(node1_ptr);
|
ret = rcl_node_fini(node1_ptr);
|
||||||
delete node1_ptr;
|
delete node1_ptr;
|
||||||
|
|
|
@ -3,10 +3,11 @@ cmake_minimum_required(VERSION 3.5)
|
||||||
project(rcl_lifecycle)
|
project(rcl_lifecycle)
|
||||||
|
|
||||||
find_package(ament_cmake REQUIRED)
|
find_package(ament_cmake REQUIRED)
|
||||||
find_package(c_utilities REQUIRED)
|
|
||||||
find_package(rcl REQUIRED)
|
|
||||||
find_package(rmw REQUIRED)
|
|
||||||
find_package(lifecycle_msgs REQUIRED)
|
find_package(lifecycle_msgs REQUIRED)
|
||||||
|
find_package(rcl REQUIRED)
|
||||||
|
find_package(rcutils REQUIRED)
|
||||||
|
find_package(rmw REQUIRED)
|
||||||
|
|
||||||
include_directories(include)
|
include_directories(include)
|
||||||
|
|
||||||
|
@ -14,7 +15,8 @@ set(rcl_lifecycle_sources
|
||||||
src/com_interface.c
|
src/com_interface.c
|
||||||
src/default_state_machine.c
|
src/default_state_machine.c
|
||||||
src/rcl_lifecycle.c
|
src/rcl_lifecycle.c
|
||||||
src/transition_map.c)
|
src/transition_map.c
|
||||||
|
)
|
||||||
set_source_files_properties(
|
set_source_files_properties(
|
||||||
${rcl_lifecycle_sources}
|
${rcl_lifecycle_sources}
|
||||||
PROPERTIES language "C")
|
PROPERTIES language "C")
|
||||||
|
@ -26,9 +28,10 @@ add_library(
|
||||||
${rcl_lifecycle_sources})
|
${rcl_lifecycle_sources})
|
||||||
|
|
||||||
ament_target_dependencies(rcl_lifecycle
|
ament_target_dependencies(rcl_lifecycle
|
||||||
"c_utilities"
|
|
||||||
"lifecycle_msgs"
|
"lifecycle_msgs"
|
||||||
"rcl")
|
"rcl"
|
||||||
|
"rcutils"
|
||||||
|
)
|
||||||
|
|
||||||
# Causes the visibility macros to use dllexport rather than dllimport,
|
# Causes the visibility macros to use dllexport rather than dllimport,
|
||||||
# which is appropriate when building the dll but not consuming it.
|
# which is appropriate when building the dll but not consuming it.
|
||||||
|
|
|
@ -10,15 +10,15 @@
|
||||||
<buildtool_depend>ament_cmake</buildtool_depend>
|
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||||
<buildtool_depend>rosidl_default_generators</buildtool_depend>
|
<buildtool_depend>rosidl_default_generators</buildtool_depend>
|
||||||
|
|
||||||
<build_depend>c_utilities</build_depend>
|
|
||||||
<build_depend>lifecycle_msgs</build_depend>
|
<build_depend>lifecycle_msgs</build_depend>
|
||||||
<build_depend>rcl</build_depend>
|
<build_depend>rcl</build_depend>
|
||||||
|
<build_depend>rcutils</build_depend>
|
||||||
<build_depend>rmw_implementation</build_depend>
|
<build_depend>rmw_implementation</build_depend>
|
||||||
<build_depend>rosidl_default_generators</build_depend>
|
<build_depend>rosidl_default_generators</build_depend>
|
||||||
|
|
||||||
<exec_depend>c_utilities</exec_depend>
|
|
||||||
<exec_depend>lifecycle_msgs</exec_depend>
|
<exec_depend>lifecycle_msgs</exec_depend>
|
||||||
<exec_depend>rcl</exec_depend>
|
<exec_depend>rcl</exec_depend>
|
||||||
|
<exec_depend>rcutils</exec_depend>
|
||||||
<exec_depend>rmw_implementation</exec_depend>
|
<exec_depend>rmw_implementation</exec_depend>
|
||||||
<exec_depend>rosidl_default_runtime</exec_depend>
|
<exec_depend>rosidl_default_runtime</exec_depend>
|
||||||
|
|
||||||
|
|
|
@ -22,7 +22,7 @@ extern "C"
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
||||||
#include "c_utilities/concat.h"
|
#include "rcutils/concat.h"
|
||||||
|
|
||||||
#include "lifecycle_msgs/msg/transition_event.h"
|
#include "lifecycle_msgs/msg/transition_event.h"
|
||||||
|
|
||||||
|
@ -119,7 +119,7 @@ rcl_lifecycle_com_interface_init(
|
||||||
|
|
||||||
// initialize publisher
|
// initialize publisher
|
||||||
{
|
{
|
||||||
topic_name = utilities_concat(node_name, pub_transition_event_suffix, "__");
|
topic_name = rcutils_concat(node_name, pub_transition_event_suffix, "__");
|
||||||
ret = rcl_lifecycle_validate_topic_name(topic_name);
|
ret = rcl_lifecycle_validate_topic_name(topic_name);
|
||||||
if (ret != RMW_RET_OK) {
|
if (ret != RMW_RET_OK) {
|
||||||
goto fail;
|
goto fail;
|
||||||
|
@ -142,7 +142,7 @@ rcl_lifecycle_com_interface_init(
|
||||||
|
|
||||||
// initialize change state service
|
// initialize change state service
|
||||||
{
|
{
|
||||||
topic_name = utilities_concat(node_name, srv_change_state_suffix, "__");
|
topic_name = rcutils_concat(node_name, srv_change_state_suffix, "__");
|
||||||
ret = rcl_lifecycle_validate_topic_name(topic_name);
|
ret = rcl_lifecycle_validate_topic_name(topic_name);
|
||||||
if (ret != RMW_RET_OK) {
|
if (ret != RMW_RET_OK) {
|
||||||
goto fail;
|
goto fail;
|
||||||
|
@ -162,7 +162,7 @@ rcl_lifecycle_com_interface_init(
|
||||||
|
|
||||||
// initialize get state service
|
// initialize get state service
|
||||||
{
|
{
|
||||||
topic_name = utilities_concat(node_name, srv_get_state_suffix, "__");
|
topic_name = rcutils_concat(node_name, srv_get_state_suffix, "__");
|
||||||
ret = rcl_lifecycle_validate_topic_name(topic_name);
|
ret = rcl_lifecycle_validate_topic_name(topic_name);
|
||||||
if (ret != RMW_RET_OK) {
|
if (ret != RMW_RET_OK) {
|
||||||
goto fail;
|
goto fail;
|
||||||
|
@ -182,7 +182,7 @@ rcl_lifecycle_com_interface_init(
|
||||||
|
|
||||||
// initialize get available states service
|
// initialize get available states service
|
||||||
{
|
{
|
||||||
topic_name = utilities_concat(node_name, srv_get_available_states_suffix, "__");
|
topic_name = rcutils_concat(node_name, srv_get_available_states_suffix, "__");
|
||||||
ret = rcl_lifecycle_validate_topic_name(topic_name);
|
ret = rcl_lifecycle_validate_topic_name(topic_name);
|
||||||
if (ret != RMW_RET_OK) {
|
if (ret != RMW_RET_OK) {
|
||||||
goto fail;
|
goto fail;
|
||||||
|
@ -202,7 +202,7 @@ rcl_lifecycle_com_interface_init(
|
||||||
|
|
||||||
// initialize get available transitions service
|
// initialize get available transitions service
|
||||||
{
|
{
|
||||||
topic_name = utilities_concat(node_name, srv_get_available_transitions_suffix, "__");
|
topic_name = rcutils_concat(node_name, srv_get_available_transitions_suffix, "__");
|
||||||
ret = rcl_lifecycle_validate_topic_name(topic_name);
|
ret = rcl_lifecycle_validate_topic_name(topic_name);
|
||||||
if (ret != RMW_RET_OK) {
|
if (ret != RMW_RET_OK) {
|
||||||
goto fail;
|
goto fail;
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue