Skip to content

Commit

Permalink
3 ➡️ 4 (#101)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
chapulina authored Mar 19, 2021
2 parents 1b49c1d + a551438 commit 8bdf0f6
Show file tree
Hide file tree
Showing 11 changed files with 189 additions and 39 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ jobs:
uses: actions/checkout@v2
- name: Compile and test
id: ci
uses: ignition-tooling/action-ignition-ci@master
uses: ignition-tooling/action-ignition-ci@bionic
with:
codecov-token: ${{ secrets.CODECOV_TOKEN }}
focal-ci:
Expand Down
21 changes: 18 additions & 3 deletions Changelog.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,12 @@
## Ignition Launch 3.x

### Ignition Launch 3.X.X (20XX-XX-XX)
### Ignition Launch 3.1.1 (2021-01-08)

1. All changes up to and including those in version 2.2.1.

### Ignition Launch 3.1.0 (2020-12-10)

1. All changes up to and including those in version 2.2.0.

### Ignition Launch 3.0.0 (2020-09-30)

Expand All @@ -20,11 +26,17 @@

## Ignition Launch 2.x

### Ignition Launch 2.2.1 (2021-01-08)

1. Fix env parsing by placing it before executable parsing.
* [Pull request 81](https://github.com/ignitionrobotics/ign-launch/pull/81)
* [Pull request 82](https://github.com/ignitionrobotics/ign-launch/pull/82)

### Ignition Launch 2.2.0 (2020-10-14)

* All changes up to and including those in version 1.10.0
1. All changes up to and including those in version 1.10.0

* Added a tutorial.
1. Added a tutorial.
* [Pull request 48](https://github.com/ignitionrobotics/ign-launch/pull/48)

### Ignition Launch 2.1.0 (2020-05-21)
Expand Down Expand Up @@ -66,6 +78,9 @@
1. Add support for specifying topics to record
* [Pull Request 54](https://github.com/ignitionrobotics/ign-launch/pull/54)

1. Fix race condition in websocket server.
* [Pull Request 68](https://github.com/ignitionrobotics/ign-launch/pull/68)

### Ignition Launch 1.9.0 (2020-08-13)

1. Added HTTP handling support to websocket server and a metrics HTTP endpoint
Expand Down
7 changes: 7 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,4 +5,11 @@ Deprecated code produces compile-time warnings. These warning serve as
notification to users that their code should be upgraded. The next major
release will remove the deprecated code.

## Ignition Launch 2.2.2

- Environment variable `IGN_LAUNCH_CONFIG_PATH` started to be treated as a path
list (colon-separated on Linux, semicolon-separated on Windows). Before, only
a single path could be set here, and setting a path list would break the whole
launch file lookup functionality.

## Ignition Launch 0.X to N.M
17 changes: 8 additions & 9 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,10 +9,10 @@

Build | Status
-- | --
Test coverage | [![codecov](https://codecov.io/gh/ignitionrobotics/ign-launch/branch/master/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-launch)
Ubuntu Bionic | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_launch-ci-master-bionic-amd64)](https://build.osrfoundation.org/job/ignition_launch-ci-master-bionic-amd64)
Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_launch-ci-master-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_launch-ci-master-homebrew-amd64)
Windows | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_launch-ci-master-windows7-amd64)](https://build.osrfoundation.org/job/ignition_launch-ci-master-windows7-amd64)
Test coverage | [![codecov](https://codecov.io/gh/ignitionrobotics/ign-launch/branch/main/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-launch)
Ubuntu Bionic | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_launch-ci-main-bionic-amd64)](https://build.osrfoundation.org/job/ignition_launch-ci-main-bionic-amd64)
Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_launch-ci-main-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_launch-ci-main-homebrew-amd64)
Windows | [![Build Status](https://build.osrfoundation.org/job/ign_launch-ci-win/badge/icon)](https://build.osrfoundation.org/job/ign_launch-ci-win/)

Ignition Launch, a component of [Ignition
Robotics](https://ignitionrobotics.org), provides a command line interface
Expand Down Expand Up @@ -137,7 +137,7 @@ necessary prerequisites followed by building from source.
# Usage
Sample launch configuration files are in the [examples directory](https://github.com/ignitionrobotics/ign-launch/blob/master/examples/).
Sample launch configuration files are in the [examples directory](https://github.com/ignitionrobotics/ign-launch/blob/main/examples/).
**Example**
Expand Down Expand Up @@ -244,18 +244,17 @@ ign-launch
# Contributing
Please see
[CONTRIBUTING.md](https://github.com/ignitionrobotics/ign-gazebo/blob/master/CONTRIBUTING.md).
Please see the [contribution guide](https://ignitionrobotics.org/docs/all/contributing).
# Code of Conduct
Please see
[CODE_OF_CONDUCT.md](https://github.com/ignitionrobotics/ign-gazebo/blob/master/CODE_OF_CONDUCT.md).
[CODE_OF_CONDUCT.md](https://github.com/ignitionrobotics/ign-gazebo/blob/main/CODE_OF_CONDUCT.md).
# Versioning
This library uses [Semantic Versioning](https://semver.org/). Additionally, this library is part of the [Ignition Robotics project](https://ignitionrobotics.org) which periodically releases a versioned set of compatible and complimentary libraries. See the [Ignition Robotics website](https://ignitionrobotics.org) for version and release information.
# License
This library is licensed under [Apache 2.0](https://www.apache.org/licenses/LICENSE-2.0). See also the [LICENSE](https://github.com/ignitionrobotics/ign-launch/blob/master/LICENSE) file.
This library is licensed under [Apache 2.0](https://www.apache.org/licenses/LICENSE-2.0). See also the [LICENSE](https://github.com/ignitionrobotics/ign-launch/blob/main/LICENSE) file.
16 changes: 8 additions & 8 deletions bitbucket-pipelines.yml
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ pipelines:
# # Ignition msgs (uncomment if a specific branch is needed)
# - apt install -y
# libprotobuf-dev protobuf-compiler libprotoc-dev
# - git clone http://github.com/ignitionrobotics/ign-msgs -b master
# - git clone http://github.com/ignitionrobotics/ign-msgs
# - cd ign-msgs
# - mkdir build
# - cd build
Expand All @@ -54,7 +54,7 @@ pipelines:
# # Ignition transport (uncomment if a specific branch is needed)
# - apt install -y
# libzmq3-dev uuid-dev libsqlite3-dev
# - git clone http://github.com/ignitionrobotics/ign-transport -b master
# - git clone http://github.com/ignitionrobotics/ign-transport
# - cd ign-transport
# - mkdir build
# - cd build
Expand All @@ -65,7 +65,7 @@ pipelines:
# - apt install -y
# libxml2-utils
# libtinyxml-dev
# - git clone http://github.com/osrf/sdformat -b master
# - git clone http://github.com/osrf/sdformat
# - cd sdformat
# - mkdir build
# - cd build
Expand All @@ -75,7 +75,7 @@ pipelines:
# Ignition Rendering from source
- apt install -y
libogre-1.9-dev libogre-2.1-dev libglew-dev libfreeimage-dev freeglut3-dev libxmu-dev libxi-dev uuid-dev xvfb
- git clone https://github.com/ignitionrobotics/ign-rendering -b master
- git clone https://github.com/ignitionrobotics/ign-rendering
- cd ign-rendering
- mkdir build
- cd build
Expand All @@ -97,7 +97,7 @@ pipelines:
qml-module-qt-labs-folderlistmodel
qml-module-qt-labs-settings
qml-module-qtgraphicaleffects
- git clone https://github.com/ignitionrobotics/ign-gui -b master
- git clone https://github.com/ignitionrobotics/ign-gui
- cd ign-gui
- mkdir build
- cd build
Expand All @@ -111,23 +111,23 @@ pipelines:
# libdart6-dev
# libdart6-utils-urdf-dev
# libbenchmark-dev
# - git clone https://github.com/ignitionrobotics/ign-physics -b master
# - git clone https://github.com/ignitionrobotics/ign-physics
# - cd ign-physics
# - mkdir build
# - cd build
# - cmake .. -DBUILD_TESTING=false
# - make install
# - cd ../..
# Ignition Sensors from source
- git clone https://github.com/ignitionrobotics/ign-sensors -b master
- git clone https://github.com/ignitionrobotics/ign-sensors
- cd ign-sensors
- mkdir build
- cd build
- cmake .. -DBUILD_TESTING=false
- make install
- cd ../..
# Ignition Gazebo from source
- git clone https://github.com/ignitionrobotics/ign-gazebo -b master
- git clone https://github.com/ignitionrobotics/ign-gazebo
- cd ign-gazebo
- mkdir build
- cd build
Expand Down
2 changes: 1 addition & 1 deletion plugins/websocket_server/WebsocketServer.hh
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ namespace ignition
///
/// `ign launch -v 4 websocket.ign`
///
/// 3. Open the [index.html](https://github.com/ignitionrobotics/ign-launch/blob/master/plugins/websocket_server/index.html) webpage.
/// 3. Open the [index.html](https://github.com/ignitionrobotics/ign-launch/blob/main/plugins/websocket_server/index.html) webpage.
///
class WebsocketServer : public ignition::launch::Plugin
{
Expand Down
7 changes: 3 additions & 4 deletions src/Manager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -521,6 +521,9 @@ bool ManagerPrivate::ParseConfig(const std::string &_config)
ignerr << "Invalid config file,m issing <ignition> element\n";
return false;
}
// Keep the environment variables in memory. See manpage for putenv.
this->envs = this->ParseEnvs(root);
this->SetEnvs(this->envs);

// Parse and create all the <executable> elements.
this->ParseExecutables(root);
Expand All @@ -529,10 +532,6 @@ bool ManagerPrivate::ParseConfig(const std::string &_config)
if (this->master)
this->ParseExecutableWrappers(root);

// Keep the environment variables in memory. See manpage for putenv.
this->envs = this->ParseEnvs(root);
this->SetEnvs(this->envs);

// Parse and create all the <plugin> elements.
if (this->master)
{
Expand Down
105 changes: 105 additions & 0 deletions src/Manager_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,46 @@

#include <gtest/gtest.h>
#include <ignition/common/Console.hh>
#include <ignition/common/Filesystem.hh>

#include <ignition/utilities/ExtraTestMacros.hh>

#include <sys/stat.h>

#include "Manager.hh"

static constexpr char kTestScriptPath[] = "/tmp/ign-launch.sh";

/////////////////////////////////////////////////
bool RemoveTestScript()
{
// Remove the file if it already exists
if (ignition::common::isFile(kTestScriptPath))
{
if (!ignition::common::removeFile(kTestScriptPath))
{
return false;
}
}
return true;
}

/////////////////////////////////////////////////
bool WriteTestScript()
{
if (!RemoveTestScript())
return false;

// Write a simple script and mark it executable
std::ofstream ofs(kTestScriptPath);
ofs << R"(#!/usr/bin/env bash
echo $TEST_VAR
touch $TEST_VAR
)";
chmod(kTestScriptPath, S_IRWXU);
return true;
}

/////////////////////////////////////////////////
TEST(Ignition_TEST, RunEmptyConfig)
{
Expand Down Expand Up @@ -81,6 +119,73 @@ TEST(Ignition_TEST, RunLs)
EXPECT_TRUE(mgr.RunConfig(config));
}


/////////////////////////////////////////////////
TEST(Ignition_TEST, IGN_UTILS_TEST_DISABLED_ON_WIN32(RunEnvPre))
{
// Test that environment is applied regardless of order
std::string testPath = "/tmp/ign-launch-env-test-pre";

if (ignition::common::isFile(testPath))
{
ASSERT_TRUE(ignition::common::removeFile(testPath));
}

ASSERT_TRUE(WriteTestScript());

std::string config = R"(
<ignition version='1.0'>
<env>
<name>TEST_VAR</name>
<value>)" + testPath + R"(</value>
</env>
<executable name='touch'>
<command>/tmp/ign-launch.sh</command>
</executable>
</ignition>
)";

ignition::launch::Manager mgr;

EXPECT_TRUE(mgr.RunConfig(config));
EXPECT_TRUE(ignition::common::isFile(testPath));
EXPECT_TRUE(ignition::common::removeFile(testPath));
EXPECT_TRUE(RemoveTestScript());
}

/////////////////////////////////////////////////
TEST(Ignition_TEST, IGN_UTILS_TEST_DISABLED_ON_WIN32(RunEnvPost))
{
// Test that environment is applied regardless of order
std::string testPath = "/tmp/ign-launch-env-test-post";

if (ignition::common::isFile(testPath))
{
ASSERT_TRUE(ignition::common::removeFile(testPath));
}

ASSERT_TRUE(WriteTestScript());

std::string config = R"(
<ignition version='1.0'>
<executable name='touch'>
<command>/tmp/ign-launch.sh</command>
</executable>
<env>
<name>TEST_VAR</name>
<value>)" + testPath + R"(</value>
</env>
</ignition>
)";

ignition::launch::Manager mgr;

EXPECT_TRUE(mgr.RunConfig(config));
EXPECT_TRUE(ignition::common::isFile(testPath));
EXPECT_TRUE(ignition::common::removeFile(testPath));
EXPECT_TRUE(RemoveTestScript());
}

/////////////////////////////////////////////////
int main(int argc, char **argv)
{
Expand Down
33 changes: 21 additions & 12 deletions src/cmdlaunch.rb.in
Original file line number Diff line number Diff line change
Expand Up @@ -159,26 +159,35 @@ class Cmd
end

if options.key?('file')
# Check if the passed in file exists.
# Check if the passed in file exists.
path = ''
if File.exists?(options['file'])
path = options['file']
end
# If not, then first check the IGN_LAUNCH_CONFIG_PATH environment
# variable, then the configuration path from the launch library.
else
if path.empty?
configPathEnv = ENV['IGN_LAUNCH_CONFIG_PATH']
if !configPathEnv.nil? &&
File.exists?(File.join(configPathEnv, options['file']))
path = File.join(configPathEnv, options['file'])
# get the configuration path from the launch library.
else
Importer.extern 'char *configPath()'
path = File.join(Importer.configPath().to_s, options['file'])
if !File.exists?(path)
puts "Unable to find file " + options['file']
exit(-1)
if !configPathEnv.nil?
configPaths = configPathEnv.split(File::PATH_SEPARATOR)
for configPath in configPaths
filePath = File.join(configPath, options['file'])
if File.exists?(filePath)
path = filePath
break
end
end
end
end
# get the configuration path from the launch library.
if path.empty?
Importer.extern 'char *configPath()'
path = File.join(Importer.configPath().to_s, options['file'])
end
if path.empty? or !File.exists?(path)
puts "Unable to find file " + options['file']
exit(-1)
end

# ERB parse the file with the variable bindings
begin
Expand Down
2 changes: 2 additions & 0 deletions tutorials.md.in
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@ Ignition @IGN_DESIGNATION_CAP@ library and how to use the library effectively.

**Tutorials**

1. \subpage basics "Ignition launch tutorial"

## License

The code associated with this documentation is licensed under an [Apache 2.0 License](https://www.apache.org/licenses/LICENSE-2.0).
Expand Down
Loading

0 comments on commit 8bdf0f6

Please sign in to comment.