Skip to content

Commit

Permalink
Backport #561: Use common::setenv
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
j-rivero authored and chapulina committed Mar 3, 2021
1 parent e592cae commit d3758c2
Show file tree
Hide file tree
Showing 54 changed files with 198 additions and 156 deletions.
24 changes: 12 additions & 12 deletions src/Server_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,8 @@ class ServerFixture : public ::testing::TestWithParam<int>
protected: void SetUp() override
{
// Augment the system plugin path. In SetUp to avoid test order issues.
setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1);
ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str());

ignition::common::Console::SetVerbosity(4);
}
Expand Down Expand Up @@ -788,9 +788,9 @@ TEST_P(ServerFixture, Seed)
/////////////////////////////////////////////////
TEST_P(ServerFixture, ResourcePath)
{
setenv("IGN_GAZEBO_RESOURCE_PATH",
ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH",
(std::string(PROJECT_SOURCE_PATH) + "/test/worlds:" +
std::string(PROJECT_SOURCE_PATH) + "/test/worlds/models").c_str(), 1);
std::string(PROJECT_SOURCE_PATH) + "/test/worlds/models").c_str());

ServerConfig serverConfig;
serverConfig.SetSdfFile("resource_paths.sdf");
Expand Down Expand Up @@ -876,8 +876,8 @@ TEST_P(ServerFixture, ResourcePath)
/////////////////////////////////////////////////
TEST_P(ServerFixture, GetResourcePaths)
{
setenv("IGN_GAZEBO_RESOURCE_PATH",
"/tmp/some/path:/home/user/another_path", 1);
ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH",
"/tmp/some/path:/home/user/another_path");

ServerConfig serverConfig;
gazebo::Server server(serverConfig);
Expand Down Expand Up @@ -908,7 +908,7 @@ TEST_P(ServerFixture, CachedFuelWorld)
{
auto cachedWorldPath =
common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds");
setenv("IGN_FUEL_CACHE_PATH", cachedWorldPath.c_str(), 1);
ignition::common::setenv("IGN_FUEL_CACHE_PATH", cachedWorldPath.c_str());

ServerConfig serverConfig;
auto fuelWorldURL =
Expand All @@ -932,10 +932,10 @@ TEST_P(ServerFixture, CachedFuelWorld)
/////////////////////////////////////////////////
TEST_P(ServerFixture, AddResourcePaths)
{
setenv("IGN_GAZEBO_RESOURCE_PATH",
"/tmp/some/path:/home/user/another_path", 1);
setenv("SDF_PATH", "", 1);
setenv("IGN_FILE_PATH", "", 1);
ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH",
"/tmp/some/path:/home/user/another_path");
ignition::common::setenv("SDF_PATH", "");
ignition::common::setenv("IGN_FILE_PATH", "");

ServerConfig serverConfig;
gazebo::Server server(serverConfig);
Expand Down Expand Up @@ -979,7 +979,7 @@ TEST_P(ServerFixture, AddResourcePaths)
// Check environment variables
for (auto env : {"IGN_GAZEBO_RESOURCE_PATH", "SDF_PATH", "IGN_FILE_PATH"})
{
char *pathCStr = getenv(env);
char *pathCStr = std::getenv(env);

auto paths = common::Split(pathCStr, ':');
paths.erase(std::remove_if(paths.begin(), paths.end(),
Expand Down
1 change: 1 addition & 0 deletions src/SimulationRunner_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <tinyxml2.h>

#include <ignition/common/Console.hh>
#include <ignition/common/Util.hh>
#include <ignition/transport/Node.hh>
#include <sdf/Box.hh>
#include <sdf/Cylinder.hh>
Expand Down
34 changes: 25 additions & 9 deletions src/Util.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,14 +16,23 @@
*/

#ifndef __APPLE__
#if __GNUC__ < 8
#if (defined(_MSVC_LANG))
#if (_MSVC_LANG >= 201703L || __cplusplus >= 201703L)
#include <filesystem> // c++17
#else
#define _SILENCE_EXPERIMENTAL_FILESYSTEM_DEPRECATION_WARNING
#include <experimental/filesystem>
#endif
#elif __GNUC__ < 8
#include <experimental/filesystem>
#else
#include <filesystem>
#endif
#endif

#include <ignition/common/Filesystem.hh>
#include <ignition/common/StringUtils.hh>
#include <ignition/common/Util.hh>

#include "ignition/gazebo/components/Actor.hh"
#include "ignition/gazebo/components/Collision.hh"
Expand Down Expand Up @@ -257,7 +266,13 @@ std::string asFullPath(const std::string &_uri, const std::string &_filePath)
}
#else
// Not a relative path, return unmodified
#if __GNUC__ < 8
#if (defined(_MSVC_LANG))
#if (_MSVC_LANG >= 201703L || __cplusplus >= 201703L)
using namespace std::filesystem;
#else
using namespace std::experimental::filesystem;
#endif
#elif __GNUC__ < 8
using namespace std::experimental::filesystem;
#else
using namespace std::filesystem;
Expand Down Expand Up @@ -303,7 +318,7 @@ std::string asFullPath(const std::string &_uri, const std::string &_filePath)
std::vector<std::string> resourcePaths()
{
std::vector<std::string> gzPaths;
char *gzPathCStr = getenv(kResourcePathEnv.c_str());
char *gzPathCStr = std::getenv(kResourcePathEnv.c_str());
if (gzPathCStr && *gzPathCStr != '\0')
{
gzPaths = common::Split(gzPathCStr, ':');
Expand All @@ -323,7 +338,7 @@ void addResourcePaths(const std::vector<std::string> &_paths)
{
// SDF paths (for <include>s)
std::vector<std::string> sdfPaths;
char *sdfPathCStr = getenv(kSdfPathEnv.c_str());
char *sdfPathCStr = std::getenv(kSdfPathEnv.c_str());
if (sdfPathCStr && *sdfPathCStr != '\0')
{
sdfPaths = common::Split(sdfPathCStr, ':');
Expand All @@ -332,15 +347,15 @@ void addResourcePaths(const std::vector<std::string> &_paths)
// Ignition file paths (for <uri>s)
auto systemPaths = common::systemPaths();
std::vector<std::string> ignPaths;
char *ignPathCStr = getenv(systemPaths->FilePathEnv().c_str());
char *ignPathCStr = std::getenv(systemPaths->FilePathEnv().c_str());
if (ignPathCStr && *ignPathCStr != '\0')
{
ignPaths = common::Split(ignPathCStr, ':');
}

// Gazebo resource paths
std::vector<std::string> gzPaths;
char *gzPathCStr = getenv(kResourcePathEnv.c_str());
char *gzPathCStr = std::getenv(kResourcePathEnv.c_str());
if (gzPathCStr && *gzPathCStr != '\0')
{
gzPaths = common::Split(gzPathCStr, ':');
Expand Down Expand Up @@ -374,19 +389,20 @@ void addResourcePaths(const std::vector<std::string> &_paths)
for (const auto &path : sdfPaths)
sdfPathsStr += ':' + path;

setenv(kSdfPathEnv.c_str(), sdfPathsStr.c_str(), 1);
ignition::common::setenv(kSdfPathEnv.c_str(), sdfPathsStr.c_str());

std::string ignPathsStr;
for (const auto &path : ignPaths)
ignPathsStr += ':' + path;

setenv(systemPaths->FilePathEnv().c_str(), ignPathsStr.c_str(), 1);
ignition::common::setenv(
systemPaths->FilePathEnv().c_str(), ignPathsStr.c_str());

std::string gzPathsStr;
for (const auto &path : gzPaths)
gzPathsStr += ':' + path;

setenv(kResourcePathEnv.c_str(), gzPathsStr.c_str(), 1);
ignition::common::setenv(kResourcePathEnv.c_str(), gzPathsStr.c_str());

// Force re-evaluation
// SDF is evaluated at find call
Expand Down
13 changes: 7 additions & 6 deletions src/gui/Gui_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@

#include <ignition/common/Console.hh>
#include <ignition/common/StringUtils.hh>
#include <ignition/common/Util.hh>
#include <ignition/transport/Node.hh>
#include <ignition/utilities/ExtraTestMacros.hh>

Expand All @@ -40,10 +41,10 @@ TEST(GuiTest, IGN_UTILS_TEST_DISABLED_ON_MAC(PathManager))
common::Console::SetVerbosity(4);
igndbg << "Start test" << std::endl;

setenv("IGN_GAZEBO_RESOURCE_PATH",
"/from_env:/tmp/more_env", 1);
setenv("SDF_PATH", "", 1);
setenv("IGN_FILE_PATH", "", 1);
ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH",
"/from_env:/tmp/more_env");
ignition::common::setenv("SDF_PATH", "");
ignition::common::setenv("IGN_FILE_PATH", "");
igndbg << "Environment set" << std::endl;

transport::Node node;
Expand Down Expand Up @@ -95,7 +96,7 @@ TEST(GuiTest, IGN_UTILS_TEST_DISABLED_ON_MAC(PathManager))
for (auto env : {"IGN_GAZEBO_RESOURCE_PATH", "SDF_PATH", "IGN_FILE_PATH"})
{
igndbg << "Checking variable [" << env << "]" << std::endl;
char *pathCStr = getenv(env);
char *pathCStr = std::getenv(env);

auto paths = common::Split(pathCStr, ':');
paths.erase(std::remove_if(paths.begin(), paths.end(),
Expand Down Expand Up @@ -141,7 +142,7 @@ TEST(GuiTest, IGN_UTILS_TEST_DISABLED_ON_MAC(PathManager))
for (auto env : {"IGN_GAZEBO_RESOURCE_PATH", "SDF_PATH", "IGN_FILE_PATH"})
{
igndbg << "Checking variable [" << env << "]" << std::endl;
char *pathCStr = getenv(env);
char *pathCStr = std::getenv(env);

auto paths = common::Split(pathCStr, ':');
paths.erase(std::remove_if(paths.begin(), paths.end(),
Expand Down
5 changes: 3 additions & 2 deletions src/ign_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <cstdlib>

#include <string>
#include <ignition/common/Util.hh>
#include <ignition/utilities/ExtraTestMacros.hh>

#include "ignition/gazebo/test_config.hh" // NOLINT(build/include)
Expand Down Expand Up @@ -94,7 +95,7 @@ TEST(CmdLine, Server)
TEST(CmdLine, IGN_UTILS_TEST_DISABLED_ON_MAC(CachedFuelWorld))
{
std::string projectPath = std::string(PROJECT_SOURCE_PATH) + "/test/worlds";
setenv("IGN_FUEL_CACHE_PATH", projectPath.c_str(), true);
ignition::common::setenv("IGN_FUEL_CACHE_PATH", projectPath.c_str());
std::string cmd = kIgnCommand + " -r -v 4 --iterations 5" +
" https://fuel.ignitionrobotics.org/1.0/OpenRobotics/worlds/Test%20world";
std::cout << "Running command [" << cmd << "]" << std::endl;
Expand Down Expand Up @@ -172,7 +173,7 @@ int main(int _argc, char **_argv)
{
// Set IGN_CONFIG_PATH to the directory where the .yaml configuration files
// is located.
setenv("IGN_CONFIG_PATH", IGN_CONFIG_PATH, 1);
ignition::common::setenv("IGN_CONFIG_PATH", IGN_CONFIG_PATH);

::testing::InitGoogleTest(&_argc, _argv);
return RUN_ALL_TESTS();
Expand Down
11 changes: 6 additions & 5 deletions src/network/PeerTracker_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

#include <cstdlib>
#include <ignition/common/Console.hh>
#include <ignition/common/Util.hh>

#include "PeerTracker.hh"
#include "ignition/gazebo/EventManager.hh"
Expand Down Expand Up @@ -281,11 +282,11 @@ TEST(PeerTracker, PartitionedEnv)
ignition::common::Console::SetVerbosity(4);
EventManager eventMgr;

setenv("IGN_PARTITION", "p1", 1);
ignition::common::setenv("IGN_PARTITION", "p1");
auto tracker1 = PeerTracker(
PeerInfo(NetworkRole::SimulationPrimary), &eventMgr);

setenv("IGN_PARTITION", "p2", 1);
ignition::common::setenv("IGN_PARTITION", "p2");
auto tracker2 = PeerTracker(
PeerInfo(NetworkRole::SimulationPrimary), &eventMgr);

Expand All @@ -296,11 +297,11 @@ TEST(PeerTracker, PartitionedEnv)
EXPECT_EQ(0u, tracker1.NumPeers());
EXPECT_EQ(0u, tracker2.NumPeers());

setenv("IGN_PARTITION", "p1", 1);
ignition::common::setenv("IGN_PARTITION", "p1");
auto tracker3 = PeerTracker(
PeerInfo(NetworkRole::SimulationSecondary), &eventMgr);

setenv("IGN_PARTITION", "p2", 1);
ignition::common::setenv("IGN_PARTITION", "p2");
auto tracker4 = PeerTracker(
PeerInfo(NetworkRole::SimulationSecondary), &eventMgr);

Expand All @@ -314,6 +315,6 @@ TEST(PeerTracker, PartitionedEnv)
EXPECT_EQ(1u, tracker3.NumPeers());
EXPECT_EQ(1u, tracker4.NumPeers());

unsetenv("IGN_PARTITION");
ignition::common::unsetenv("IGN_PARTITION");
}
#endif
5 changes: 3 additions & 2 deletions test/integration/air_pressure_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <ignition/msgs/fluid_pressure.pb.h>

#include <ignition/common/Console.hh>
#include <ignition/common/Util.hh>
#include <ignition/transport/Node.hh>

#include "ignition/gazebo/components/AirPressureSensor.hh"
Expand All @@ -40,8 +41,8 @@ class AirPressureTest : public ::testing::Test
protected: void SetUp() override
{
ignition::common::Console::SetVerbosity(4);
setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1);
ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str());
}
};

Expand Down
5 changes: 3 additions & 2 deletions test/integration/altimeter_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <mutex>

#include <ignition/common/Console.hh>
#include <ignition/common/Util.hh>
#include <ignition/math/Pose3.hh>
#include <ignition/transport/Node.hh>

Expand All @@ -46,8 +47,8 @@ class AltimeterTest : public ::testing::Test
protected: void SetUp() override
{
ignition::common::Console::SetVerbosity(4);
setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1);
ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str());
}
};

Expand Down
5 changes: 3 additions & 2 deletions test/integration/apply_joint_force_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <ignition/msgs/double.pb.h>

#include <ignition/common/Console.hh>
#include <ignition/common/Util.hh>
#include <ignition/transport/Node.hh>

#include "ignition/gazebo/components/Joint.hh"
Expand All @@ -44,8 +45,8 @@ class ApplyJointForceTestFixture : public ::testing::Test
protected: void SetUp() override
{
ignition::common::Console::SetVerbosity(4);
setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1);
ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str());
}
};

Expand Down
5 changes: 3 additions & 2 deletions test/integration/battery_plugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@

#include <ignition/common/Battery.hh>
#include <ignition/common/Console.hh>
#include <ignition/common/Util.hh>
#include <ignition/common/Filesystem.hh>

#include <sdf/Root.hh>
Expand Down Expand Up @@ -48,8 +49,8 @@ class BatteryPluginTest : public ::testing::Test
protected: void SetUp() override
{
common::Console::SetVerbosity(4);
setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1);
ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str());

auto plugin = sm.LoadPlugin("libMockSystem.so",
"ignition::gazebo::MockSystem",
Expand Down
6 changes: 4 additions & 2 deletions test/integration/breadcrumbs.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,14 @@
#include <ignition/msgs/empty.pb.h>
#include <ignition/msgs/twist.pb.h>

#include <optional>
#include <regex>

#include <sdf/Root.hh>
#include <sdf/World.hh>

#include <ignition/common/Console.hh>
#include <ignition/common/Util.hh>
#include <ignition/transport/Node.hh>

#include "ignition/gazebo/Entity.hh"
Expand All @@ -48,8 +50,8 @@ class BreadcrumbsTest : public ::testing::Test
protected: void SetUp() override
{
ignition::common::Console::SetVerbosity(4);
setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1);
ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str());
}
public: void LoadWorld(const std::string &_path, bool _useLevels = false)
{
Expand Down
Loading

0 comments on commit d3758c2

Please sign in to comment.