Skip to content

Commit

Permalink
[env] Add set_env_var function (#150)
Browse files Browse the repository at this point in the history
* [env] Add `set_env_var` function

This commit adds the `set_env_var` function, which is essentially an
`rcpputils` wrapper around `rcutils_set_env`.

In doing so, also:
- Rename `get_env.{hpp,cpp}` to `env.{hpp,cpp}`
- Update FEATURES.md with new signature

Signed-off-by: Abrar Rahman Protyasha <aprotyas@u.rochester.edu>

* Add tests for `set_env_var` function

Also, renamed `test_get_env.cpp` to `test_env.cpp` to reflect
the addition of a new function.

Signed-off-by: Abrar Rahman Protyasha <aprotyas@u.rochester.edu>

* Change `get_env.hpp` header includes to `env.hpp`

Signed-off-by: Abrar Rahman Protyasha <aprotyas@u.rochester.edu>

* Re-add (and deprecate) `get_env.hpp`

It's better to deprecate the header on a tick-tock cycle rather than
removing it outright, so this commit reverts the deletion and actually
deprecates the header.

Signed-off-by: Abrar Rahman Protyasha <aprotyas@u.rochester.edu>
  • Loading branch information
aprotyas authored Nov 11, 2021
1 parent ce44a14 commit cb117a5
Show file tree
Hide file tree
Showing 9 changed files with 177 additions and 63 deletions.
8 changes: 4 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ add_library(${PROJECT_NAME}
src/asserts.cpp
src/filesystem_helper.cpp
src/find_library.cpp
src/get_env.cpp
src/env.cpp
src/shared_library.cpp)
target_include_directories(${PROJECT_NAME} PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
Expand Down Expand Up @@ -69,13 +69,13 @@ if(BUILD_TESTING)

ament_add_gtest(test_join test/test_join.cpp)

ament_add_gtest(test_get_env test/test_get_env.cpp
ament_add_gtest(test_env test/test_env.cpp
ENV
EMPTY_TEST=
NORMAL_TEST=foo
)
ament_target_dependencies(test_get_env rcutils)
target_link_libraries(test_get_env ${PROJECT_NAME})
ament_target_dependencies(test_env rcutils)
target_link_libraries(test_env ${PROJECT_NAME})

ament_add_gtest(test_scope_exit test/test_scope_exit.cpp)
target_link_libraries(test_scope_exit ${PROJECT_NAME})
Expand Down
2 changes: 1 addition & 1 deletion docs/FEATURES.md
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@ The `rcpputils/process.hpp` header contains process utilities.
Namely, this header provides the `rcpputils::get_executable_name()` function, which retrieves and returns the current program name as a string.

## Environment helpers {#environment-helpers}
The `rcpputils/get_env.hpp` header provides functionality to lookup the value of a provided environment variable through the `rcpputils::get_env_var(const char *)` function.
The `rcpputils/env.hpp` header provides functionality to lookup the value of a provided environment variable through the `rcpputils::get_env_var(const char *)` function and set/un-set the value of a named, process-scoped environment variable through the `rcpputils::set_env_var(const char *, const char *)` function.

## Scope guard support {#scope-guard-support}
Support for a general-purpose scope guard is provided in the `rcpputils/scope_exit.hpp` header.
Expand Down
67 changes: 67 additions & 0 deletions include/rcpputils/env.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
// Copyright (c) 2020, Open Source Robotics Foundation, Inc.
// All rights reserved.
//
// Software License Agreement (BSD License 2.0)
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above
// copyright notice, this list of conditions and the following
// disclaimer in the documentation and/or other materials provided
// with the distribution.
// * Neither the name of the copyright holders nor the names of its
// contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

#ifndef RCPPUTILS__ENV_HPP_
#define RCPPUTILS__ENV_HPP_

#include <string>

#include "rcpputils/visibility_control.hpp"

namespace rcpputils
{

/// Retrieve the value of the given environment variable if it exists, or "".
/*
* \param[in] env_var the name of the environment variable
* \return The value of the environment variable if it exists, or "".
* \throws std::runtime_error on error
*/
RCPPUTILS_PUBLIC
std::string get_env_var(const char * env_var);

/// Set/un-set a process-scoped environment variable.
/*
* \param[in] env_var The name of the environment variable.
* \param[in] env_value Value to set the environment variable to, or `NULL`
* to un-set.
* \return Boolean representing whether the operation was successful.
* \throws std::runtime_error if env_name is invalid/NULL, or if setting
* the environment variable fails.
*
*/
RCPPUTILS_PUBLIC
bool set_env_var(const char * env_var, const char * env_value);

} // namespace rcpputils

#endif // RCPPUTILS__ENV_HPP_
23 changes: 7 additions & 16 deletions include/rcpputils/get_env.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,22 +33,13 @@
#ifndef RCPPUTILS__GET_ENV_HPP_
#define RCPPUTILS__GET_ENV_HPP_

#include <string>
#ifdef _MSC_VER
#pragma message \
("rcpputils/get_env.hpp has been deprecated, please include rcpputils/env.hpp instead")
#else
#warning rcpputils/get_env.hpp has been deprecated, please include rcpputils/env.hpp instead
#endif

#include "rcpputils/visibility_control.hpp"

namespace rcpputils
{

/// Retrieve the value of the given environment variable if it exists, or "".
/*
* \param[in] env_var the name of the environment variable
* \return The value of the environment variable if it exists, or "".
* \throws std::runtime_error on error
*/
RCPPUTILS_PUBLIC
std::string get_env_var(const char * env_var);

} // namespace rcpputils
#include "rcpputils/env.hpp"

#endif // RCPPUTILS__GET_ENV_HPP_
14 changes: 13 additions & 1 deletion src/get_env.cpp → src/env.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,9 @@
#include <string>

#include "rcutils/env.h"
#include "rcutils/error_handling.h"

#include "rcpputils/get_env.hpp"
#include "rcpputils/env.hpp"

namespace rcpputils
{
Expand All @@ -50,4 +51,15 @@ std::string get_env_var(const char * env_var)
return value ? value : "";
}

bool set_env_var(const char * env_var, const char * env_value)
{
if (!rcutils_set_env(env_var, env_value)) {
std::string err = rcutils_get_error_string().str;
// Resetting the error state since error string has been extracted
rcutils_reset_error();
throw std::runtime_error(err);
}
return true;
}

} // namespace rcpputils
2 changes: 1 addition & 1 deletion src/find_library.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@

#include "rcpputils/filesystem_helper.hpp"
#include "rcpputils/split.hpp"
#include "rcpputils/get_env.hpp"
#include "rcpputils/env.hpp"

namespace rcpputils
{
Expand Down
83 changes: 83 additions & 0 deletions test/test_env.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
// 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 <gtest/gtest.h>

#include <rcpputils/env.hpp>

#include <stdexcept>
#include <string>


/* Tests get_env_var.
*
* Expected environment variables must be set by the calling code:
*
* - EMPTY_TEST=
* - NORMAL_TEST=foo
*
* These are set in the call to `ament_add_gtest()` in the `CMakeLists.txt`.
*/

TEST(TestGetEnv, test_get_env) {
std::string env;
env = rcpputils::get_env_var("NORMAL_TEST");
EXPECT_STREQ("foo", env.c_str());
env = rcpputils::get_env_var("SHOULD_NOT_EXIST_TEST");
EXPECT_STREQ("", env.c_str());
env = rcpputils::get_env_var("EMPTY_TEST");
EXPECT_STREQ("", env.c_str());
}

/* Tests set_env_var. */

TEST(TestSetEnv, test_set_env) {
// Invalid cases: Environment variable name is invalid/NULL.
EXPECT_THROW(
rcpputils::set_env_var(nullptr, nullptr),
std::runtime_error);
EXPECT_THROW(
rcpputils::set_env_var("=INVALID_ENV_VAR=", nullptr),
std::runtime_error);
EXPECT_THROW(
rcpputils::set_env_var("=INVALID_ENV_VAR=", "InvalidEnvValue"),
std::runtime_error);

// Starting empty
EXPECT_STREQ("", rcpputils::get_env_var("NEW_ENV_VAR").c_str());

// Simple set
EXPECT_TRUE(rcpputils::set_env_var("NEW_ENV_VAR", "NewEnvValue"));
EXPECT_STREQ(
"NewEnvValue",
rcpputils::get_env_var("NEW_ENV_VAR").c_str());

// Re-set
EXPECT_TRUE(rcpputils::set_env_var("NEW_ENV_VAR", "DifferentEnvValue"));
EXPECT_STREQ(
"DifferentEnvValue",
rcpputils::get_env_var("NEW_ENV_VAR").c_str());

// Un-set
EXPECT_TRUE(rcpputils::set_env_var("NEW_ENV_VAR", nullptr));
EXPECT_STREQ(
"",
rcpputils::get_env_var("NEW_ENV_VAR").c_str());

// Un-set again
EXPECT_TRUE(rcpputils::set_env_var("NEW_ENV_VAR", nullptr));
EXPECT_STREQ(
"",
rcpputils::get_env_var("NEW_ENV_VAR").c_str());
}
2 changes: 1 addition & 1 deletion test/test_filesystem_helper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <string>

#include "rcpputils/filesystem_helper.hpp"
#include "rcpputils/get_env.hpp"
#include "rcpputils/env.hpp"

#ifdef _WIN32
static constexpr const bool is_win32 = true;
Expand Down
39 changes: 0 additions & 39 deletions test/test_get_env.cpp

This file was deleted.

0 comments on commit cb117a5

Please sign in to comment.