File: env.h

package info (click to toggle)
ros2-rcutils 6.9.4-2
  • links: PTS, VCS
  • area: main
  • in suites: forky, sid
  • size: 1,388 kB
  • sloc: ansic: 7,405; cpp: 7,369; python: 281; xml: 29; makefile: 4
file content (152 lines) | stat: -rw-r--r-- 5,655 bytes parent folder | download | duplicates (2)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
// 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.

/// \file

#ifndef RCUTILS__ENV_H_
#define RCUTILS__ENV_H_

#ifdef __cplusplus
extern "C"
{
#endif

#include <stdbool.h>

#include "rcutils/macros.h"
#include "rcutils/visibility_control.h"

/// Set or un-set a process-scoped environment variable.
/**
 * This function modifies the environment variables for the current process by
 * copying given string values into the process' global environment variable
 * store.
 *
 * \par Thread Safety:
 * This function is not thread-safe. Take care not to modify the environment variables while
 * another thread might be reading or writing environment variables.
 *
 * \par Platform Consistency:
 * The behavior when setting a variable to an empty string (`""`) differs
 * between platforms. On Windows, the variable is un-set (as if \p env_value was
 * `NULL`), while on other platforms the variable is set to an empty string as
 * expected.
 *
 * \param[in] env_name Name of the environment variable to modify.
 * \param[in] env_value Value to set the environment variable to, or `NULL` to
 *   un-set.
 * \return `true` if success, or
 * \return `false` if env_name is invalid or NULL, or
 * \return `false` on failure.
 */
RCUTILS_PUBLIC
RCUTILS_WARN_UNUSED
bool
rcutils_set_env(const char * env_name, const char * env_value);

/// Set or un-set a process-scoped environment variable while specifying overwrite behavior.
/**
 * This function modifies the environment variables for the current process by
 * copying given string values into the process' global environment variable
 * store.
 *
 * \par Thread Safety:
 * This function is not thread-safe. Take care not to modify the environment variables while
 * another thread might be reading or writing environment variables.
 *
 * \par Platform Consistency:
 * The behavior when setting a variable to an empty string (`""`) differs
 * between platforms. On Windows, the variable is un-set (as if \p env_value was
 * `NULL`), while on other platforms the variable is set to an empty string as
 * expected.
 *
 * \param[in] env_name Name of the environment variable to modify.
 * \param[in] env_value Value to set the environment variable to, or `NULL` to
 *   un-set.
 * \param[in] overwrite If true, the environemnt variable value will not be overwritten
 *   if previously set.
 * \return `true` if success, or
 * \return `false` if env_name is invalid or NULL, or
 * \return `false` on failure.
 */
RCUTILS_PUBLIC
RCUTILS_WARN_UNUSED
bool
rcutils_set_env_overwrite(const char * env_name, const char * env_value, bool overwrite);

/// Retrieve the value of the given environment variable if it exists, or "".
/** The c-string which is returned in the env_value output parameter is only
 * valid until the next time this function is called, because it is a direct
 * pointer to the static storage.
 * The variable env_value populated by this function should never have free()
 * called on it.
 * If the environment variable is not set, an empty string will be returned.
 *
 * In both cases, environment variable set or unset, NULL is returned unless
 * an exception has occurred, in which case the error string is returned.
 * For example:
 *
 * ```c
 * #include <stdio.h>
 * #include <rcutils/env.h>
 * const char * env_value;
 * const char * error_str;
 * error_str = rcutils_get_env("SOME_ENV_VAR", &env_value);
 * if (error_str != NULL) {
 *   fprintf(stderr, "Error getting env var: %s\n", error_str);
 * }
 * printf("Valued of 'SOME_ENV_VAR': %s\n", env_value);
 * ```
 *
 * This function cannot be concurrently called together with rcutils_set_env (or any platform specific equivalent)
 * on different threads, but multiple concurrent calls to this function are thread safe.
 *
 * \param[in] env_name the name of the environment variable
 * \param[out] env_value pointer to the value cstring, or "" if unset
 * \return NULL on success (success can be returning an empty string), or
 * \return an error string on failure.
 */
RCUTILS_PUBLIC
RCUTILS_WARN_UNUSED
const char *
rcutils_get_env(const char * env_name, const char ** env_value);

/// Retrieve the full path to the home directory.
/**
 * The c-string which is returned is only valid until the next time this
 * function is called, because it is a direct pointer to the static storage.
 * Also note that the string returned here should *not* be freed.
 *
 * The function first tries to get the HOME environment variable.
 * If that variable exists and is non-empty, that will be returned.
 * Otherwise, on Windows, the function tries to get the USERPROFILE environment variable.
 * If that variable exists and is non-empty, that will be returned.
 * Otherwise, NULL will be returned.
 *
 * This function cannot be thread-safely called together with rcutils_set_env
 * (or any platform specific equivalent), but multiple calls to this function are thread safe.
 *
 * \return The home directory on success, or
 * \return `NULL` on failure.
 */
RCUTILS_PUBLIC
RCUTILS_WARN_UNUSED
const char *
rcutils_get_home_dir(void);

#ifdef __cplusplus
}
#endif

#endif  // RCUTILS__ENV_H_