Skip to content

Commit 3be919f

Browse files
committed
use rcutils_get_env instead of getenv() in node_options.cpp
Signed-off-by: Suyash458 <[email protected]>
1 parent 7c1721a commit 3be919f

File tree

1 file changed

+3
-2
lines changed

1 file changed

+3
-2
lines changed

rclcpp/src/rclcpp/node_options.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
#include "rclcpp/logging.hpp"
2626
#include "rclcpp/publisher_options.hpp"
2727
#include "rclcpp/qos.hpp"
28+
#include "rcutils/get_env.h"
2829

2930
using rclcpp::exceptions::throw_from_rcl_error;
3031

@@ -315,10 +316,10 @@ NodeOptions::get_domain_id_from_env() const
315316
{
316317
// Determine the domain id based on the options and the ROS_DOMAIN_ID env variable.
317318
size_t domain_id = std::numeric_limits<size_t>::max();
318-
char * ros_domain_id = nullptr;
319+
const char * ros_domain_id = nullptr;
319320
const char * env_var = "ROS_DOMAIN_ID";
320321
#ifndef _WIN32
321-
ros_domain_id = getenv(env_var);
322+
rcutils_get_env(env_var, &ros_domain_id);
322323
#else
323324
size_t ros_domain_id_size;
324325
_dupenv_s(&ros_domain_id, &ros_domain_id_size, env_var);

0 commit comments

Comments
 (0)