Switch to one Participant per Context (#515)
Signed-off-by: Ivan Santiago Paunovic <ivanpauno@ekumenlabs.com>
This commit is contained in:
parent
73948da4c5
commit
72ecb5ff43
30 changed files with 1315 additions and 666 deletions
|
@ -37,6 +37,7 @@ set(${PROJECT_NAME}_sources
|
||||||
src/rcl/client.c
|
src/rcl/client.c
|
||||||
src/rcl/common.c
|
src/rcl/common.c
|
||||||
src/rcl/context.c
|
src/rcl/context.c
|
||||||
|
src/rcl/domain_id.c
|
||||||
src/rcl/event.c
|
src/rcl/event.c
|
||||||
src/rcl/expand_topic_name.c
|
src/rcl/expand_topic_name.c
|
||||||
src/rcl/graph.c
|
src/rcl/graph.c
|
||||||
|
@ -53,13 +54,14 @@ set(${PROJECT_NAME}_sources
|
||||||
src/rcl/publisher.c
|
src/rcl/publisher.c
|
||||||
src/rcl/remap.c
|
src/rcl/remap.c
|
||||||
src/rcl/rmw_implementation_identifier_check.c
|
src/rcl/rmw_implementation_identifier_check.c
|
||||||
|
src/rcl/security.c
|
||||||
src/rcl/service.c
|
src/rcl/service.c
|
||||||
src/rcl/subscription.c
|
src/rcl/subscription.c
|
||||||
src/rcl/time.c
|
src/rcl/time.c
|
||||||
src/rcl/timer.c
|
src/rcl/timer.c
|
||||||
|
src/rcl/validate_security_context_name.c
|
||||||
src/rcl/validate_topic_name.c
|
src/rcl/validate_topic_name.c
|
||||||
src/rcl/wait.c
|
src/rcl/wait.c
|
||||||
src/rcl/security_directory.c
|
|
||||||
)
|
)
|
||||||
|
|
||||||
add_library(${PROJECT_NAME} ${${PROJECT_NAME}_sources})
|
add_library(${PROJECT_NAME} ${${PROJECT_NAME}_sources})
|
||||||
|
|
|
@ -42,6 +42,7 @@ typedef struct rcl_arguments_t
|
||||||
#define RCL_PARAM_FILE_FLAG "--params-file"
|
#define RCL_PARAM_FILE_FLAG "--params-file"
|
||||||
#define RCL_REMAP_FLAG "--remap"
|
#define RCL_REMAP_FLAG "--remap"
|
||||||
#define RCL_SHORT_REMAP_FLAG "-r"
|
#define RCL_SHORT_REMAP_FLAG "-r"
|
||||||
|
#define RCL_SECURITY_CONTEXT_FLAG "--security-context"
|
||||||
#define RCL_LOG_LEVEL_FLAG "--log-level"
|
#define RCL_LOG_LEVEL_FLAG "--log-level"
|
||||||
#define RCL_EXTERNAL_LOG_CONFIG_FLAG "--log-config-file"
|
#define RCL_EXTERNAL_LOG_CONFIG_FLAG "--log-config-file"
|
||||||
// To be prefixed with --enable- or --disable-
|
// To be prefixed with --enable- or --disable-
|
||||||
|
|
48
rcl/include/rcl/domain_id.h
Normal file
48
rcl/include/rcl/domain_id.h
Normal file
|
@ -0,0 +1,48 @@
|
||||||
|
// Copyright 2019 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__DOMAIN_ID_H_
|
||||||
|
#define RCL__DOMAIN_ID_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <stddef.h>
|
||||||
|
|
||||||
|
#include "rcl/types.h"
|
||||||
|
#include "rcl/visibility_control.h"
|
||||||
|
#include "rmw/domain_id.h"
|
||||||
|
|
||||||
|
#define RCL_DEFAULT_DOMAIN_ID RMW_DEFAULT_DOMAIN_ID
|
||||||
|
|
||||||
|
extern const char * const RCL_DOMAIN_ID_ENV_VAR;
|
||||||
|
|
||||||
|
/// Determine the default domain ID, based on the environment.
|
||||||
|
/**
|
||||||
|
* \param[out] domain_id Must not be NULL.
|
||||||
|
* \returns RCL_RET_INVALID_ARGUMENT if an argument is invalid, or,
|
||||||
|
* \returns RCL_RET_ERROR in case of an unexpected error, or,
|
||||||
|
* \returns RCL_RET_OK.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_get_default_domain_id(size_t * domain_id);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // RCL__DOMAIN_ID_H_
|
|
@ -429,6 +429,7 @@ rcl_names_and_types_fini(rcl_names_and_types_t * names_and_types);
|
||||||
* \param[out] node_names struct storing discovered node names
|
* \param[out] node_names struct storing discovered node names
|
||||||
* \param[out] node_namesspaces struct storing discovered node namespaces
|
* \param[out] node_namesspaces struct storing discovered node namespaces
|
||||||
* \return `RCL_RET_OK` if the query was successful, or
|
* \return `RCL_RET_OK` if the query was successful, or
|
||||||
|
* \return `RCL_RET_BAD_ALLOC` if an error occurred while allocating memory, or
|
||||||
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
|
@ -440,6 +441,39 @@ rcl_get_node_names(
|
||||||
rcutils_string_array_t * node_names,
|
rcutils_string_array_t * node_names,
|
||||||
rcutils_string_array_t * node_namespaces);
|
rcutils_string_array_t * node_namespaces);
|
||||||
|
|
||||||
|
/// Return a list of available nodes in the ROS graph, including their security context names.
|
||||||
|
/**
|
||||||
|
* An \ref rcl_get_node_names equivalent, but including in its output the security context
|
||||||
|
* name the node is using.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Maybe [1]
|
||||||
|
* <i>[1] RMW implementation in use may need to protect the data structure with a lock</i>
|
||||||
|
*
|
||||||
|
* \param[in] node the handle to the node being used to query the ROS graph
|
||||||
|
* \param[in] allocator used to control allocation and deallocation of names
|
||||||
|
* \param[out] node_names struct storing discovered node names
|
||||||
|
* \param[out] node_namesspaces struct storing discovered node namespaces
|
||||||
|
* \param[out] security_contexts struct storing discovered node security contexts
|
||||||
|
* \return `RCL_RET_OK` if the query was successful, or
|
||||||
|
* \return `RCL_RET_BAD_ALLOC` if an error occurred while allocating memory, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_get_node_names_with_security_contexts(
|
||||||
|
const rcl_node_t * node,
|
||||||
|
rcl_allocator_t allocator,
|
||||||
|
rcutils_string_array_t * node_names,
|
||||||
|
rcutils_string_array_t * node_namespaces,
|
||||||
|
rcutils_string_array_t * security_contexts);
|
||||||
|
|
||||||
/// Return the number of publishers on a given topic.
|
/// Return the number of publishers on a given topic.
|
||||||
/**
|
/**
|
||||||
* The `node` parameter must point to a valid node.
|
* The `node` parameter must point to a valid node.
|
||||||
|
|
|
@ -22,18 +22,22 @@ extern "C"
|
||||||
|
|
||||||
#include "rcl/types.h"
|
#include "rcl/types.h"
|
||||||
#include "rcl/visibility_control.h"
|
#include "rcl/visibility_control.h"
|
||||||
|
#include "rmw/localhost.h"
|
||||||
|
|
||||||
extern const char * const RCL_LOCALHOST_ENV_VAR;
|
extern const char * const RCL_LOCALHOST_ENV_VAR;
|
||||||
|
|
||||||
/// Determine if the user wants to communicate using loopback only.
|
/// Determine if the user wants to communicate using loopback only.
|
||||||
/**
|
/**
|
||||||
* Checks if localhost should be used for network communication checking ROS_LOCALHOST_ONLY env
|
* Checks if localhost should be used for network communication based on environment.
|
||||||
* variable
|
*
|
||||||
* \returns true if ROS_LOCALHOST_ONLY is set and is 1, false otherwise.
|
* \param[out] localhost_only Must not be NULL.
|
||||||
|
* \returns RCL_RET_INVALID_ARGUMENT if an argument is invalid, or
|
||||||
|
* \returns RCL_RET_ERROR if an unexpected error happened, or
|
||||||
|
* \returns RCL_RET_OK.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
bool
|
rcl_ret_t
|
||||||
rcl_localhost_only();
|
rcl_get_localhost_only(rmw_localhost_only_t * localhost_only);
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
}
|
}
|
||||||
|
|
|
@ -336,7 +336,7 @@ rcl_node_get_options(const rcl_node_t * node);
|
||||||
* This function returns the ROS domain ID that the node is in.
|
* This function returns the ROS domain ID that the node is in.
|
||||||
*
|
*
|
||||||
* This function should be used to determine what `domain_id` was used rather
|
* This function should be used to determine what `domain_id` was used rather
|
||||||
* than checking the domin_id field in the node options, because if
|
* than checking the domain_id field in the node options, because if
|
||||||
* `RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID` is used when creating the node then
|
* `RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID` is used when creating the node then
|
||||||
* it is not changed after creation, but this function will return the actual
|
* it is not changed after creation, but this function will return the actual
|
||||||
* `domain_id` used.
|
* `domain_id` used.
|
||||||
|
|
|
@ -23,8 +23,10 @@ extern "C"
|
||||||
#include "rcl/allocator.h"
|
#include "rcl/allocator.h"
|
||||||
#include "rcl/arguments.h"
|
#include "rcl/arguments.h"
|
||||||
|
|
||||||
|
#include "rcl/domain_id.h"
|
||||||
|
|
||||||
/// Constant which indicates that the default domain id should be used.
|
/// Constant which indicates that the default domain id should be used.
|
||||||
#define RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID SIZE_MAX
|
#define RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID RCL_DEFAULT_DOMAIN_ID
|
||||||
|
|
||||||
/// Structure which encapsulates the options for creating a rcl_node_t.
|
/// Structure which encapsulates the options for creating a rcl_node_t.
|
||||||
typedef struct rcl_node_options_t
|
typedef struct rcl_node_options_t
|
||||||
|
|
124
rcl/include/rcl/security.h
Normal file
124
rcl/include/rcl/security.h
Normal file
|
@ -0,0 +1,124 @@
|
||||||
|
// Copyright 2018-2020 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__SECURITY_H_
|
||||||
|
#define RCL__SECURITY_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
#include "rcl/allocator.h"
|
||||||
|
#include "rcl/types.h"
|
||||||
|
#include "rcl/visibility_control.h"
|
||||||
|
#include "rmw/security_options.h"
|
||||||
|
|
||||||
|
#ifndef ROS_SECURITY_DIRECTORY_OVERRIDE
|
||||||
|
# define ROS_SECURITY_DIRECTORY_OVERRIDE "ROS_SECURITY_DIRECTORY_OVERRIDE"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME
|
||||||
|
# define ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME "ROS_SECURITY_ROOT_DIRECTORY"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef ROS_SECURITY_STRATEGY_VAR_NAME
|
||||||
|
# define ROS_SECURITY_STRATEGY_VAR_NAME "ROS_SECURITY_STRATEGY"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef ROS_SECURITY_ENABLE_VAR_NAME
|
||||||
|
# define ROS_SECURITY_ENABLE_VAR_NAME "ROS_SECURITY_ENABLE"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/// Initialize security options from values in the environment variables and given names.
|
||||||
|
/**
|
||||||
|
* Initialize the given security options based on the environment.
|
||||||
|
* For more details:
|
||||||
|
* \sa rcl_security_enabled
|
||||||
|
* \sa rcl_get_enforcement_policy
|
||||||
|
* \sa rcl_get_secure_root
|
||||||
|
*
|
||||||
|
* \param[in] name name used to find the securiy root path.
|
||||||
|
* \param[in] allocator used to do allocations.
|
||||||
|
* \param[out] security_options security options that will be configured according to
|
||||||
|
* the environment.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_get_security_options_from_environment(
|
||||||
|
const char * name,
|
||||||
|
const rcutils_allocator_t * allocator,
|
||||||
|
rmw_security_options_t * security_options);
|
||||||
|
|
||||||
|
/// Check if security has to be used, according to the environment.
|
||||||
|
/**
|
||||||
|
* If `ROS_SECURITY_ENABLE` environment variable is set to "true", `use_security` will be set to
|
||||||
|
* true.
|
||||||
|
*
|
||||||
|
* \param[out] use_security Must not be NULL.
|
||||||
|
* \returns RCL_RET_INVALID_ARGUMENT if an argument is not valid, or
|
||||||
|
* \returns RCL_RET_ERROR if an unexpected error happened, or
|
||||||
|
* \returns RCL_RET_OK.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_security_enabled(bool * use_security);
|
||||||
|
|
||||||
|
/// Get security enforcement policy from the environment.
|
||||||
|
/**
|
||||||
|
* Sets `policy` based on the value of `ROS_SECURITY_STRATEGY` environment variable.
|
||||||
|
* If `ROS_SECURITY_STRATEGY` is "Enforce", `policy` will be `RMW_SECURITY_ENFORCEMENT_ENFORCE`.
|
||||||
|
* If not, `policy` will be `RMW_SECURITY_ENFORCEMENT_PERMISSIVE`.
|
||||||
|
*
|
||||||
|
* \param[out] policy Must not be NULL.
|
||||||
|
* \returns RCL_RET_INVALID_ARGUMENT if an argument is not valid, or
|
||||||
|
* \returns RCL_RET_ERROR if an unexpected error happened, or
|
||||||
|
* \returns RCL_RET_OK.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_get_enforcement_policy(rmw_security_enforcement_policy_t * policy);
|
||||||
|
|
||||||
|
/// Return the secure root given a security context name.
|
||||||
|
/**
|
||||||
|
* Return the security directory associated with the security context name.
|
||||||
|
*
|
||||||
|
* The value of the environment variable `ROS_SECURITY_ROOT_DIRECTORY` is used as a root.
|
||||||
|
* The specific directory to be used, is found from that root using the `name` passed.
|
||||||
|
* E.g. for a context named "/a/b/c" and root "/r", the secure root path will be
|
||||||
|
* "/r/a/b/c", where the delimiter "/" is native for target file system (e.g. "\\" for _WIN32).
|
||||||
|
*
|
||||||
|
* However, this expansion can be overridden by setting the secure directory override environment
|
||||||
|
* (`ROS_SECURITY_DIRECTORY_OVERRIDE`) variable, allowing users to explicitly specify the exact secure
|
||||||
|
* root directory to be utilized.
|
||||||
|
* Such an override is useful for applications where the security context is non-deterministic
|
||||||
|
* before runtime, or when testing and using additional tools that may not otherwise be easily
|
||||||
|
* provisioned.
|
||||||
|
*
|
||||||
|
* \param[in] name validated name (a single token)
|
||||||
|
* \param[in] allocator the allocator to use for allocation
|
||||||
|
* \returns Machine specific (absolute) secure root path or NULL on failure.
|
||||||
|
* Returned pointer must be deallocated by the caller of this function
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
char *
|
||||||
|
rcl_get_secure_root(const char * name, const rcl_allocator_t * allocator);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // RCL__SECURITY_H_
|
|
@ -1,67 +0,0 @@
|
||||||
// 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__SECURITY_DIRECTORY_H_
|
|
||||||
#define RCL__SECURITY_DIRECTORY_H_
|
|
||||||
|
|
||||||
#ifdef __cplusplus
|
|
||||||
extern "C"
|
|
||||||
{
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#include "rcl/allocator.h"
|
|
||||||
#include "rcl/visibility_control.h"
|
|
||||||
|
|
||||||
#ifndef ROS_SECURITY_NODE_DIRECTORY_VAR_NAME
|
|
||||||
#define ROS_SECURITY_NODE_DIRECTORY_VAR_NAME "ROS_SECURITY_NODE_DIRECTORY"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME
|
|
||||||
#define ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME "ROS_SECURITY_ROOT_DIRECTORY"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef ROS_SECURITY_LOOKUP_TYPE_VAR_NAME
|
|
||||||
#define ROS_SECURITY_LOOKUP_TYPE_VAR_NAME "ROS_SECURITY_LOOKUP_TYPE"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/// Return the secure root directory associated with a node given its validated name and namespace.
|
|
||||||
/**
|
|
||||||
* E.g. for a node named "c" in namespace "/a/b", the secure root path will be
|
|
||||||
* "a/b/c", where the delimiter "/" is native for target file system (e.g. "\\" for _WIN32).
|
|
||||||
* If no exact match is found for the node name, a best match would be used instead
|
|
||||||
* (by performing longest-prefix matching).
|
|
||||||
*
|
|
||||||
* However, this expansion can be overridden by setting the secure node directory environment
|
|
||||||
* variable, allowing users to explicitly specify the exact secure root directory to be utilized.
|
|
||||||
* Such an override is useful for where the FQN of a node is non-deterministic before runtime,
|
|
||||||
* or when testing and using additional tools that may not otherwise be easily provisioned.
|
|
||||||
*
|
|
||||||
* \param[in] node_name validated node name (a single token)
|
|
||||||
* \param[in] node_namespace validated, absolute namespace (starting with "/")
|
|
||||||
* \param[in] allocator the allocator to use for allocation
|
|
||||||
* \returns machine specific (absolute) node secure root path or NULL on failure
|
|
||||||
* returned pointer must be deallocated by the caller of this function
|
|
||||||
*/
|
|
||||||
RCL_PUBLIC
|
|
||||||
char * rcl_get_secure_root(
|
|
||||||
const char * node_name,
|
|
||||||
const char * node_namespace,
|
|
||||||
const rcl_allocator_t * allocator
|
|
||||||
);
|
|
||||||
|
|
||||||
#ifdef __cplusplus
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // RCL__SECURITY_DIRECTORY_H_
|
|
91
rcl/include/rcl/validate_security_context_name.h
Normal file
91
rcl/include/rcl/validate_security_context_name.h
Normal file
|
@ -0,0 +1,91 @@
|
||||||
|
// Copyright 2020 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__VALIDATE_SECURITY_CONTEXT_NAME_H_
|
||||||
|
#define RCL__VALIDATE_SECURITY_CONTEXT_NAME_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "rmw/validate_namespace.h"
|
||||||
|
#include "rmw/validate_node_name.h"
|
||||||
|
|
||||||
|
#include "rcl/macros.h"
|
||||||
|
#include "rcl/types.h"
|
||||||
|
#include "rcl/visibility_control.h"
|
||||||
|
|
||||||
|
#define RCL_SECURITY_CONTEXT_NAME_VALID RMW_NAMESPACE_VALID
|
||||||
|
#define RCL_SECURITY_CONTEXT_NAME_INVALID_IS_EMPTY_STRING RMW_NAMESPACE_INVALID_IS_EMPTY_STRING
|
||||||
|
#define RCL_SECURITY_CONTEXT_NAME_INVALID_NOT_ABSOLUTE RMW_NAMESPACE_INVALID_NOT_ABSOLUTE
|
||||||
|
#define RCL_SECURITY_CONTEXT_NAME_INVALID_ENDS_WITH_FORWARD_SLASH \
|
||||||
|
RMW_NAMESPACE_INVALID_ENDS_WITH_FORWARD_SLASH
|
||||||
|
#define RCL_SECURITY_CONTEXT_NAME_INVALID_CONTAINS_UNALLOWED_CHARACTERS \
|
||||||
|
RMW_NAMESPACE_INVALID_CONTAINS_UNALLOWED_CHARACTERS
|
||||||
|
#define RCL_SECURITY_CONTEXT_NAME_INVALID_CONTAINS_REPEATED_FORWARD_SLASH \
|
||||||
|
RMW_NAMESPACE_INVALID_CONTAINS_REPEATED_FORWARD_SLASH
|
||||||
|
#define RCL_SECURITY_CONTEXT_NAME_INVALID_NAME_TOKEN_STARTS_WITH_NUMBER \
|
||||||
|
RMW_NAMESPACE_INVALID_NAME_TOKEN_STARTS_WITH_NUMBER
|
||||||
|
#define RCL_SECURITY_CONTEXT_NAME_INVALID_TOO_LONG RMW_NAMESPACE_INVALID_TOO_LONG
|
||||||
|
|
||||||
|
#define RCL_SECURITY_CONTEXT_NAME_MAX_LENGTH RMW_NODE_NAME_MAX_NAME_LENGTH
|
||||||
|
|
||||||
|
/// Determine if a given security context name is valid.
|
||||||
|
/**
|
||||||
|
* The same rules as \ref rmw_validate_namespace are used.
|
||||||
|
* The only difference is in the maximum allowed length, which can be up to 255 characters.
|
||||||
|
*
|
||||||
|
* \param[in] security_context security_context to be validated
|
||||||
|
* \param[out] validation_result int in which the result of the check is stored
|
||||||
|
* \param[out] invalid_index index of the input string where an error occurred
|
||||||
|
* \returns `RMW_RET_OK` on successfully running the check, or
|
||||||
|
* \returns `RMW_RET_INVALID_ARGUMENT` on invalid parameters, or
|
||||||
|
* \returns `RMW_RET_ERROR` when an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_validate_security_context_name(
|
||||||
|
const char * security_context,
|
||||||
|
int * validation_result,
|
||||||
|
size_t * invalid_index);
|
||||||
|
|
||||||
|
/// Deterimine if a given security context name is valid.
|
||||||
|
/**
|
||||||
|
* This is an overload of \ref rcl_validate_security_context_name with an extra parameter
|
||||||
|
* for the length of security_context.
|
||||||
|
*
|
||||||
|
* \param[in] security_context The number of characters in security_context.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_validate_security_context_name_with_size(
|
||||||
|
const char * security_context,
|
||||||
|
size_t security_context_length,
|
||||||
|
int * validation_result,
|
||||||
|
size_t * invalid_index);
|
||||||
|
|
||||||
|
/// Return a validation result description, or NULL if unknown or RCL_SECURITY_CONTEXT_NAME_VALID.
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
const char *
|
||||||
|
rcl_security_context_name_validation_result_string(int validation_result);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // RCL__VALIDATE_SECURITY_CONTEXT_NAME_H_
|
|
@ -245,6 +245,22 @@ _rcl_parse_param_file_rule(
|
||||||
rcl_params_t * params,
|
rcl_params_t * params,
|
||||||
char ** param_file);
|
char ** param_file);
|
||||||
|
|
||||||
|
/// Parse a security context argument.
|
||||||
|
/**
|
||||||
|
* \param[in] arg the argument to parse
|
||||||
|
* \param[in] allocator an allocator to use
|
||||||
|
* \param[in,out] security_context parsed security context
|
||||||
|
* \return RCL_RET_OK if a valid security context was parsed, or
|
||||||
|
* \return RCL_RET_BAD_ALLOC if an allocation failed, or
|
||||||
|
* \return RLC_RET_ERROR if an unspecified error occurred.
|
||||||
|
*/
|
||||||
|
RCL_LOCAL
|
||||||
|
rcl_ret_t
|
||||||
|
_rcl_parse_security_context(
|
||||||
|
const char * arg,
|
||||||
|
rcl_allocator_t allocator,
|
||||||
|
char ** security_context);
|
||||||
|
|
||||||
#define RCL_ENABLE_FLAG_PREFIX "--enable-"
|
#define RCL_ENABLE_FLAG_PREFIX "--enable-"
|
||||||
#define RCL_DISABLE_FLAG_PREFIX "--disable-"
|
#define RCL_DISABLE_FLAG_PREFIX "--disable-"
|
||||||
|
|
||||||
|
@ -533,6 +549,39 @@ rcl_parse_arguments(
|
||||||
ret = RCL_RET_INVALID_ROS_ARGS;
|
ret = RCL_RET_INVALID_ROS_ARGS;
|
||||||
goto fail;
|
goto fail;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Attempt to parse argument as a security context
|
||||||
|
if (strcmp(RCL_SECURITY_CONTEXT_FLAG, argv[i]) == 0) {
|
||||||
|
if (i + 1 < argc) {
|
||||||
|
if (NULL != args_impl->security_context) {
|
||||||
|
RCUTILS_LOG_DEBUG_NAMED(
|
||||||
|
ROS_PACKAGE_NAME, "Overriding security context name : %s\n",
|
||||||
|
args_impl->security_context);
|
||||||
|
allocator.deallocate(args_impl->security_context, allocator.state);
|
||||||
|
args_impl->security_context = NULL;
|
||||||
|
}
|
||||||
|
if (RCL_RET_OK == _rcl_parse_security_context(
|
||||||
|
argv[i + 1], allocator, &args_impl->security_context))
|
||||||
|
{
|
||||||
|
RCUTILS_LOG_DEBUG_NAMED(
|
||||||
|
ROS_PACKAGE_NAME, "Got security context : %s\n",
|
||||||
|
args_impl->security_context);
|
||||||
|
++i; // Skip flag here, for loop will skip value.
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
rcl_error_string_t prev_error_string = rcl_get_error_string();
|
||||||
|
rcl_reset_error();
|
||||||
|
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
|
||||||
|
"Couldn't parse security context name: '%s %s'. Error: %s", argv[i], argv[i + 1],
|
||||||
|
prev_error_string.str);
|
||||||
|
} else {
|
||||||
|
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
|
||||||
|
"Couldn't parse trailing %s flag. No security context path provided.", argv[i]);
|
||||||
|
}
|
||||||
|
ret = RCL_RET_INVALID_ROS_ARGS;
|
||||||
|
goto fail;
|
||||||
|
}
|
||||||
|
|
||||||
RCUTILS_LOG_DEBUG_NAMED(
|
RCUTILS_LOG_DEBUG_NAMED(
|
||||||
ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s flag.",
|
ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s flag.",
|
||||||
i, argv[i], RCL_EXTERNAL_LOG_CONFIG_FLAG);
|
i, argv[i], RCL_EXTERNAL_LOG_CONFIG_FLAG);
|
||||||
|
@ -1051,6 +1100,16 @@ rcl_arguments_copy(
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
char * security_context_copy = rcutils_strdup(args->impl->security_context, allocator);
|
||||||
|
if (args->impl->security_context && !security_context_copy) {
|
||||||
|
if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
|
||||||
|
RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
|
||||||
|
} else {
|
||||||
|
RCL_SET_ERROR_MSG("Error while copying security context argument");
|
||||||
|
}
|
||||||
|
return RCL_RET_BAD_ALLOC;
|
||||||
|
}
|
||||||
|
args_out->impl->security_context = security_context_copy;
|
||||||
return RCL_RET_OK;
|
return RCL_RET_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1098,6 +1157,7 @@ rcl_arguments_fini(
|
||||||
args->impl->num_param_files_args = 0;
|
args->impl->num_param_files_args = 0;
|
||||||
args->impl->parameter_files = NULL;
|
args->impl->parameter_files = NULL;
|
||||||
}
|
}
|
||||||
|
args->impl->allocator.deallocate(args->impl->security_context, args->impl->allocator.state);
|
||||||
|
|
||||||
if (NULL != args->impl->external_log_config_file) {
|
if (NULL != args->impl->external_log_config_file) {
|
||||||
args->impl->allocator.deallocate(
|
args->impl->allocator.deallocate(
|
||||||
|
@ -2003,6 +2063,23 @@ _rcl_parse_external_log_config_file_rule(
|
||||||
return RCL_RET_INVALID_PARAM_RULE;
|
return RCL_RET_INVALID_PARAM_RULE;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
rcl_ret_t
|
||||||
|
_rcl_parse_security_context(
|
||||||
|
const char * arg,
|
||||||
|
rcl_allocator_t allocator,
|
||||||
|
char ** security_context)
|
||||||
|
{
|
||||||
|
RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
|
||||||
|
RCL_CHECK_ARGUMENT_FOR_NULL(security_context, RCL_RET_INVALID_ARGUMENT);
|
||||||
|
|
||||||
|
*security_context = rcutils_strdup(arg, allocator);
|
||||||
|
if (NULL == *security_context) {
|
||||||
|
RCL_SET_ERROR_MSG("Failed to allocate memory for security context name");
|
||||||
|
return RCL_RET_BAD_ALLOC;
|
||||||
|
}
|
||||||
|
return RCL_RET_OK;
|
||||||
|
}
|
||||||
|
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
_rcl_parse_disabling_flag(
|
_rcl_parse_disabling_flag(
|
||||||
const char * arg,
|
const char * arg,
|
||||||
|
@ -2105,6 +2182,7 @@ _rcl_allocate_initialized_arguments_impl(rcl_arguments_t * args, rcl_allocator_t
|
||||||
args_impl->log_stdout_disabled = false;
|
args_impl->log_stdout_disabled = false;
|
||||||
args_impl->log_rosout_disabled = false;
|
args_impl->log_rosout_disabled = false;
|
||||||
args_impl->log_ext_lib_disabled = false;
|
args_impl->log_ext_lib_disabled = false;
|
||||||
|
args_impl->security_context = NULL;
|
||||||
args_impl->allocator = *allocator;
|
args_impl->allocator = *allocator;
|
||||||
|
|
||||||
return RCL_RET_OK;
|
return RCL_RET_OK;
|
||||||
|
|
|
@ -61,6 +61,9 @@ typedef struct rcl_arguments_impl_t
|
||||||
/// A boolean value indicating if the external lib handler should be used for log output
|
/// A boolean value indicating if the external lib handler should be used for log output
|
||||||
bool log_ext_lib_disabled;
|
bool log_ext_lib_disabled;
|
||||||
|
|
||||||
|
/// Security context to be used.
|
||||||
|
char * security_context;
|
||||||
|
|
||||||
/// Allocator used to allocate objects in this struct
|
/// Allocator used to allocate objects in this struct
|
||||||
rcl_allocator_t allocator;
|
rcl_allocator_t allocator;
|
||||||
} rcl_arguments_impl_t;
|
} rcl_arguments_impl_t;
|
||||||
|
|
|
@ -108,7 +108,7 @@ __cleanup_context(rcl_context_t * context)
|
||||||
rcl_ret_t ret = rcl_arguments_fini(&(context->global_arguments));
|
rcl_ret_t ret = rcl_arguments_fini(&(context->global_arguments));
|
||||||
if (RCL_RET_OK != ret) {
|
if (RCL_RET_OK != ret) {
|
||||||
RCUTILS_SAFE_FWRITE_TO_STDERR(
|
RCUTILS_SAFE_FWRITE_TO_STDERR(
|
||||||
"[rcl|init.c:" RCUTILS_STRINGIFY(__LINE__)
|
"[rcl|context.c:" RCUTILS_STRINGIFY(__LINE__)
|
||||||
"] failed to finalize global arguments while cleaning up context, memory may be leaked: ");
|
"] failed to finalize global arguments while cleaning up context, memory may be leaked: ");
|
||||||
RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
|
RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
|
||||||
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
|
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
|
||||||
|
@ -126,7 +126,7 @@ __cleanup_context(rcl_context_t * context)
|
||||||
rcl_ret_t ret = rcl_init_options_fini(&(context->impl->init_options));
|
rcl_ret_t ret = rcl_init_options_fini(&(context->impl->init_options));
|
||||||
if (RCL_RET_OK != ret) {
|
if (RCL_RET_OK != ret) {
|
||||||
RCUTILS_SAFE_FWRITE_TO_STDERR(
|
RCUTILS_SAFE_FWRITE_TO_STDERR(
|
||||||
"[rcl|init.c:" RCUTILS_STRINGIFY(__LINE__)
|
"[rcl|context.c:" RCUTILS_STRINGIFY(__LINE__)
|
||||||
"] failed to finalize init options while cleaning up context, memory may be leaked: ");
|
"] failed to finalize init options while cleaning up context, memory may be leaked: ");
|
||||||
RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
|
RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
|
||||||
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
|
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
|
||||||
|
@ -139,7 +139,7 @@ __cleanup_context(rcl_context_t * context)
|
||||||
rmw_ret_t rmw_ret = rmw_context_fini(&(context->impl->rmw_context));
|
rmw_ret_t rmw_ret = rmw_context_fini(&(context->impl->rmw_context));
|
||||||
if (RMW_RET_OK != rmw_ret) {
|
if (RMW_RET_OK != rmw_ret) {
|
||||||
RCUTILS_SAFE_FWRITE_TO_STDERR(
|
RCUTILS_SAFE_FWRITE_TO_STDERR(
|
||||||
"[rcl|init.c:" RCUTILS_STRINGIFY(__LINE__)
|
"[rcl|context.c:" RCUTILS_STRINGIFY(__LINE__)
|
||||||
"] failed to finalize rmw context while cleaning up context, memory may be leaked: ");
|
"] failed to finalize rmw context while cleaning up context, memory may be leaked: ");
|
||||||
RCUTILS_SAFE_FWRITE_TO_STDERR(rcutils_get_error_string().str);
|
RCUTILS_SAFE_FWRITE_TO_STDERR(rcutils_get_error_string().str);
|
||||||
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
|
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
|
||||||
|
|
52
rcl/src/rcl/domain_id.c
Normal file
52
rcl/src/rcl/domain_id.c
Normal file
|
@ -0,0 +1,52 @@
|
||||||
|
// Copyright 2019 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/domain_id.h"
|
||||||
|
|
||||||
|
#include <limits.h>
|
||||||
|
|
||||||
|
#include "rcutils/get_env.h"
|
||||||
|
|
||||||
|
#include "rcl/error_handling.h"
|
||||||
|
#include "rcl/types.h"
|
||||||
|
|
||||||
|
const char * const RCL_DOMAIN_ID_ENV_VAR = "ROS_DOMAIN_ID";
|
||||||
|
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_get_default_domain_id(size_t * domain_id)
|
||||||
|
{
|
||||||
|
const char * ros_domain_id = NULL;
|
||||||
|
const char * get_env_error_str = NULL;
|
||||||
|
|
||||||
|
if (!domain_id) {
|
||||||
|
return RCL_RET_INVALID_ARGUMENT;
|
||||||
|
}
|
||||||
|
|
||||||
|
get_env_error_str = rcutils_get_env(RCL_DOMAIN_ID_ENV_VAR, &ros_domain_id);
|
||||||
|
if (NULL != get_env_error_str) {
|
||||||
|
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
|
||||||
|
"Error getting env var '" RCUTILS_STRINGIFY(RCL_DOMAIN_ID_ENV_VAR) "': %s\n",
|
||||||
|
get_env_error_str);
|
||||||
|
return RCL_RET_ERROR;
|
||||||
|
}
|
||||||
|
if (ros_domain_id) {
|
||||||
|
unsigned long number = strtoul(ros_domain_id, NULL, 0); // NOLINT(runtime/int)
|
||||||
|
if (number == ULONG_MAX) {
|
||||||
|
RCL_SET_ERROR_MSG("failed to interpret ROS_DOMAIN_ID as integral number");
|
||||||
|
return RCL_RET_ERROR;
|
||||||
|
}
|
||||||
|
*domain_id = (size_t)number;
|
||||||
|
}
|
||||||
|
return RCL_RET_OK;
|
||||||
|
}
|
|
@ -339,6 +339,53 @@ rcl_get_node_names(
|
||||||
return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
|
return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_get_node_names_with_security_contexts(
|
||||||
|
const rcl_node_t * node,
|
||||||
|
rcl_allocator_t allocator,
|
||||||
|
rcutils_string_array_t * node_names,
|
||||||
|
rcutils_string_array_t * node_namespaces,
|
||||||
|
rcutils_string_array_t * security_contexts)
|
||||||
|
{
|
||||||
|
if (!rcl_node_is_valid(node)) {
|
||||||
|
return RCL_RET_NODE_INVALID; // error already set
|
||||||
|
}
|
||||||
|
RCL_CHECK_ARGUMENT_FOR_NULL(node_names, RCL_RET_INVALID_ARGUMENT);
|
||||||
|
if (node_names->size != 0) {
|
||||||
|
RCL_SET_ERROR_MSG("node_names size is not zero");
|
||||||
|
return RCL_RET_INVALID_ARGUMENT;
|
||||||
|
}
|
||||||
|
if (node_names->data) {
|
||||||
|
RCL_SET_ERROR_MSG("node_names is not null");
|
||||||
|
return RCL_RET_INVALID_ARGUMENT;
|
||||||
|
}
|
||||||
|
RCL_CHECK_ARGUMENT_FOR_NULL(node_namespaces, RCL_RET_INVALID_ARGUMENT);
|
||||||
|
if (node_namespaces->size != 0) {
|
||||||
|
RCL_SET_ERROR_MSG("node_namespaces size is not zero");
|
||||||
|
return RCL_RET_INVALID_ARGUMENT;
|
||||||
|
}
|
||||||
|
if (node_namespaces->data) {
|
||||||
|
RCL_SET_ERROR_MSG("node_namespaces is not null");
|
||||||
|
return RCL_RET_INVALID_ARGUMENT;
|
||||||
|
}
|
||||||
|
RCL_CHECK_ARGUMENT_FOR_NULL(security_contexts, RCL_RET_INVALID_ARGUMENT);
|
||||||
|
if (security_contexts->size != 0) {
|
||||||
|
RCL_SET_ERROR_MSG("security_contexts size is not zero");
|
||||||
|
return RCL_RET_INVALID_ARGUMENT;
|
||||||
|
}
|
||||||
|
if (security_contexts->data) {
|
||||||
|
RCL_SET_ERROR_MSG("security_contexts is not null");
|
||||||
|
return RCL_RET_INVALID_ARGUMENT;
|
||||||
|
}
|
||||||
|
(void)allocator; // to be used in rmw_get_node_names in the future
|
||||||
|
rmw_ret_t rmw_ret = rmw_get_node_names_with_security_contexts(
|
||||||
|
rcl_node_get_rmw_handle(node),
|
||||||
|
node_names,
|
||||||
|
node_namespaces,
|
||||||
|
security_contexts);
|
||||||
|
return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
|
||||||
|
}
|
||||||
|
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_count_publishers(
|
rcl_count_publishers(
|
||||||
const rcl_node_t * node,
|
const rcl_node_t * node,
|
||||||
|
|
|
@ -19,17 +19,26 @@ extern "C"
|
||||||
|
|
||||||
#include "rcl/init.h"
|
#include "rcl/init.h"
|
||||||
|
|
||||||
|
#include "rcutils/logging_macros.h"
|
||||||
|
#include "rcutils/stdatomic_helper.h"
|
||||||
|
#include "rcutils/strdup.h"
|
||||||
|
|
||||||
|
#include "rmw/error_handling.h"
|
||||||
|
|
||||||
|
#include "tracetools/tracetools.h"
|
||||||
|
|
||||||
|
#include "rcl/arguments.h"
|
||||||
|
#include "rcl/domain_id.h"
|
||||||
|
#include "rcl/error_handling.h"
|
||||||
|
#include "rcl/localhost.h"
|
||||||
|
#include "rcl/logging.h"
|
||||||
|
#include "rcl/security.h"
|
||||||
|
#include "rcl/validate_security_context_name.h"
|
||||||
|
|
||||||
#include "./arguments_impl.h"
|
#include "./arguments_impl.h"
|
||||||
#include "./common.h"
|
#include "./common.h"
|
||||||
#include "./context_impl.h"
|
#include "./context_impl.h"
|
||||||
#include "./init_options_impl.h"
|
#include "./init_options_impl.h"
|
||||||
#include "rcl/arguments.h"
|
|
||||||
#include "rcl/error_handling.h"
|
|
||||||
#include "rcl/logging.h"
|
|
||||||
#include "rcutils/logging_macros.h"
|
|
||||||
#include "rcutils/stdatomic_helper.h"
|
|
||||||
#include "rmw/error_handling.h"
|
|
||||||
#include "tracetools/tracetools.h"
|
|
||||||
|
|
||||||
static atomic_uint_least64_t __rcl_next_unique_id = ATOMIC_VAR_INIT(1);
|
static atomic_uint_least64_t __rcl_next_unique_id = ATOMIC_VAR_INIT(1);
|
||||||
|
|
||||||
|
@ -144,6 +153,72 @@ rcl_init(
|
||||||
rcutils_atomic_store((atomic_uint_least64_t *)(&context->instance_id_storage), next_instance_id);
|
rcutils_atomic_store((atomic_uint_least64_t *)(&context->instance_id_storage), next_instance_id);
|
||||||
context->impl->init_options.impl->rmw_init_options.instance_id = next_instance_id;
|
context->impl->init_options.impl->rmw_init_options.instance_id = next_instance_id;
|
||||||
|
|
||||||
|
size_t * domain_id = &context->impl->init_options.impl->rmw_init_options.domain_id;
|
||||||
|
if (RCL_DEFAULT_DOMAIN_ID == *domain_id) {
|
||||||
|
// Get actual domain id based on environment variable.
|
||||||
|
ret = rcl_get_default_domain_id(domain_id);
|
||||||
|
if (RCL_RET_OK != ret) {
|
||||||
|
fail_ret = ret;
|
||||||
|
goto fail;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
rmw_localhost_only_t * localhost_only =
|
||||||
|
&context->impl->init_options.impl->rmw_init_options.localhost_only;
|
||||||
|
if (RMW_LOCALHOST_ONLY_DEFAULT == *localhost_only) {
|
||||||
|
// Get actual localhost_only value based on environment variable, if needed.
|
||||||
|
ret = rcl_get_localhost_only(localhost_only);
|
||||||
|
if (RCL_RET_OK != ret) {
|
||||||
|
fail_ret = ret;
|
||||||
|
goto fail;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (context->global_arguments.impl->security_context) {
|
||||||
|
context->impl->init_options.impl->rmw_init_options.security_context = rcutils_strdup(
|
||||||
|
context->global_arguments.impl->security_context,
|
||||||
|
context->impl->allocator);
|
||||||
|
} else {
|
||||||
|
context->impl->init_options.impl->rmw_init_options.security_context = rcutils_strdup(
|
||||||
|
"/", context->impl->allocator);
|
||||||
|
}
|
||||||
|
int validation_result;
|
||||||
|
size_t invalid_index;
|
||||||
|
ret = rcl_validate_security_context_name(
|
||||||
|
context->impl->init_options.impl->rmw_init_options.security_context,
|
||||||
|
&validation_result,
|
||||||
|
&invalid_index);
|
||||||
|
if (RCL_RET_OK != ret) {
|
||||||
|
RCL_SET_ERROR_MSG("rcl_validate_security_context_name() failed");
|
||||||
|
fail_ret = ret;
|
||||||
|
goto fail;
|
||||||
|
}
|
||||||
|
if (RCL_SECURITY_CONTEXT_NAME_VALID != validation_result) {
|
||||||
|
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
|
||||||
|
"Security context name is not valid: '%s'. Invalid index: %zu",
|
||||||
|
rcl_security_context_name_validation_result_string(validation_result),
|
||||||
|
invalid_index);
|
||||||
|
fail_ret = RMW_RET_ERROR;
|
||||||
|
goto fail;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!context->impl->init_options.impl->rmw_init_options.security_context) {
|
||||||
|
RCL_SET_ERROR_MSG("failed to set context name");
|
||||||
|
fail_ret = RMW_RET_BAD_ALLOC;
|
||||||
|
goto fail;
|
||||||
|
}
|
||||||
|
|
||||||
|
rmw_security_options_t * security_options =
|
||||||
|
&context->impl->init_options.impl->rmw_init_options.security_options;
|
||||||
|
ret = rcl_get_security_options_from_environment(
|
||||||
|
context->impl->init_options.impl->rmw_init_options.security_context,
|
||||||
|
&context->impl->allocator,
|
||||||
|
security_options);
|
||||||
|
if (RMW_RET_OK != ret) {
|
||||||
|
fail_ret = ret;
|
||||||
|
goto fail;
|
||||||
|
}
|
||||||
|
|
||||||
// Initialize rmw_init.
|
// Initialize rmw_init.
|
||||||
rmw_ret_t rmw_ret = rmw_init(
|
rmw_ret_t rmw_ret = rmw_init(
|
||||||
&(context->impl->init_options.impl->rmw_init_options),
|
&(context->impl->init_options.impl->rmw_init_options),
|
||||||
|
|
|
@ -17,7 +17,7 @@
|
||||||
|
|
||||||
#include "rcl/init_options.h"
|
#include "rcl/init_options.h"
|
||||||
|
|
||||||
#include "rmw/init.h"
|
#include "rmw/init_options.h"
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
extern "C"
|
extern "C"
|
||||||
|
|
|
@ -12,19 +12,35 @@
|
||||||
// See the License for the specific language governing permissions and
|
// See the License for the specific language governing permissions and
|
||||||
// limitations under the License.
|
// limitations under the License.
|
||||||
|
|
||||||
#include <rcl/localhost.h>
|
#include "rcl/localhost.h"
|
||||||
|
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
||||||
#include "rcutils/get_env.h"
|
#include "rcutils/get_env.h"
|
||||||
|
|
||||||
|
#include "rcl/error_handling.h"
|
||||||
|
#include "rcl/types.h"
|
||||||
|
|
||||||
const char * const RCL_LOCALHOST_ENV_VAR = "ROS_LOCALHOST_ONLY";
|
const char * const RCL_LOCALHOST_ENV_VAR = "ROS_LOCALHOST_ONLY";
|
||||||
|
|
||||||
bool
|
rcl_ret_t
|
||||||
rcl_localhost_only()
|
rcl_get_localhost_only(rmw_localhost_only_t * localhost_only)
|
||||||
{
|
{
|
||||||
const char * ros_local_host_env_val = NULL;
|
const char * ros_local_host_env_val = NULL;
|
||||||
return rcutils_get_env(RCL_LOCALHOST_ENV_VAR, &ros_local_host_env_val) == NULL &&
|
const char * get_env_error_str = NULL;
|
||||||
ros_local_host_env_val != NULL && strcmp(ros_local_host_env_val, "1") == 0;
|
|
||||||
|
if (!localhost_only) {
|
||||||
|
return RCL_RET_INVALID_ARGUMENT;
|
||||||
|
}
|
||||||
|
|
||||||
|
get_env_error_str = rcutils_get_env(RCL_LOCALHOST_ENV_VAR, &ros_local_host_env_val);
|
||||||
|
if (NULL != get_env_error_str) {
|
||||||
|
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
|
||||||
|
"Error getting env var '" RCUTILS_STRINGIFY(RCL_DOMAIN_ID_ENV_VAR) "': %s\n",
|
||||||
|
get_env_error_str);
|
||||||
|
return RCL_RET_ERROR;
|
||||||
|
}
|
||||||
|
*localhost_only = ros_local_host_env_val != NULL && strcmp(ros_local_host_env_val, "1") == 0;
|
||||||
|
return RCL_RET_OK;
|
||||||
}
|
}
|
||||||
|
|
|
@ -26,12 +26,14 @@ extern "C"
|
||||||
|
|
||||||
#include "rcl/arguments.h"
|
#include "rcl/arguments.h"
|
||||||
#include "rcl/error_handling.h"
|
#include "rcl/error_handling.h"
|
||||||
|
#include "rcl/domain_id.h"
|
||||||
#include "rcl/localhost.h"
|
#include "rcl/localhost.h"
|
||||||
#include "rcl/logging.h"
|
#include "rcl/logging.h"
|
||||||
#include "rcl/logging_rosout.h"
|
#include "rcl/logging_rosout.h"
|
||||||
#include "rcl/rcl.h"
|
#include "rcl/rcl.h"
|
||||||
#include "rcl/remap.h"
|
#include "rcl/remap.h"
|
||||||
#include "rcl/security_directory.h"
|
#include "rcl/security.h"
|
||||||
|
|
||||||
#include "rcutils/filesystem.h"
|
#include "rcutils/filesystem.h"
|
||||||
#include "rcutils/find.h"
|
#include "rcutils/find.h"
|
||||||
#include "rcutils/format_string.h"
|
#include "rcutils/format_string.h"
|
||||||
|
@ -41,8 +43,9 @@ extern "C"
|
||||||
#include "rcutils/repl_str.h"
|
#include "rcutils/repl_str.h"
|
||||||
#include "rcutils/snprintf.h"
|
#include "rcutils/snprintf.h"
|
||||||
#include "rcutils/strdup.h"
|
#include "rcutils/strdup.h"
|
||||||
|
|
||||||
#include "rmw/error_handling.h"
|
#include "rmw/error_handling.h"
|
||||||
#include "rmw/node_security_options.h"
|
#include "rmw/security_options.h"
|
||||||
#include "rmw/rmw.h"
|
#include "rmw/rmw.h"
|
||||||
#include "rmw/validate_namespace.h"
|
#include "rmw/validate_namespace.h"
|
||||||
#include "rmw/validate_node_name.h"
|
#include "rmw/validate_node_name.h"
|
||||||
|
@ -50,11 +53,6 @@ extern "C"
|
||||||
|
|
||||||
#include "./context_impl.h"
|
#include "./context_impl.h"
|
||||||
|
|
||||||
#define ROS_SECURITY_STRATEGY_VAR_NAME "ROS_SECURITY_STRATEGY"
|
|
||||||
#define ROS_SECURITY_ENABLE_VAR_NAME "ROS_SECURITY_ENABLE"
|
|
||||||
#define ROS_DOMAIN_ID_VAR_NAME "ROS_DOMAIN_ID"
|
|
||||||
|
|
||||||
|
|
||||||
typedef struct rcl_node_impl_t
|
typedef struct rcl_node_impl_t
|
||||||
{
|
{
|
||||||
rcl_node_options_t options;
|
rcl_node_options_t options;
|
||||||
|
@ -123,15 +121,13 @@ rcl_node_init(
|
||||||
const rcl_node_options_t * options)
|
const rcl_node_options_t * options)
|
||||||
{
|
{
|
||||||
size_t domain_id = 0;
|
size_t domain_id = 0;
|
||||||
const char * ros_domain_id;
|
rmw_localhost_only_t localhost_only = RMW_LOCALHOST_ONLY_DEFAULT;
|
||||||
const char * get_env_error_str;
|
|
||||||
const rmw_guard_condition_t * rmw_graph_guard_condition = NULL;
|
const rmw_guard_condition_t * rmw_graph_guard_condition = NULL;
|
||||||
rcl_guard_condition_options_t graph_guard_condition_options =
|
rcl_guard_condition_options_t graph_guard_condition_options =
|
||||||
rcl_guard_condition_get_default_options();
|
rcl_guard_condition_get_default_options();
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_ret_t fail_ret = RCL_RET_ERROR;
|
rcl_ret_t fail_ret = RCL_RET_ERROR;
|
||||||
char * remapped_node_name = NULL;
|
char * remapped_node_name = NULL;
|
||||||
char * node_secure_root = NULL;
|
|
||||||
|
|
||||||
// Check options and allocator first, so allocator can be used for errors.
|
// Check options and allocator first, so allocator can be used for errors.
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT);
|
RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT);
|
||||||
|
@ -258,79 +254,24 @@ rcl_node_init(
|
||||||
RCL_CHECK_FOR_NULL_WITH_MSG(
|
RCL_CHECK_FOR_NULL_WITH_MSG(
|
||||||
node->impl->logger_name, "creating logger name failed", goto fail);
|
node->impl->logger_name, "creating logger name failed", goto fail);
|
||||||
|
|
||||||
// node rmw_node_handle
|
domain_id = node->impl->options.domain_id;
|
||||||
if (node->impl->options.domain_id == RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID) {
|
if (RCL_DEFAULT_DOMAIN_ID == domain_id) {
|
||||||
// Find the domain ID set by the environment.
|
if (RCL_RET_OK != rcl_get_default_domain_id(&domain_id)) {
|
||||||
get_env_error_str = rcutils_get_env(ROS_DOMAIN_ID_VAR_NAME, &ros_domain_id);
|
|
||||||
if (NULL != get_env_error_str) {
|
|
||||||
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
|
|
||||||
"Error getting env var '" RCUTILS_STRINGIFY(ROS_DOMAIN_ID_VAR_NAME) "': %s\n",
|
|
||||||
get_env_error_str);
|
|
||||||
goto fail;
|
goto fail;
|
||||||
}
|
}
|
||||||
if (ros_domain_id) {
|
|
||||||
unsigned long number = strtoul(ros_domain_id, NULL, 0); // NOLINT(runtime/int)
|
|
||||||
if (number == ULONG_MAX) {
|
|
||||||
RCL_SET_ERROR_MSG("failed to interpret ROS_DOMAIN_ID as integral number");
|
|
||||||
goto fail;
|
|
||||||
}
|
|
||||||
domain_id = (size_t)number;
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
domain_id = node->impl->options.domain_id;
|
|
||||||
}
|
}
|
||||||
// actual domain id
|
|
||||||
node->impl->actual_domain_id = domain_id;
|
|
||||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Using domain ID of '%zu'", domain_id);
|
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Using domain ID of '%zu'", domain_id);
|
||||||
|
node->impl->actual_domain_id = domain_id;
|
||||||
|
|
||||||
const char * ros_security_enable = NULL;
|
if (RMW_LOCALHOST_ONLY_DEFAULT == localhost_only) {
|
||||||
const char * ros_enforce_security = NULL;
|
if (RMW_RET_OK != rcl_get_localhost_only(&localhost_only)) {
|
||||||
|
goto fail;
|
||||||
get_env_error_str = rcutils_get_env(ROS_SECURITY_ENABLE_VAR_NAME, &ros_security_enable);
|
|
||||||
if (NULL != get_env_error_str) {
|
|
||||||
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
|
|
||||||
"Error getting env var '" RCUTILS_STRINGIFY(ROS_SECURITY_ENABLE_VAR_NAME) "': %s\n",
|
|
||||||
get_env_error_str);
|
|
||||||
ret = RCL_RET_ERROR;
|
|
||||||
goto fail;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool use_security = (0 == strcmp(ros_security_enable, "true"));
|
|
||||||
RCUTILS_LOG_DEBUG_NAMED(
|
|
||||||
ROS_PACKAGE_NAME, "Using security: %s", use_security ? "true" : "false");
|
|
||||||
|
|
||||||
get_env_error_str = rcutils_get_env(ROS_SECURITY_STRATEGY_VAR_NAME, &ros_enforce_security);
|
|
||||||
if (NULL != get_env_error_str) {
|
|
||||||
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
|
|
||||||
"Error getting env var '" RCUTILS_STRINGIFY(ROS_SECURITY_STRATEGY_VAR_NAME) "': %s\n",
|
|
||||||
get_env_error_str);
|
|
||||||
ret = RCL_RET_ERROR;
|
|
||||||
goto fail;
|
|
||||||
}
|
|
||||||
|
|
||||||
rmw_node_security_options_t node_security_options =
|
|
||||||
rmw_get_zero_initialized_node_security_options();
|
|
||||||
node_security_options.enforce_security = (0 == strcmp(ros_enforce_security, "Enforce")) ?
|
|
||||||
RMW_SECURITY_ENFORCEMENT_ENFORCE : RMW_SECURITY_ENFORCEMENT_PERMISSIVE;
|
|
||||||
|
|
||||||
if (!use_security) {
|
|
||||||
node_security_options.enforce_security = RMW_SECURITY_ENFORCEMENT_PERMISSIVE;
|
|
||||||
} else { // if use_security
|
|
||||||
// File discovery magic here
|
|
||||||
node_secure_root = rcl_get_secure_root(name, local_namespace_, allocator);
|
|
||||||
if (node_secure_root) {
|
|
||||||
RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, "Found security directory: %s", node_secure_root);
|
|
||||||
node_security_options.security_root_path = node_secure_root;
|
|
||||||
} else {
|
|
||||||
if (RMW_SECURITY_ENFORCEMENT_ENFORCE == node_security_options.enforce_security) {
|
|
||||||
ret = RCL_RET_ERROR;
|
|
||||||
goto cleanup;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
node->impl->rmw_node_handle = rmw_create_node(
|
node->impl->rmw_node_handle = rmw_create_node(
|
||||||
&(node->context->impl->rmw_context),
|
&(node->context->impl->rmw_context),
|
||||||
name, local_namespace_, domain_id, &node_security_options, rcl_localhost_only());
|
name, local_namespace_, domain_id, localhost_only);
|
||||||
|
|
||||||
RCL_CHECK_FOR_NULL_WITH_MSG(
|
RCL_CHECK_FOR_NULL_WITH_MSG(
|
||||||
node->impl->rmw_node_handle, rmw_get_error_string().str, goto fail);
|
node->impl->rmw_node_handle, rmw_get_error_string().str, goto fail);
|
||||||
|
@ -431,7 +372,6 @@ cleanup:
|
||||||
if (NULL != remapped_node_name) {
|
if (NULL != remapped_node_name) {
|
||||||
allocator->deallocate(remapped_node_name, allocator->state);
|
allocator->deallocate(remapped_node_name, allocator->state);
|
||||||
}
|
}
|
||||||
allocator->deallocate(node_secure_root, allocator->state);
|
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -20,6 +20,7 @@ extern "C"
|
||||||
#include "rcl/node_options.h"
|
#include "rcl/node_options.h"
|
||||||
|
|
||||||
#include "rcl/arguments.h"
|
#include "rcl/arguments.h"
|
||||||
|
#include "rcl/domain_id.h"
|
||||||
#include "rcl/error_handling.h"
|
#include "rcl/error_handling.h"
|
||||||
#include "rcl/logging_rosout.h"
|
#include "rcl/logging_rosout.h"
|
||||||
|
|
||||||
|
|
186
rcl/src/rcl/security.c
Normal file
186
rcl/src/rcl/security.c
Normal file
|
@ -0,0 +1,186 @@
|
||||||
|
// Copyright 2018-2020 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/security.h"
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
#include "rcl/error_handling.h"
|
||||||
|
|
||||||
|
#include "rcutils/logging_macros.h"
|
||||||
|
#include "rcutils/filesystem.h"
|
||||||
|
#include "rcutils/get_env.h"
|
||||||
|
#include "rcutils/strdup.h"
|
||||||
|
|
||||||
|
#include "rmw/security_options.h"
|
||||||
|
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_get_security_options_from_environment(
|
||||||
|
const char * name,
|
||||||
|
const rcutils_allocator_t * allocator,
|
||||||
|
rmw_security_options_t * security_options)
|
||||||
|
{
|
||||||
|
bool use_security = false;
|
||||||
|
rcl_ret_t ret = rcl_security_enabled(&use_security);
|
||||||
|
if (RCL_RET_OK != ret) {
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
RCUTILS_LOG_DEBUG_NAMED(
|
||||||
|
ROS_PACKAGE_NAME, "Using security: %s", use_security ? "true" : "false");
|
||||||
|
|
||||||
|
if (!use_security) {
|
||||||
|
security_options->enforce_security = RMW_SECURITY_ENFORCEMENT_PERMISSIVE;
|
||||||
|
return RMW_RET_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ret = rcl_get_enforcement_policy(&security_options->enforce_security);
|
||||||
|
if (RCL_RET_OK != ret) {
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
// File discovery magic here
|
||||||
|
char * secure_root = rcl_get_secure_root(name, allocator);
|
||||||
|
if (secure_root) {
|
||||||
|
RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, "Found security directory: %s", secure_root);
|
||||||
|
security_options->security_root_path = secure_root;
|
||||||
|
} else {
|
||||||
|
if (RMW_SECURITY_ENFORCEMENT_ENFORCE == security_options->enforce_security) {
|
||||||
|
return RCL_RET_ERROR;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return RCL_RET_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_security_enabled(bool * use_security)
|
||||||
|
{
|
||||||
|
const char * ros_security_enable = NULL;
|
||||||
|
const char * get_env_error_str = NULL;
|
||||||
|
|
||||||
|
RCL_CHECK_ARGUMENT_FOR_NULL(use_security, RCL_RET_INVALID_ARGUMENT);
|
||||||
|
|
||||||
|
get_env_error_str = rcutils_get_env(ROS_SECURITY_ENABLE_VAR_NAME, &ros_security_enable);
|
||||||
|
if (NULL != get_env_error_str) {
|
||||||
|
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
|
||||||
|
"Error getting env var '" RCUTILS_STRINGIFY(ROS_SECURITY_ENABLE_VAR_NAME) "': %s\n",
|
||||||
|
get_env_error_str);
|
||||||
|
return RCL_RET_ERROR;
|
||||||
|
}
|
||||||
|
|
||||||
|
*use_security = (0 == strcmp(ros_security_enable, "true"));
|
||||||
|
return RCL_RET_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_get_enforcement_policy(rmw_security_enforcement_policy_t * policy)
|
||||||
|
{
|
||||||
|
const char * ros_enforce_security = NULL;
|
||||||
|
const char * get_env_error_str = NULL;
|
||||||
|
|
||||||
|
RCL_CHECK_ARGUMENT_FOR_NULL(policy, RCL_RET_INVALID_ARGUMENT);
|
||||||
|
|
||||||
|
get_env_error_str = rcutils_get_env(ROS_SECURITY_STRATEGY_VAR_NAME, &ros_enforce_security);
|
||||||
|
if (NULL != get_env_error_str) {
|
||||||
|
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
|
||||||
|
"Error getting env var '" RCUTILS_STRINGIFY(ROS_SECURITY_STRATEGY_VAR_NAME) "': %s\n",
|
||||||
|
get_env_error_str);
|
||||||
|
return RCL_RET_ERROR;
|
||||||
|
}
|
||||||
|
|
||||||
|
*policy = (0 == strcmp(ros_enforce_security, "Enforce")) ?
|
||||||
|
RMW_SECURITY_ENFORCEMENT_ENFORCE : RMW_SECURITY_ENFORCEMENT_PERMISSIVE;
|
||||||
|
return RCL_RET_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
char * exact_match_lookup(
|
||||||
|
const char * name,
|
||||||
|
const char * ros_secure_root_env,
|
||||||
|
const rcl_allocator_t * allocator)
|
||||||
|
{
|
||||||
|
// Perform an exact match for the node/context's name in directory <root dir>/<namespace>.
|
||||||
|
char * secure_root = NULL;
|
||||||
|
// "/" case when root namespace is explicitly passed in
|
||||||
|
if (0 == strcmp(name, "/")) {
|
||||||
|
secure_root = rcutils_strdup(ros_secure_root_env, *allocator);
|
||||||
|
} else {
|
||||||
|
char * root_path = NULL;
|
||||||
|
// Get native path, ignore the leading forward slash
|
||||||
|
// TODO(ros2team): remove the hard-coded length, use the length of the root namespace instead
|
||||||
|
root_path = rcutils_to_native_path(name + 1, *allocator);
|
||||||
|
secure_root = rcutils_join_path(ros_secure_root_env, root_path, *allocator);
|
||||||
|
allocator->deallocate(root_path, allocator->state);
|
||||||
|
}
|
||||||
|
return secure_root;
|
||||||
|
}
|
||||||
|
|
||||||
|
char * rcl_get_secure_root(
|
||||||
|
const char * name,
|
||||||
|
const rcl_allocator_t * allocator)
|
||||||
|
{
|
||||||
|
bool ros_secure_directory_override = true;
|
||||||
|
|
||||||
|
// find out if either of the configuration environment variables are set
|
||||||
|
const char * env_buf = NULL;
|
||||||
|
if (NULL == name) {
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (rcutils_get_env(ROS_SECURITY_DIRECTORY_OVERRIDE, &env_buf)) {
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
if (!env_buf) {
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
if (0 == strcmp("", env_buf)) {
|
||||||
|
// check root directory if override directory environment variable is empty
|
||||||
|
if (rcutils_get_env(ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME, &env_buf)) {
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
if (!env_buf) {
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
if (0 == strcmp("", env_buf)) {
|
||||||
|
return NULL; // environment variable was empty
|
||||||
|
}
|
||||||
|
ros_secure_directory_override = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// found a usable environment variable, copy into our memory before overwriting with next lookup
|
||||||
|
char * ros_secure_root_env = rcutils_strdup(env_buf, *allocator);
|
||||||
|
|
||||||
|
char * secure_root = NULL;
|
||||||
|
if (ros_secure_directory_override) {
|
||||||
|
secure_root = rcutils_strdup(ros_secure_root_env, *allocator);
|
||||||
|
} else {
|
||||||
|
secure_root = exact_match_lookup(name, ros_secure_root_env, allocator);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (NULL == secure_root || !rcutils_is_directory(secure_root)) {
|
||||||
|
// Check secure_root is not NULL before checking directory
|
||||||
|
if (NULL == secure_root) {
|
||||||
|
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
|
||||||
|
"SECURITY ERROR: unable to find a folder matching the name '%s' in '%s'. ",
|
||||||
|
name, ros_secure_root_env);
|
||||||
|
} else {
|
||||||
|
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
|
||||||
|
"SECURITY ERROR: directory '%s' does not exist.", secure_root);
|
||||||
|
}
|
||||||
|
allocator->deallocate(ros_secure_root_env, allocator->state);
|
||||||
|
allocator->deallocate(secure_root, allocator->state);
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
allocator->deallocate(ros_secure_root_env, allocator->state);
|
||||||
|
return secure_root;
|
||||||
|
}
|
|
@ -1,266 +0,0 @@
|
||||||
// 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/security_directory.h"
|
|
||||||
|
|
||||||
#include "rcl/error_handling.h"
|
|
||||||
#include "rcutils/filesystem.h"
|
|
||||||
#include "rcutils/get_env.h"
|
|
||||||
#include "rcutils/format_string.h"
|
|
||||||
|
|
||||||
#ifdef __clang__
|
|
||||||
# pragma clang diagnostic push
|
|
||||||
# pragma clang diagnostic ignored "-Wembedded-directive"
|
|
||||||
#endif
|
|
||||||
#include "tinydir/tinydir.h"
|
|
||||||
#ifdef __clang__
|
|
||||||
# pragma clang diagnostic pop
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/**
|
|
||||||
* A security lookup function takes in the node's name, namespace, a security root directory and an allocator;
|
|
||||||
* It returns the relevant information required to load the security credentials,
|
|
||||||
* which is currently a path to a directory on the filesystem containing DDS Security permission files.
|
|
||||||
*/
|
|
||||||
typedef char * (* security_lookup_fn_t) (
|
|
||||||
const char * node_name,
|
|
||||||
const char * node_namespace,
|
|
||||||
const char * ros_secure_root_env,
|
|
||||||
const rcl_allocator_t * allocator
|
|
||||||
);
|
|
||||||
|
|
||||||
char * exact_match_lookup(
|
|
||||||
const char * node_name,
|
|
||||||
const char * node_namespace,
|
|
||||||
const char * ros_secure_root_env,
|
|
||||||
const rcl_allocator_t * allocator
|
|
||||||
);
|
|
||||||
|
|
||||||
char * prefix_match_lookup(
|
|
||||||
const char * node_name,
|
|
||||||
const char * node_namespace,
|
|
||||||
const char * ros_secure_root_env,
|
|
||||||
const rcl_allocator_t * allocator
|
|
||||||
);
|
|
||||||
|
|
||||||
security_lookup_fn_t g_security_lookup_fns[] = {
|
|
||||||
NULL,
|
|
||||||
exact_match_lookup,
|
|
||||||
prefix_match_lookup,
|
|
||||||
};
|
|
||||||
|
|
||||||
typedef enum ros_security_lookup_type_e
|
|
||||||
{
|
|
||||||
ROS_SECURITY_LOOKUP_NODE_OVERRIDE = 0,
|
|
||||||
ROS_SECURITY_LOOKUP_MATCH_EXACT = 1,
|
|
||||||
ROS_SECURITY_LOOKUP_MATCH_PREFIX = 2,
|
|
||||||
} ros_security_lookup_type_t;
|
|
||||||
|
|
||||||
char * g_security_lookup_type_strings[] = {
|
|
||||||
"NODE_OVERRIDE",
|
|
||||||
"MATCH_EXACT",
|
|
||||||
"MATCH_PREFIX"
|
|
||||||
};
|
|
||||||
|
|
||||||
/// Return the directory whose name most closely matches node_name (longest-prefix match),
|
|
||||||
/// scanning under base_dir.
|
|
||||||
/**
|
|
||||||
* By using a prefix match, a node named e.g. "my_node_123" will be able to load and use the
|
|
||||||
* directory "my_node" if no better match exists.
|
|
||||||
* \param[in] base_dir
|
|
||||||
* \param[in] node_name
|
|
||||||
* \param[out] matched_name must be a valid memory address allocated with at least
|
|
||||||
* _TINYDIR_FILENAME_MAX characters.
|
|
||||||
* \return true if a match was found
|
|
||||||
*/
|
|
||||||
static bool get_best_matching_directory(
|
|
||||||
const char * base_dir,
|
|
||||||
const char * node_name,
|
|
||||||
char * matched_name)
|
|
||||||
{
|
|
||||||
size_t max_match_length = 0;
|
|
||||||
tinydir_dir dir;
|
|
||||||
if (NULL == base_dir || NULL == node_name || NULL == matched_name) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
if (-1 == tinydir_open(&dir, base_dir)) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
while (dir.has_next) {
|
|
||||||
tinydir_file file;
|
|
||||||
if (-1 == tinydir_readfile(&dir, &file)) {
|
|
||||||
goto cleanup;
|
|
||||||
}
|
|
||||||
if (file.is_dir) {
|
|
||||||
size_t matched_name_length = strnlen(file.name, sizeof(file.name) - 1);
|
|
||||||
if (
|
|
||||||
0 == strncmp(file.name, node_name, matched_name_length) &&
|
|
||||||
matched_name_length > max_match_length)
|
|
||||||
{
|
|
||||||
max_match_length = matched_name_length;
|
|
||||||
memcpy(matched_name, file.name, max_match_length);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
if (-1 == tinydir_next(&dir)) {
|
|
||||||
goto cleanup;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
cleanup:
|
|
||||||
tinydir_close(&dir);
|
|
||||||
return max_match_length > 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
char * exact_match_lookup(
|
|
||||||
const char * node_name,
|
|
||||||
const char * node_namespace,
|
|
||||||
const char * ros_secure_root_env,
|
|
||||||
const rcl_allocator_t * allocator)
|
|
||||||
{
|
|
||||||
// Perform an exact match for the node's name in directory <root dir>/<namespace>.
|
|
||||||
char * node_secure_root = NULL;
|
|
||||||
// "/" case when root namespace is explicitly passed in
|
|
||||||
if (1 == strlen(node_namespace)) {
|
|
||||||
node_secure_root = rcutils_join_path(ros_secure_root_env, node_name, *allocator);
|
|
||||||
} else {
|
|
||||||
char * node_fqn = NULL;
|
|
||||||
char * node_root_path = NULL;
|
|
||||||
// Combine node namespace with node name
|
|
||||||
// TODO(ros2team): remove the hard-coded value of the root namespace
|
|
||||||
node_fqn = rcutils_format_string(*allocator, "%s%s%s", node_namespace, "/", node_name);
|
|
||||||
// Get native path, ignore the leading forward slash
|
|
||||||
// TODO(ros2team): remove the hard-coded length, use the length of the root namespace instead
|
|
||||||
node_root_path = rcutils_to_native_path(node_fqn + 1, *allocator);
|
|
||||||
node_secure_root = rcutils_join_path(ros_secure_root_env, node_root_path, *allocator);
|
|
||||||
allocator->deallocate(node_fqn, allocator->state);
|
|
||||||
allocator->deallocate(node_root_path, allocator->state);
|
|
||||||
}
|
|
||||||
return node_secure_root;
|
|
||||||
}
|
|
||||||
|
|
||||||
char * prefix_match_lookup(
|
|
||||||
const char * node_name,
|
|
||||||
const char * node_namespace,
|
|
||||||
const char * ros_secure_root_env,
|
|
||||||
const rcl_allocator_t * allocator)
|
|
||||||
{
|
|
||||||
// Perform longest prefix match for the node's name in directory <root dir>/<namespace>.
|
|
||||||
char * node_secure_root = NULL;
|
|
||||||
char matched_dir[_TINYDIR_FILENAME_MAX] = {0};
|
|
||||||
char * base_lookup_dir = NULL;
|
|
||||||
if (strlen(node_namespace) == 1) {
|
|
||||||
base_lookup_dir = (char *) ros_secure_root_env;
|
|
||||||
} else {
|
|
||||||
// TODO(ros2team): remove the hard-coded length, use the length of the root namespace instead.
|
|
||||||
base_lookup_dir = rcutils_join_path(ros_secure_root_env, node_namespace + 1, *allocator);
|
|
||||||
}
|
|
||||||
if (get_best_matching_directory(base_lookup_dir, node_name, matched_dir)) {
|
|
||||||
node_secure_root = rcutils_join_path(base_lookup_dir, matched_dir, *allocator);
|
|
||||||
}
|
|
||||||
if (base_lookup_dir != ros_secure_root_env && NULL != base_lookup_dir) {
|
|
||||||
allocator->deallocate(base_lookup_dir, allocator->state);
|
|
||||||
}
|
|
||||||
return node_secure_root;
|
|
||||||
}
|
|
||||||
|
|
||||||
char * rcl_get_secure_root(
|
|
||||||
const char * node_name,
|
|
||||||
const char * node_namespace,
|
|
||||||
const rcl_allocator_t * allocator)
|
|
||||||
{
|
|
||||||
bool ros_secure_node_override = true;
|
|
||||||
|
|
||||||
// find out if either of the configuration environment variables are set
|
|
||||||
const char * env_buf = NULL;
|
|
||||||
if (NULL == node_name) {
|
|
||||||
return NULL;
|
|
||||||
}
|
|
||||||
if (rcutils_get_env(ROS_SECURITY_NODE_DIRECTORY_VAR_NAME, &env_buf)) {
|
|
||||||
return NULL;
|
|
||||||
}
|
|
||||||
if (!env_buf) {
|
|
||||||
return NULL;
|
|
||||||
}
|
|
||||||
size_t ros_secure_root_size = strlen(env_buf);
|
|
||||||
if (!ros_secure_root_size) {
|
|
||||||
// check root directory if node directory environment variable is empty
|
|
||||||
if (rcutils_get_env(ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME, &env_buf)) {
|
|
||||||
return NULL;
|
|
||||||
}
|
|
||||||
if (!env_buf) {
|
|
||||||
return NULL;
|
|
||||||
}
|
|
||||||
ros_secure_root_size = strlen(env_buf);
|
|
||||||
if (!ros_secure_root_size) {
|
|
||||||
return NULL; // environment variable was empty
|
|
||||||
} else {
|
|
||||||
ros_secure_node_override = false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// found a usable environment variable, copy into our memory before overwriting with next lookup
|
|
||||||
char * ros_secure_root_env =
|
|
||||||
(char *)allocator->allocate(ros_secure_root_size + 1, allocator->state);
|
|
||||||
memcpy(ros_secure_root_env, env_buf, ros_secure_root_size + 1);
|
|
||||||
// TODO(ros2team): This make an assumption on the value and length of the root namespace.
|
|
||||||
// This should likely come from another (rcl/rmw?) function for reuse.
|
|
||||||
// If the namespace is the root namespace ("/"), the secure root is just the node name.
|
|
||||||
|
|
||||||
char * lookup_strategy = NULL;
|
|
||||||
char * node_secure_root = NULL;
|
|
||||||
if (ros_secure_node_override) {
|
|
||||||
node_secure_root = (char *)allocator->allocate(ros_secure_root_size + 1, allocator->state);
|
|
||||||
memcpy(node_secure_root, ros_secure_root_env, ros_secure_root_size + 1);
|
|
||||||
lookup_strategy = g_security_lookup_type_strings[ROS_SECURITY_LOOKUP_NODE_OVERRIDE];
|
|
||||||
|
|
||||||
} else {
|
|
||||||
// Check which lookup method to use and invoke the relevant function.
|
|
||||||
const char * ros_security_lookup_type = NULL;
|
|
||||||
if (rcutils_get_env(ROS_SECURITY_LOOKUP_TYPE_VAR_NAME, &ros_security_lookup_type)) {
|
|
||||||
allocator->deallocate(ros_secure_root_env, allocator->state);
|
|
||||||
return NULL;
|
|
||||||
}
|
|
||||||
if (
|
|
||||||
0 == strcmp(
|
|
||||||
ros_security_lookup_type,
|
|
||||||
g_security_lookup_type_strings[ROS_SECURITY_LOOKUP_MATCH_PREFIX]))
|
|
||||||
{
|
|
||||||
node_secure_root = g_security_lookup_fns[ROS_SECURITY_LOOKUP_MATCH_PREFIX]
|
|
||||||
(node_name, node_namespace, ros_secure_root_env, allocator);
|
|
||||||
lookup_strategy = g_security_lookup_type_strings[ROS_SECURITY_LOOKUP_MATCH_PREFIX];
|
|
||||||
} else { /* Default is MATCH_EXACT */
|
|
||||||
node_secure_root = g_security_lookup_fns[ROS_SECURITY_LOOKUP_MATCH_EXACT]
|
|
||||||
(node_name, node_namespace, ros_secure_root_env, allocator);
|
|
||||||
lookup_strategy = g_security_lookup_type_strings[ROS_SECURITY_LOOKUP_MATCH_EXACT];
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (NULL == node_secure_root || !rcutils_is_directory(node_secure_root)) {
|
|
||||||
// Check node_secure_root is not NULL before checking directory
|
|
||||||
if (NULL == node_secure_root) {
|
|
||||||
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
|
|
||||||
"SECURITY ERROR: unable to find a folder matching the node name '%s' in '%s%s'. "
|
|
||||||
"Lookup strategy: %s",
|
|
||||||
node_name, ros_secure_root_env, node_namespace, lookup_strategy);
|
|
||||||
} else {
|
|
||||||
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
|
|
||||||
"SECURITY ERROR: directory '%s' does not exist. Lookup strategy: %s",
|
|
||||||
node_secure_root, lookup_strategy);
|
|
||||||
}
|
|
||||||
allocator->deallocate(ros_secure_root_env, allocator->state);
|
|
||||||
allocator->deallocate(node_secure_root, allocator->state);
|
|
||||||
return NULL;
|
|
||||||
}
|
|
||||||
allocator->deallocate(ros_secure_root_env, allocator->state);
|
|
||||||
return node_secure_root;
|
|
||||||
}
|
|
153
rcl/src/rcl/validate_security_context_name.c
Normal file
153
rcl/src/rcl/validate_security_context_name.c
Normal file
|
@ -0,0 +1,153 @@
|
||||||
|
// Copyright 2020 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/validate_security_context_name.h"
|
||||||
|
|
||||||
|
#include <ctype.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
|
#include <rcutils/snprintf.h>
|
||||||
|
|
||||||
|
#include "rmw/validate_namespace.h"
|
||||||
|
|
||||||
|
#include "rcl/error_handling.h"
|
||||||
|
|
||||||
|
#include "./common.h"
|
||||||
|
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_validate_security_context_name(
|
||||||
|
const char * security_context,
|
||||||
|
int * validation_result,
|
||||||
|
size_t * invalid_index)
|
||||||
|
{
|
||||||
|
if (!security_context) {
|
||||||
|
return RCL_RET_INVALID_ARGUMENT;
|
||||||
|
}
|
||||||
|
return rcl_validate_security_context_name_with_size(
|
||||||
|
security_context, strlen(security_context), validation_result, invalid_index);
|
||||||
|
}
|
||||||
|
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_validate_security_context_name_with_size(
|
||||||
|
const char * security_context,
|
||||||
|
size_t security_context_length,
|
||||||
|
int * validation_result,
|
||||||
|
size_t * invalid_index)
|
||||||
|
{
|
||||||
|
if (!security_context) {
|
||||||
|
return RCL_RET_INVALID_ARGUMENT;
|
||||||
|
}
|
||||||
|
if (!validation_result) {
|
||||||
|
return RCL_RET_INVALID_ARGUMENT;
|
||||||
|
}
|
||||||
|
|
||||||
|
int tmp_validation_result;
|
||||||
|
size_t tmp_invalid_index;
|
||||||
|
rmw_ret_t ret = rmw_validate_namespace_with_size(
|
||||||
|
security_context, security_context_length, &tmp_validation_result, &tmp_invalid_index);
|
||||||
|
if (ret != RMW_RET_OK) {
|
||||||
|
return rcl_convert_rmw_ret_to_rcl_ret(ret);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (tmp_validation_result != RMW_NAMESPACE_VALID &&
|
||||||
|
tmp_validation_result != RMW_NAMESPACE_INVALID_TOO_LONG)
|
||||||
|
{
|
||||||
|
switch (tmp_validation_result) {
|
||||||
|
case RMW_NAMESPACE_INVALID_IS_EMPTY_STRING:
|
||||||
|
*validation_result = RCL_SECURITY_CONTEXT_NAME_INVALID_IS_EMPTY_STRING;
|
||||||
|
break;
|
||||||
|
case RMW_NAMESPACE_INVALID_NOT_ABSOLUTE:
|
||||||
|
*validation_result = RCL_SECURITY_CONTEXT_NAME_INVALID_NOT_ABSOLUTE;
|
||||||
|
break;
|
||||||
|
case RMW_NAMESPACE_INVALID_ENDS_WITH_FORWARD_SLASH:
|
||||||
|
*validation_result = RCL_SECURITY_CONTEXT_NAME_INVALID_ENDS_WITH_FORWARD_SLASH;
|
||||||
|
break;
|
||||||
|
case RMW_NAMESPACE_INVALID_CONTAINS_UNALLOWED_CHARACTERS:
|
||||||
|
*validation_result = RCL_SECURITY_CONTEXT_NAME_INVALID_CONTAINS_UNALLOWED_CHARACTERS;
|
||||||
|
break;
|
||||||
|
case RMW_NAMESPACE_INVALID_CONTAINS_REPEATED_FORWARD_SLASH:
|
||||||
|
*validation_result = RCL_SECURITY_CONTEXT_NAME_INVALID_CONTAINS_REPEATED_FORWARD_SLASH;
|
||||||
|
break;
|
||||||
|
case RMW_NAMESPACE_INVALID_NAME_TOKEN_STARTS_WITH_NUMBER:
|
||||||
|
*validation_result = RCL_SECURITY_CONTEXT_NAME_INVALID_NAME_TOKEN_STARTS_WITH_NUMBER;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
{
|
||||||
|
char default_err_msg[256];
|
||||||
|
// explicitly not taking return value which is number of bytes written
|
||||||
|
int ret = rcutils_snprintf(
|
||||||
|
default_err_msg, sizeof(default_err_msg),
|
||||||
|
"rcl_validate_security_context_name_with_size(): "
|
||||||
|
"unknown rmw_validate_namespace_with_size() result '%d'",
|
||||||
|
tmp_validation_result);
|
||||||
|
if (ret < 0) {
|
||||||
|
RCL_SET_ERROR_MSG(
|
||||||
|
"rcl_validate_security_context_name_with_size(): "
|
||||||
|
"rcutils_snprintf() failed while reporting an unknown validation result");
|
||||||
|
} else {
|
||||||
|
RCL_SET_ERROR_MSG(default_err_msg);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return RCL_RET_ERROR;
|
||||||
|
}
|
||||||
|
if (invalid_index) {
|
||||||
|
*invalid_index = tmp_invalid_index;
|
||||||
|
}
|
||||||
|
return RCL_RET_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
// security_context might be longer that namespace length, check false positives and correct
|
||||||
|
if (RMW_NAMESPACE_INVALID_TOO_LONG == tmp_validation_result) {
|
||||||
|
if (RCL_SECURITY_CONTEXT_NAME_MAX_LENGTH >= security_context_length) {
|
||||||
|
*validation_result = RCL_SECURITY_CONTEXT_NAME_VALID;
|
||||||
|
} else {
|
||||||
|
*validation_result = RCL_SECURITY_CONTEXT_NAME_INVALID_TOO_LONG;
|
||||||
|
if (invalid_index) {
|
||||||
|
*invalid_index = RCL_SECURITY_CONTEXT_NAME_MAX_LENGTH - 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return RCL_RET_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
// everything was ok, set result to valid namespace, avoid setting invalid_index, and return
|
||||||
|
*validation_result = RCL_SECURITY_CONTEXT_NAME_VALID;
|
||||||
|
return RCL_RET_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
const char *
|
||||||
|
rcl_security_context_name_validation_result_string(int validation_result)
|
||||||
|
{
|
||||||
|
switch (validation_result) {
|
||||||
|
case RCL_SECURITY_CONTEXT_NAME_VALID:
|
||||||
|
return NULL;
|
||||||
|
case RCL_SECURITY_CONTEXT_NAME_INVALID_IS_EMPTY_STRING:
|
||||||
|
return "context name must not be empty";
|
||||||
|
case RCL_SECURITY_CONTEXT_NAME_INVALID_NOT_ABSOLUTE:
|
||||||
|
return "context name must be absolute, it must lead with a '/'";
|
||||||
|
case RCL_SECURITY_CONTEXT_NAME_INVALID_ENDS_WITH_FORWARD_SLASH:
|
||||||
|
return "context name must not end with a '/', unless only a '/'";
|
||||||
|
case RCL_SECURITY_CONTEXT_NAME_INVALID_CONTAINS_UNALLOWED_CHARACTERS:
|
||||||
|
return "context name must not contain characters other than alphanumerics, '_', or '/'";
|
||||||
|
case RCL_SECURITY_CONTEXT_NAME_INVALID_CONTAINS_REPEATED_FORWARD_SLASH:
|
||||||
|
return "context name must not contain repeated '/'";
|
||||||
|
case RCL_SECURITY_CONTEXT_NAME_INVALID_NAME_TOKEN_STARTS_WITH_NUMBER:
|
||||||
|
return "context name must not have a token that starts with a number";
|
||||||
|
case RCL_SECURITY_CONTEXT_NAME_INVALID_TOO_LONG:
|
||||||
|
return "context name should not exceed '"
|
||||||
|
RCUTILS_STRINGIFY(RCL_SECURITY_CONTEXT_NAME_MAX_NAME_LENGTH) "'";
|
||||||
|
default:
|
||||||
|
return "unknown result code for rcl context name validation";
|
||||||
|
}
|
||||||
|
}
|
|
@ -98,6 +98,7 @@ function(test_target_function)
|
||||||
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
||||||
LIBRARIES ${PROJECT_NAME}
|
LIBRARIES ${PROJECT_NAME}
|
||||||
AMENT_DEPENDENCIES ${rmw_implementation} "osrf_testing_tools_cpp" "test_msgs"
|
AMENT_DEPENDENCIES ${rmw_implementation} "osrf_testing_tools_cpp" "test_msgs"
|
||||||
|
TIMEOUT 120
|
||||||
${AMENT_GTEST_ARGS}
|
${AMENT_GTEST_ARGS}
|
||||||
)
|
)
|
||||||
|
|
||||||
|
@ -316,8 +317,8 @@ rcl_add_custom_gtest(test_timer${target_suffix}
|
||||||
AMENT_DEPENDENCIES "osrf_testing_tools_cpp"
|
AMENT_DEPENDENCIES "osrf_testing_tools_cpp"
|
||||||
)
|
)
|
||||||
|
|
||||||
rcl_add_custom_gtest(test_security_directory
|
rcl_add_custom_gtest(test_security
|
||||||
SRCS rcl/test_security_directory.cpp
|
SRCS rcl/test_security.cpp
|
||||||
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
||||||
LIBRARIES ${PROJECT_NAME}
|
LIBRARIES ${PROJECT_NAME}
|
||||||
AMENT_DEPENDENCIES "osrf_testing_tools_cpp"
|
AMENT_DEPENDENCIES "osrf_testing_tools_cpp"
|
||||||
|
|
|
@ -18,6 +18,7 @@
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
#include <sstream>
|
#include <sstream>
|
||||||
#include <thread>
|
#include <thread>
|
||||||
|
#include <tuple>
|
||||||
#include <string>
|
#include <string>
|
||||||
#include <set>
|
#include <set>
|
||||||
#include <utility>
|
#include <utility>
|
||||||
|
@ -162,3 +163,134 @@ TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names)
|
||||||
delete node5_ptr;
|
delete node5_ptr;
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
TEST_F(
|
||||||
|
CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names_with_security_contexts)
|
||||||
|
{
|
||||||
|
rcl_ret_t ret;
|
||||||
|
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
|
||||||
|
ret = rcl_init_options_init(&init_options, rcl_get_default_allocator());
|
||||||
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||||
|
{
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str;
|
||||||
|
});
|
||||||
|
rcl_context_t context = rcl_get_zero_initialized_context();
|
||||||
|
const char * security_context_name = "/default";
|
||||||
|
const char * argv[] = {"--ros-args", "--security-context", security_context_name};
|
||||||
|
ret = rcl_init(3, argv, &init_options, &context);
|
||||||
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||||
|
{
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_shutdown(&context)) << rcl_get_error_string().str;
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_context_fini(&context)) << rcl_get_error_string().str;
|
||||||
|
});
|
||||||
|
std::multiset<std::tuple<std::string, std::string, std::string>>
|
||||||
|
expected_nodes, discovered_nodes;
|
||||||
|
|
||||||
|
rcl_node_t node1 = rcl_get_zero_initialized_node();
|
||||||
|
const char * node1_name = "node1";
|
||||||
|
const char * node1_namespace = "/";
|
||||||
|
rcl_node_options_t node1_options = rcl_node_get_default_options();
|
||||||
|
ret = rcl_node_init(&node1, node1_name, node1_namespace, &context, &node1_options);
|
||||||
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
expected_nodes.insert(
|
||||||
|
std::make_tuple(
|
||||||
|
std::string(node1_name),
|
||||||
|
std::string(node1_namespace),
|
||||||
|
std::string(security_context_name)));
|
||||||
|
|
||||||
|
rcl_node_t node2 = rcl_get_zero_initialized_node();
|
||||||
|
const char * node2_name = "node2";
|
||||||
|
const char * node2_namespace = "/";
|
||||||
|
rcl_node_options_t node2_options = rcl_node_get_default_options();
|
||||||
|
ret = rcl_node_init(&node2, node2_name, node2_namespace, &context, &node2_options);
|
||||||
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
expected_nodes.insert(
|
||||||
|
std::make_tuple(
|
||||||
|
std::string(node2_name),
|
||||||
|
std::string(node2_namespace),
|
||||||
|
std::string(security_context_name)));
|
||||||
|
|
||||||
|
rcl_node_t node3 = rcl_get_zero_initialized_node();
|
||||||
|
const char * node3_name = "node3";
|
||||||
|
const char * node3_namespace = "/ns";
|
||||||
|
rcl_node_options_t node3_options = rcl_node_get_default_options();
|
||||||
|
ret = rcl_node_init(&node3, node3_name, node3_namespace, &context, &node3_options);
|
||||||
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
expected_nodes.insert(
|
||||||
|
std::make_tuple(
|
||||||
|
std::string(node3_name),
|
||||||
|
std::string(node3_namespace),
|
||||||
|
std::string(security_context_name)));
|
||||||
|
|
||||||
|
rcl_node_t node4 = rcl_get_zero_initialized_node();
|
||||||
|
const char * node4_name = "node2";
|
||||||
|
const char * node4_namespace = "/ns/ns";
|
||||||
|
rcl_node_options_t node4_options = rcl_node_get_default_options();
|
||||||
|
ret = rcl_node_init(&node4, node4_name, node4_namespace, &context, &node4_options);
|
||||||
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
expected_nodes.insert(
|
||||||
|
std::make_tuple(
|
||||||
|
std::string(node4_name),
|
||||||
|
std::string(node4_namespace),
|
||||||
|
std::string(security_context_name)));
|
||||||
|
|
||||||
|
rcl_node_t node5 = rcl_get_zero_initialized_node();
|
||||||
|
const char * node5_name = "node1";
|
||||||
|
const char * node5_namespace = "/";
|
||||||
|
rcl_node_options_t node5_options = rcl_node_get_default_options();
|
||||||
|
ret = rcl_node_init(&node5, node5_name, node5_namespace, &context, &node5_options);
|
||||||
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
expected_nodes.insert(
|
||||||
|
std::make_tuple(
|
||||||
|
std::string(node5_name),
|
||||||
|
std::string(node5_namespace),
|
||||||
|
std::string(security_context_name)));
|
||||||
|
|
||||||
|
std::this_thread::sleep_for(1s);
|
||||||
|
|
||||||
|
rcutils_string_array_t node_names = rcutils_get_zero_initialized_string_array();
|
||||||
|
rcutils_string_array_t node_namespaces = rcutils_get_zero_initialized_string_array();
|
||||||
|
rcutils_string_array_t security_contexts = rcutils_get_zero_initialized_string_array();
|
||||||
|
ret = rcl_get_node_names_with_security_contexts(
|
||||||
|
&node1, node1_options.allocator, &node_names, &node_namespaces, &security_contexts);
|
||||||
|
ASSERT_EQ(RCUTILS_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
|
||||||
|
std::stringstream ss;
|
||||||
|
ss << "[test_rcl_get_node_names]: Found node names:" << std::endl;
|
||||||
|
for (size_t i = 0; i < node_names.size; ++i) {
|
||||||
|
ss << node_names.data[i] << std::endl;
|
||||||
|
}
|
||||||
|
EXPECT_EQ(node_names.size, node_namespaces.size) << ss.str();
|
||||||
|
|
||||||
|
for (size_t i = 0; i < node_names.size; ++i) {
|
||||||
|
discovered_nodes.insert(
|
||||||
|
std::make_tuple(
|
||||||
|
std::string(node_names.data[i]),
|
||||||
|
std::string(node_namespaces.data[i]),
|
||||||
|
std::string(security_contexts.data[i])));
|
||||||
|
}
|
||||||
|
EXPECT_EQ(discovered_nodes, expected_nodes);
|
||||||
|
|
||||||
|
ret = rcutils_string_array_fini(&node_names);
|
||||||
|
ASSERT_EQ(RCUTILS_RET_OK, ret);
|
||||||
|
|
||||||
|
ret = rcutils_string_array_fini(&node_namespaces);
|
||||||
|
ASSERT_EQ(RCUTILS_RET_OK, ret);
|
||||||
|
|
||||||
|
ret = rcl_node_fini(&node1);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
|
||||||
|
ret = rcl_node_fini(&node2);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
|
||||||
|
ret = rcl_node_fini(&node3);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
|
||||||
|
ret = rcl_node_fini(&node4);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
|
||||||
|
ret = rcl_node_fini(&node5);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
}
|
||||||
|
|
|
@ -364,7 +364,7 @@ TEST_F(
|
||||||
&this->node, &allocator, fqdn.c_str(), false,
|
&this->node, &allocator, fqdn.c_str(), false,
|
||||||
&topic_endpoint_info_array_pub);
|
&topic_endpoint_info_array_pub);
|
||||||
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
|
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
|
||||||
EXPECT_EQ(topic_endpoint_info_array_pub.size, 1u) << "Expected one publisher";
|
ASSERT_EQ(topic_endpoint_info_array_pub.size, 1u) << "Expected one publisher";
|
||||||
rmw_topic_endpoint_info_t topic_endpoint_info_pub = topic_endpoint_info_array_pub.info_array[0];
|
rmw_topic_endpoint_info_t topic_endpoint_info_pub = topic_endpoint_info_array_pub.info_array[0];
|
||||||
EXPECT_STREQ(topic_endpoint_info_pub.node_name, this->test_graph_node_name);
|
EXPECT_STREQ(topic_endpoint_info_pub.node_name, this->test_graph_node_name);
|
||||||
EXPECT_STREQ(topic_endpoint_info_pub.node_namespace, "/");
|
EXPECT_STREQ(topic_endpoint_info_pub.node_namespace, "/");
|
||||||
|
@ -377,7 +377,7 @@ TEST_F(
|
||||||
&this->node, &allocator, fqdn.c_str(), false,
|
&this->node, &allocator, fqdn.c_str(), false,
|
||||||
&topic_endpoint_info_array_sub);
|
&topic_endpoint_info_array_sub);
|
||||||
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
|
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
|
||||||
EXPECT_EQ(topic_endpoint_info_array_sub.size, 1u) << "Expected one subscription";
|
ASSERT_EQ(topic_endpoint_info_array_sub.size, 1u) << "Expected one subscription";
|
||||||
rmw_topic_endpoint_info_t topic_endpoint_info_sub = topic_endpoint_info_array_sub.info_array[0];
|
rmw_topic_endpoint_info_t topic_endpoint_info_sub = topic_endpoint_info_array_sub.info_array[0];
|
||||||
EXPECT_STREQ(topic_endpoint_info_sub.node_name, this->test_graph_node_name);
|
EXPECT_STREQ(topic_endpoint_info_sub.node_name, this->test_graph_node_name);
|
||||||
EXPECT_STREQ(topic_endpoint_info_sub.node_namespace, "/");
|
EXPECT_STREQ(topic_endpoint_info_sub.node_namespace, "/");
|
||||||
|
|
|
@ -120,14 +120,11 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors)
|
||||||
{
|
{
|
||||||
osrf_testing_tools_cpp::memory_tools::disable_monitoring_in_all_threads();
|
osrf_testing_tools_cpp::memory_tools::disable_monitoring_in_all_threads();
|
||||||
rcl_ret_t ret = rcl_node_fini(&invalid_node);
|
rcl_ret_t ret = rcl_node_fini(&invalid_node);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_context_fini(&invalid_context)) << rcl_get_error_string().str;
|
||||||
EXPECT_EQ(RCL_RET_OK, ret);
|
EXPECT_EQ(RCL_RET_OK, ret);
|
||||||
});
|
});
|
||||||
ret = rcl_shutdown(&invalid_context); // Shutdown to invalidate the node.
|
ret = rcl_shutdown(&invalid_context); // Shutdown to invalidate the node.
|
||||||
ASSERT_EQ(RCL_RET_OK, ret);
|
ASSERT_EQ(RCL_RET_OK, ret);
|
||||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
|
||||||
{
|
|
||||||
EXPECT_EQ(RCL_RET_OK, rcl_context_fini(&invalid_context)) << rcl_get_error_string().str;
|
|
||||||
});
|
|
||||||
rcl_context_t context = rcl_get_zero_initialized_context();
|
rcl_context_t context = rcl_get_zero_initialized_context();
|
||||||
ret = rcl_init(0, nullptr, &init_options, &context);
|
ret = rcl_init(0, nullptr, &init_options, &context);
|
||||||
ASSERT_EQ(RCL_RET_OK, ret);
|
ASSERT_EQ(RCL_RET_OK, ret);
|
||||||
|
|
221
rcl/test/rcl/test_security.cpp
Normal file
221
rcl/test/rcl/test_security.cpp
Normal file
|
@ -0,0 +1,221 @@
|
||||||
|
// Copyright 2018-2020 Amazon.com, Inc. or its affiliates. All Rights Reserved.
|
||||||
|
//
|
||||||
|
// 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 <gtest/gtest.h>
|
||||||
|
|
||||||
|
#include <algorithm>
|
||||||
|
#include <cstring>
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
#include "rcl/security.h"
|
||||||
|
#include "rcl/error_handling.h"
|
||||||
|
|
||||||
|
#include "rcutils/filesystem.h"
|
||||||
|
|
||||||
|
#include "rmw/error_handling.h"
|
||||||
|
|
||||||
|
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
||||||
|
|
||||||
|
|
||||||
|
#define TEST_SECURITY_DIRECTORY_RESOURCES_DIR_NAME "/test_security_directory"
|
||||||
|
#define TEST_SECURITY_CONTEXT "dummy_security_context"
|
||||||
|
#define TEST_SECURITY_CONTEXT_ABSOLUTE "/" TEST_SECURITY_CONTEXT
|
||||||
|
|
||||||
|
#ifndef _WIN32
|
||||||
|
# define PATH_SEPARATOR "/"
|
||||||
|
#else
|
||||||
|
# define PATH_SEPARATOR "\\"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
char g_envstring[512] = {0};
|
||||||
|
|
||||||
|
static int putenv_wrapper(const char * env_var)
|
||||||
|
{
|
||||||
|
#ifdef _WIN32
|
||||||
|
return _putenv(env_var);
|
||||||
|
#else
|
||||||
|
return putenv(const_cast<char *>(env_var));
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
static int unsetenv_wrapper(const char * var_name)
|
||||||
|
{
|
||||||
|
#ifdef _WIN32
|
||||||
|
// On windows, putenv("VAR=") deletes VAR from environment
|
||||||
|
std::string var(var_name);
|
||||||
|
var += "=";
|
||||||
|
return _putenv(var.c_str());
|
||||||
|
#else
|
||||||
|
return unsetenv(var_name);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
class TestGetSecureRoot : public ::testing::Test
|
||||||
|
{
|
||||||
|
protected:
|
||||||
|
void SetUp() final
|
||||||
|
{
|
||||||
|
// Reset rcutil error global state in case a previously
|
||||||
|
// running test has failed.
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
// Always make sure the variable we set is unset at the beginning of a test
|
||||||
|
unsetenv_wrapper(ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME);
|
||||||
|
unsetenv_wrapper(ROS_SECURITY_DIRECTORY_OVERRIDE);
|
||||||
|
unsetenv_wrapper(ROS_SECURITY_STRATEGY_VAR_NAME);
|
||||||
|
unsetenv_wrapper(ROS_SECURITY_ENABLE_VAR_NAME);
|
||||||
|
allocator = rcl_get_default_allocator();
|
||||||
|
root_path = nullptr;
|
||||||
|
secure_root = nullptr;
|
||||||
|
base_lookup_dir_fqn = nullptr;
|
||||||
|
}
|
||||||
|
|
||||||
|
void TearDown() final
|
||||||
|
{
|
||||||
|
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||||
|
{
|
||||||
|
allocator.deallocate(root_path, allocator.state);
|
||||||
|
});
|
||||||
|
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||||
|
{
|
||||||
|
allocator.deallocate(secure_root, allocator.state);
|
||||||
|
});
|
||||||
|
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||||
|
{
|
||||||
|
allocator.deallocate(base_lookup_dir_fqn, allocator.state);
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_base_lookup_dir_fqn(const char * resource_dir, const char * resource_dir_name)
|
||||||
|
{
|
||||||
|
base_lookup_dir_fqn = rcutils_join_path(
|
||||||
|
resource_dir, resource_dir_name, allocator);
|
||||||
|
std::string putenv_input = ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME "=";
|
||||||
|
putenv_input += base_lookup_dir_fqn;
|
||||||
|
memcpy(
|
||||||
|
g_envstring, putenv_input.c_str(),
|
||||||
|
std::min(putenv_input.length(), sizeof(g_envstring) - 1));
|
||||||
|
putenv_wrapper(g_envstring);
|
||||||
|
}
|
||||||
|
|
||||||
|
rcl_allocator_t allocator;
|
||||||
|
char * root_path;
|
||||||
|
char * secure_root;
|
||||||
|
char * base_lookup_dir_fqn;
|
||||||
|
};
|
||||||
|
|
||||||
|
TEST_F(TestGetSecureRoot, failureScenarios) {
|
||||||
|
EXPECT_EQ(
|
||||||
|
rcl_get_secure_root(TEST_SECURITY_CONTEXT_ABSOLUTE, &allocator),
|
||||||
|
(char *) NULL);
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
putenv_wrapper(ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME "=" TEST_RESOURCES_DIRECTORY);
|
||||||
|
|
||||||
|
/* Security directory is set, but there's no matching directory */
|
||||||
|
/// Wrong security context
|
||||||
|
EXPECT_EQ(
|
||||||
|
rcl_get_secure_root("some_other_security_context", &allocator),
|
||||||
|
(char *) NULL);
|
||||||
|
rcl_reset_error();
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(TestGetSecureRoot, successScenarios_local_exactMatch) {
|
||||||
|
putenv_wrapper(
|
||||||
|
ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME "="
|
||||||
|
TEST_RESOURCES_DIRECTORY TEST_SECURITY_DIRECTORY_RESOURCES_DIR_NAME);
|
||||||
|
|
||||||
|
secure_root = rcl_get_secure_root(TEST_SECURITY_CONTEXT_ABSOLUTE, &allocator);
|
||||||
|
std::string secure_root_str(secure_root);
|
||||||
|
ASSERT_STREQ(
|
||||||
|
TEST_SECURITY_CONTEXT,
|
||||||
|
secure_root_str.substr(secure_root_str.size() - strlen(TEST_SECURITY_CONTEXT)).c_str());
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(TestGetSecureRoot, successScenarios_local_exactMatch_multipleTokensName) {
|
||||||
|
putenv_wrapper(ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME "=" TEST_RESOURCES_DIRECTORY);
|
||||||
|
|
||||||
|
secure_root = rcl_get_secure_root(
|
||||||
|
TEST_SECURITY_DIRECTORY_RESOURCES_DIR_NAME PATH_SEPARATOR TEST_SECURITY_CONTEXT, &allocator);
|
||||||
|
std::string secure_root_str(secure_root);
|
||||||
|
ASSERT_STREQ(
|
||||||
|
TEST_SECURITY_CONTEXT,
|
||||||
|
secure_root_str.substr(secure_root_str.size() - strlen(TEST_SECURITY_CONTEXT)).c_str());
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(TestGetSecureRoot, nodeSecurityDirectoryOverride_validDirectory) {
|
||||||
|
/* Specify a valid directory */
|
||||||
|
putenv_wrapper(ROS_SECURITY_DIRECTORY_OVERRIDE "=" TEST_RESOURCES_DIRECTORY);
|
||||||
|
root_path = rcl_get_secure_root(
|
||||||
|
"name shouldn't matter", &allocator);
|
||||||
|
ASSERT_STREQ(root_path, TEST_RESOURCES_DIRECTORY);
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(
|
||||||
|
TestGetSecureRoot,
|
||||||
|
nodeSecurityDirectoryOverride_validDirectory_overrideRootDirectoryAttempt) {
|
||||||
|
/* Setting root dir has no effect */
|
||||||
|
putenv_wrapper(ROS_SECURITY_DIRECTORY_OVERRIDE "=" TEST_RESOURCES_DIRECTORY);
|
||||||
|
root_path = rcl_get_secure_root("name shouldn't matter", &allocator);
|
||||||
|
putenv_wrapper(ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME "=" TEST_RESOURCES_DIRECTORY);
|
||||||
|
ASSERT_STREQ(root_path, TEST_RESOURCES_DIRECTORY);
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(TestGetSecureRoot, nodeSecurityDirectoryOverride_invalidDirectory) {
|
||||||
|
/* The override provided should exist. Providing correct node/namespace/root dir won't help
|
||||||
|
* if the node override is invalid. */
|
||||||
|
putenv_wrapper(
|
||||||
|
ROS_SECURITY_DIRECTORY_OVERRIDE
|
||||||
|
"=TheresN_oWayThi_sDirectory_Exists_hence_this_should_fail");
|
||||||
|
EXPECT_EQ(
|
||||||
|
rcl_get_secure_root(TEST_SECURITY_CONTEXT_ABSOLUTE, &allocator),
|
||||||
|
(char *) NULL);
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(TestGetSecureRoot, test_get_security_options) {
|
||||||
|
/* The override provided should exist. Providing correct security context name/root dir
|
||||||
|
* won't help if the node override is invalid. */
|
||||||
|
rmw_security_options_t options = rmw_get_zero_initialized_security_options();
|
||||||
|
putenv_wrapper(ROS_SECURITY_ENABLE_VAR_NAME "=false");
|
||||||
|
rcl_ret_t ret = rcl_get_security_options_from_environment(
|
||||||
|
"doesn't matter at all", &allocator, &options);
|
||||||
|
ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
|
||||||
|
EXPECT_EQ(RMW_SECURITY_ENFORCEMENT_PERMISSIVE, options.enforce_security);
|
||||||
|
EXPECT_EQ(NULL, options.security_root_path);
|
||||||
|
|
||||||
|
putenv_wrapper(ROS_SECURITY_ENABLE_VAR_NAME "=true");
|
||||||
|
putenv_wrapper(ROS_SECURITY_STRATEGY_VAR_NAME "=Enforce");
|
||||||
|
|
||||||
|
putenv_wrapper(
|
||||||
|
ROS_SECURITY_DIRECTORY_OVERRIDE "=" TEST_RESOURCES_DIRECTORY);
|
||||||
|
ret = rcl_get_security_options_from_environment(
|
||||||
|
"doesn't matter at all", &allocator, &options);
|
||||||
|
ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
|
||||||
|
EXPECT_EQ(RMW_SECURITY_ENFORCEMENT_ENFORCE, options.enforce_security);
|
||||||
|
EXPECT_STREQ(TEST_RESOURCES_DIRECTORY, options.security_root_path);
|
||||||
|
EXPECT_EQ(RMW_RET_OK, rmw_security_options_fini(&options, &allocator));
|
||||||
|
|
||||||
|
options = rmw_get_zero_initialized_security_options();
|
||||||
|
unsetenv_wrapper(ROS_SECURITY_DIRECTORY_OVERRIDE);
|
||||||
|
putenv_wrapper(
|
||||||
|
ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME "="
|
||||||
|
TEST_RESOURCES_DIRECTORY TEST_SECURITY_DIRECTORY_RESOURCES_DIR_NAME);
|
||||||
|
ret = rcl_get_security_options_from_environment(
|
||||||
|
TEST_SECURITY_CONTEXT_ABSOLUTE, &allocator, &options);
|
||||||
|
ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
|
||||||
|
EXPECT_EQ(RMW_SECURITY_ENFORCEMENT_ENFORCE, options.enforce_security);
|
||||||
|
EXPECT_STREQ(
|
||||||
|
TEST_RESOURCES_DIRECTORY TEST_SECURITY_DIRECTORY_RESOURCES_DIR_NAME
|
||||||
|
PATH_SEPARATOR TEST_SECURITY_CONTEXT, options.security_root_path);
|
||||||
|
}
|
|
@ -1,226 +0,0 @@
|
||||||
// Copyright 2018 Amazon.com, Inc. or its affiliates. All Rights Reserved.
|
|
||||||
//
|
|
||||||
// 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 <gtest/gtest.h>
|
|
||||||
|
|
||||||
#include <string>
|
|
||||||
#include <algorithm>
|
|
||||||
#include "rcl/security_directory.h"
|
|
||||||
#include "rcutils/filesystem.h"
|
|
||||||
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
|
||||||
#include "rcl/error_handling.h"
|
|
||||||
|
|
||||||
#define ROOT_NAMESPACE "/"
|
|
||||||
#define TEST_SECURITY_DIRECTORY_RESOURCES_DIR_NAME "test_security_directory"
|
|
||||||
#define TEST_NODE_NAME "dummy_node"
|
|
||||||
#define TEST_NODE_NAMESPACE ROOT_NAMESPACE TEST_SECURITY_DIRECTORY_RESOURCES_DIR_NAME
|
|
||||||
|
|
||||||
char g_envstring[512] = {0};
|
|
||||||
|
|
||||||
static int putenv_wrapper(const char * env_var)
|
|
||||||
{
|
|
||||||
#ifdef _WIN32
|
|
||||||
return _putenv(env_var);
|
|
||||||
#else
|
|
||||||
return putenv(reinterpret_cast<char *>(const_cast<char *>(env_var)));
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
static int unsetenv_wrapper(const char * var_name)
|
|
||||||
{
|
|
||||||
#ifdef _WIN32
|
|
||||||
// On windows, putenv("VAR=") deletes VAR from environment
|
|
||||||
std::string var(var_name);
|
|
||||||
var += "=";
|
|
||||||
return _putenv(var.c_str());
|
|
||||||
#else
|
|
||||||
return unsetenv(var_name);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
class TestGetSecureRoot : public ::testing::Test
|
|
||||||
{
|
|
||||||
protected:
|
|
||||||
void SetUp() final
|
|
||||||
{
|
|
||||||
// Reset rcutil error global state in case a previously
|
|
||||||
// running test has failed.
|
|
||||||
rcl_reset_error();
|
|
||||||
|
|
||||||
// Always make sure the variable we set is unset at the beginning of a test
|
|
||||||
unsetenv_wrapper(ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME);
|
|
||||||
unsetenv_wrapper(ROS_SECURITY_NODE_DIRECTORY_VAR_NAME);
|
|
||||||
unsetenv_wrapper(ROS_SECURITY_LOOKUP_TYPE_VAR_NAME);
|
|
||||||
allocator = rcl_get_default_allocator();
|
|
||||||
root_path = nullptr;
|
|
||||||
secure_root = nullptr;
|
|
||||||
base_lookup_dir_fqn = nullptr;
|
|
||||||
}
|
|
||||||
|
|
||||||
void TearDown() final
|
|
||||||
{
|
|
||||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
|
||||||
{
|
|
||||||
allocator.deallocate(root_path, allocator.state);
|
|
||||||
});
|
|
||||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
|
||||||
{
|
|
||||||
allocator.deallocate(secure_root, allocator.state);
|
|
||||||
});
|
|
||||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
|
||||||
{
|
|
||||||
allocator.deallocate(base_lookup_dir_fqn, allocator.state);
|
|
||||||
});
|
|
||||||
}
|
|
||||||
|
|
||||||
void set_base_lookup_dir_fqn(const char * resource_dir, const char * resource_dir_name)
|
|
||||||
{
|
|
||||||
base_lookup_dir_fqn = rcutils_join_path(
|
|
||||||
resource_dir, resource_dir_name, allocator);
|
|
||||||
std::string putenv_input = ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME "=";
|
|
||||||
putenv_input += base_lookup_dir_fqn;
|
|
||||||
memcpy(
|
|
||||||
g_envstring, putenv_input.c_str(),
|
|
||||||
std::min(putenv_input.length(), sizeof(g_envstring) - 1));
|
|
||||||
putenv_wrapper(g_envstring);
|
|
||||||
}
|
|
||||||
|
|
||||||
rcl_allocator_t allocator;
|
|
||||||
char * root_path;
|
|
||||||
char * secure_root;
|
|
||||||
char * base_lookup_dir_fqn;
|
|
||||||
};
|
|
||||||
|
|
||||||
TEST_F(TestGetSecureRoot, failureScenarios) {
|
|
||||||
ASSERT_EQ(
|
|
||||||
rcl_get_secure_root(TEST_NODE_NAME, TEST_NODE_NAMESPACE, &allocator),
|
|
||||||
(char *) NULL);
|
|
||||||
|
|
||||||
putenv_wrapper(ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME "=" TEST_RESOURCES_DIRECTORY);
|
|
||||||
|
|
||||||
/* Security directory is set, but there's no matching directory */
|
|
||||||
/// Wrong namespace
|
|
||||||
ASSERT_EQ(
|
|
||||||
rcl_get_secure_root(TEST_NODE_NAME, "/some_other_namespace", &allocator),
|
|
||||||
(char *) NULL);
|
|
||||||
/// Wrong node name
|
|
||||||
ASSERT_EQ(
|
|
||||||
rcl_get_secure_root("not_" TEST_NODE_NAME, TEST_NODE_NAMESPACE, &allocator),
|
|
||||||
(char *) NULL);
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST_F(TestGetSecureRoot, successScenarios_local_exactMatch) {
|
|
||||||
putenv_wrapper(ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME "=" TEST_RESOURCES_DIRECTORY);
|
|
||||||
|
|
||||||
/* --------------------------
|
|
||||||
* Namespace : Custom (local)
|
|
||||||
* Match type : Exact
|
|
||||||
* --------------------------
|
|
||||||
* Root: ${CMAKE_BINARY_DIR}/tests/resources
|
|
||||||
* Namespace: /test_security_directory
|
|
||||||
* Node: dummy_node
|
|
||||||
*/
|
|
||||||
secure_root = rcl_get_secure_root(TEST_NODE_NAME, TEST_NODE_NAMESPACE, &allocator);
|
|
||||||
std::string secure_root_str(secure_root);
|
|
||||||
ASSERT_STREQ(
|
|
||||||
TEST_NODE_NAME,
|
|
||||||
secure_root_str.substr(secure_root_str.size() - (sizeof(TEST_NODE_NAME) - 1)).c_str());
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST_F(TestGetSecureRoot, successScenarios_local_prefixMatch) {
|
|
||||||
putenv_wrapper(ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME "=" TEST_RESOURCES_DIRECTORY);
|
|
||||||
secure_root = rcl_get_secure_root(TEST_NODE_NAME, TEST_NODE_NAMESPACE, &allocator);
|
|
||||||
|
|
||||||
/* --------------------------
|
|
||||||
* Namespace : Custom (local)
|
|
||||||
* Match type : Prefix
|
|
||||||
* --------------------------
|
|
||||||
* Root: ${CMAKE_BINARY_DIR}/tests/resources
|
|
||||||
* Namespace: /test_security_directory
|
|
||||||
* Node: dummy_node_and_some_suffix_added */
|
|
||||||
root_path = rcl_get_secure_root(
|
|
||||||
TEST_NODE_NAME "_and_some_suffix_added", TEST_NODE_NAMESPACE, &allocator);
|
|
||||||
ASSERT_STRNE(root_path, secure_root);
|
|
||||||
putenv_wrapper(ROS_SECURITY_LOOKUP_TYPE_VAR_NAME "=MATCH_PREFIX");
|
|
||||||
root_path = rcl_get_secure_root(
|
|
||||||
TEST_NODE_NAME "_and_some_suffix_added", TEST_NODE_NAMESPACE, &allocator);
|
|
||||||
ASSERT_STREQ(root_path, secure_root);
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST_F(TestGetSecureRoot, successScenarios_root_exactMatch) {
|
|
||||||
putenv_wrapper(ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME "=" TEST_RESOURCES_DIRECTORY);
|
|
||||||
putenv_wrapper(ROS_SECURITY_LOOKUP_TYPE_VAR_NAME "=MATCH_PREFIX");
|
|
||||||
secure_root = rcl_get_secure_root(TEST_NODE_NAME, TEST_NODE_NAMESPACE, &allocator);
|
|
||||||
|
|
||||||
/* Include the namespace as part of the root security directory and test root namespace */
|
|
||||||
set_base_lookup_dir_fqn(TEST_RESOURCES_DIRECTORY, TEST_SECURITY_DIRECTORY_RESOURCES_DIR_NAME);
|
|
||||||
/* --------------------------
|
|
||||||
* Namespace : Root
|
|
||||||
* Match type : Exact
|
|
||||||
* --------------------------
|
|
||||||
* Root: ${CMAKE_BINARY_DIR}/tests/resources/test_security_directory
|
|
||||||
* Namespace: /
|
|
||||||
* Node: dummy_node */
|
|
||||||
root_path = rcl_get_secure_root(TEST_NODE_NAME, ROOT_NAMESPACE, &allocator);
|
|
||||||
ASSERT_STREQ(root_path, secure_root);
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST_F(TestGetSecureRoot, successScenarios_root_prefixMatch) {
|
|
||||||
putenv_wrapper(ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME "=" TEST_RESOURCES_DIRECTORY);
|
|
||||||
putenv_wrapper(ROS_SECURITY_LOOKUP_TYPE_VAR_NAME "=MATCH_PREFIX");
|
|
||||||
secure_root = rcl_get_secure_root(TEST_NODE_NAME, TEST_NODE_NAMESPACE, &allocator);
|
|
||||||
|
|
||||||
/* Include the namespace as part of the root security directory and test root namespace */
|
|
||||||
set_base_lookup_dir_fqn(TEST_RESOURCES_DIRECTORY, TEST_SECURITY_DIRECTORY_RESOURCES_DIR_NAME);
|
|
||||||
/* --------------------------
|
|
||||||
* Namespace : Root
|
|
||||||
* Match type : Prefix
|
|
||||||
* --------------------------
|
|
||||||
* Root dir: ${CMAKE_BINARY_DIR}/tests/resources/test_security_directory
|
|
||||||
* Namespace: /
|
|
||||||
* Node: dummy_node_and_some_suffix_added */
|
|
||||||
root_path = rcl_get_secure_root(
|
|
||||||
TEST_NODE_NAME "_and_some_suffix_added", ROOT_NAMESPACE, &allocator);
|
|
||||||
ASSERT_STREQ(root_path, secure_root);
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST_F(TestGetSecureRoot, nodeSecurityDirectoryOverride_validDirectory) {
|
|
||||||
/* Specify a valid directory */
|
|
||||||
putenv_wrapper(ROS_SECURITY_NODE_DIRECTORY_VAR_NAME "=" TEST_RESOURCES_DIRECTORY);
|
|
||||||
root_path = rcl_get_secure_root(
|
|
||||||
"name shouldn't matter", "namespace shouldn't matter", &allocator);
|
|
||||||
ASSERT_STREQ(root_path, TEST_RESOURCES_DIRECTORY);
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST_F(
|
|
||||||
TestGetSecureRoot,
|
|
||||||
nodeSecurityDirectoryOverride_validDirectory_overrideRootDirectoryAttempt) {
|
|
||||||
/* Setting root dir has no effect */
|
|
||||||
putenv_wrapper(ROS_SECURITY_NODE_DIRECTORY_VAR_NAME "=" TEST_RESOURCES_DIRECTORY);
|
|
||||||
root_path = rcl_get_secure_root(
|
|
||||||
"name shouldn't matter", "namespace shouldn't matter", &allocator);
|
|
||||||
putenv_wrapper(ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME "=" TEST_RESOURCES_DIRECTORY);
|
|
||||||
ASSERT_STREQ(root_path, TEST_RESOURCES_DIRECTORY);
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST_F(TestGetSecureRoot, nodeSecurityDirectoryOverride_invalidDirectory) {
|
|
||||||
/* The override provided should exist. Providing correct node/namespace/root dir won't help
|
|
||||||
* if the node override is invalid. */
|
|
||||||
putenv_wrapper(
|
|
||||||
ROS_SECURITY_NODE_DIRECTORY_VAR_NAME
|
|
||||||
"=TheresN_oWayThi_sDirectory_Exists_hence_this_would_fail");
|
|
||||||
ASSERT_EQ(
|
|
||||||
rcl_get_secure_root(TEST_NODE_NAME, TEST_NODE_NAMESPACE, &allocator),
|
|
||||||
(char *) NULL);
|
|
||||||
}
|
|
Loading…
Add table
Add a link
Reference in a new issue