From 66f0b31164fa7523e7d69d7d9445f621d96a4082 Mon Sep 17 00:00:00 2001 From: Mabel Zhang Date: Tue, 14 Jun 2022 20:56:18 -0400 Subject: [PATCH 1/3] Bash completion for flags (#167) Signed-off-by: Mabel Zhang Signed-off-by: Louise Poubel Co-authored-by: Louise Poubel --- CMakeLists.txt | 4 +++ src/CMakeLists.txt | 28 +++++++++++++++++++ src/ign_TEST.cc | 42 ++++++++++++++++++++++++++--- src/launch.bash_completion.sh | 51 +++++++++++++++++++++++++++++++++++ 4 files changed, 121 insertions(+), 4 deletions(-) create mode 100644 src/launch.bash_completion.sh diff --git a/CMakeLists.txt b/CMakeLists.txt index bdf38ce3..ddaea83d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -46,6 +46,10 @@ set(IGN_PLUGIN_MAJOR_VER ${ignition-plugin1_VERSION_MAJOR}) ign_find_package(ignition-tools REQUIRED PKGCONFIG "ignition-tools") +# Note that CLI files are installed regardless of whether the dependency is +# available during build time +find_program(HAVE_IGN_TOOLS ign) +set(IGN_TOOLS_VER 1) #-------------------------------------- # Find ignition-transport diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index d4fa818e..a168daf5 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -35,6 +35,21 @@ ign_build_tests(TYPE UNIT SOURCES ${gtest_sources} ignition-common${IGN_COMMON_MAJOR_VER}::ignition-common${IGN_COMMON_MAJOR_VER} ) +if(TARGET UNIT_ign_TEST) + # Running `ign launch` on macOS has problems when run with /usr/bin/ruby + # due to System Integrity Protection (SIP). Try to find ruby from + # homebrew as a workaround. + if (APPLE) + find_program(BREW_RUBY ruby HINTS /usr/local/opt/ruby/bin) + endif() + + target_compile_definitions(UNIT_ign_TEST PRIVATE + "BREW_RUBY=\"${BREW_RUBY} \"") + + target_compile_definitions(UNIT_ign_TEST PRIVATE + "IGN_PATH=\"${HAVE_IGN_TOOLS}\"") +endif() + # Generate a the ruby script. # Note that the major version of the library is included in the name. # Ex: cmdlaunch0.rb @@ -94,3 +109,16 @@ set(ign_library_path "${CMAKE_BINARY_DIR}/test/lib/ruby/ignition/cmdlaunch${PROJ configure_file( "launch.yaml.in" "${CMAKE_BINARY_DIR}/test/conf/launch${PROJECT_VERSION_MAJOR}.yaml" @ONLY) + +#=============================================================================== +# Bash completion + +# Tack version onto and install the bash completion script +configure_file( + "launch.bash_completion.sh" + "${CMAKE_CURRENT_BINARY_DIR}/launch${PROJECT_VERSION_MAJOR}.bash_completion.sh" @ONLY) +install( + FILES + ${CMAKE_CURRENT_BINARY_DIR}/launch${PROJECT_VERSION_MAJOR}.bash_completion.sh + DESTINATION + ${CMAKE_INSTALL_PREFIX}/${CMAKE_INSTALL_DATAROOTDIR}/gz/gz${IGN_TOOLS_VER}.completion.d) diff --git a/src/ign_TEST.cc b/src/ign_TEST.cc index e2d13c61..a9af15e9 100644 --- a/src/ign_TEST.cc +++ b/src/ign_TEST.cc @@ -21,8 +21,13 @@ #include +#include #include "ignition/launch/test_config.hh" // NOLINT(build/include) +static const std::string kIgnCommand( + std::string("IGN_CONFIG_PATH=") + IGN_CONFIG_PATH + " " + + std::string(BREW_RUBY) + std::string(IGN_PATH) + " launch "); + ///////////////////////////////////////////////// std::string customExecStr(std::string _cmd) { @@ -48,8 +53,7 @@ std::string customExecStr(std::string _cmd) ///////////////////////////////////////////////// TEST(CmdLine, Ls) { - std::string cmd = std::string("IGN_CONFIG_PATH=") + IGN_CONFIG_PATH + - " ign launch " + + std::string cmd = kIgnCommand + std::string(PROJECT_SOURCE_PATH) + "/test/config/ls.ign"; std::cout << "Running command [" << cmd << "]" << std::endl; @@ -66,9 +70,39 @@ TEST(CmdLine, EchoSelf) std::string filePath = std::string(PROJECT_SOURCE_PATH) + "/test/config/echo.ign"; - std::string cmd = std::string("IGN_CONFIG_PATH=") + IGN_CONFIG_PATH + - " ign launch " + filePath; + std::string cmd = kIgnCommand + filePath; std::string output = customExecStr(cmd); EXPECT_EQ(filePath, output) << output; } + +////////////////////////////////////////////////// +/// \brief Check --help message and bash completion script for consistent flags +TEST(CmdLine, HelpVsCompletionFlags) +{ + // Flags in help message + std::string helpOutput = customExecStr(kIgnCommand + "--help"); + + // Call the output function in the bash completion script + std::string scriptPath = ignition::common::joinPaths( + std::string(PROJECT_SOURCE_PATH), + "src", "launch.bash_completion.sh"); + + // Equivalent to: + // sh -c "bash -c \". /path/to/launch.bash_completion.sh; _gz_launch_flags\"" + std::string cmd = "bash -c \". " + scriptPath + "; _gz_launch_flags\""; + std::string scriptOutput = customExecStr(cmd); + + // Tokenize script output + std::istringstream iss(scriptOutput); + std::vector flags((std::istream_iterator(iss)), + std::istream_iterator()); + + EXPECT_GT(flags.size(), 0u); + + // Match each flag in script output with help message + for (const auto &flag : flags) + { + EXPECT_NE(std::string::npos, helpOutput.find(flag)) << helpOutput; + } +} diff --git a/src/launch.bash_completion.sh b/src/launch.bash_completion.sh new file mode 100644 index 00000000..0a6e4843 --- /dev/null +++ b/src/launch.bash_completion.sh @@ -0,0 +1,51 @@ +#!/usr/bin/env bash +# +# Copyright (C) 2022 Open Source Robotics Foundation +# +# 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. +# + +# bash tab-completion + +# This is a per-library function definition, used in conjunction with the +# top-level entry point in ign-tools. + +GZ_LAUNCH_COMPLETION_LIST=" + -v --verbose + -h --help + --force-version + --versions +" + +function _gz_launch +{ + if [[ ${COMP_WORDS[COMP_CWORD]} == -* ]]; then + # Specify options (-*) word list for this subcommand + COMPREPLY=($(compgen -W "$GZ_LAUNCH_COMPLETION_LIST" \ + -- "${COMP_WORDS[COMP_CWORD]}" )) + return + else + # Just use bash default auto-complete, because we never have two + # subcommands in the same line. If that is ever needed, change here to + # detect subsequent subcommands + COMPREPLY=($(compgen -o default -- "${COMP_WORDS[COMP_CWORD]}")) + return + fi +} + +function _gz_launch_flags +{ + for word in $GZ_LAUNCH_COMPLETION_LIST; do + echo "$word" + done +} From 0f6edef48d681ac4f48e648bdc8136add6cc0e93 Mon Sep 17 00:00:00 2001 From: Jenn Nguyen Date: Fri, 15 Jul 2022 13:19:33 -0700 Subject: [PATCH 2/3] Ignition -> Gazebo (#178) Signed-off-by: Jenn Nguyen --- README.md | 51 +++++++++++++++++++++++++-------------------------- 1 file changed, 25 insertions(+), 26 deletions(-) diff --git a/README.md b/README.md index e29f8ab5..5cb86653 100644 --- a/README.md +++ b/README.md @@ -1,21 +1,20 @@ -# Ignition Launch : Run and manage programs and plugins +# Gazebo Launch : Run and manage programs and plugins **Maintainer:** nate AT openrobotics DOT org -[![GitHub open issues](https://img.shields.io/github/issues-raw/ignitionrobotics/ign-launch.svg)](https://github.com/ignitionrobotics/ign-launch/issues) -[![GitHub open pull requests](https://img.shields.io/github/issues-pr-raw/ignitionrobotics/ign-launch.svg)](https://github.com/ignitionrobotics/ign-launch/pulls) +[![GitHub open issues](https://img.shields.io/github/issues-raw/gazebosim/gz-launch.svg)](https://github.com/gazebosim/gz-launch/issues) +[![GitHub open pull requests](https://img.shields.io/github/issues-pr-raw/gazebosim/gz-launch.svg)](https://github.com/gazebosim/gz-launch/pulls) [![Discourse topics](https://img.shields.io/discourse/https/community.gazebosim.org/topics.svg)](https://community.gazebosim.org) [![Hex.pm](https://img.shields.io/hexpm/l/plug.svg)](https://www.apache.org/licenses/LICENSE-2.0) Build | Status -- | -- -Test coverage | [![codecov](https://codecov.io/gh/ignitionrobotics/ign-launch/branch/ign-launch2/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-launch) -Ubuntu Bionic | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_launch-ci-ign-launch2-bionic-amd64)](https://build.osrfoundation.org/job/ignition_launch-ci-ign-launch2-bionic-amd64) +Test coverage | [![codecov](https://codecov.io/gh/gazebosim/gz-launch/branch/ign-launch2/graph/badge.svg)](https://codecov.io/gh/gazebosim/gz-launch/branch/ign-launch2) +Ubuntu Focal | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_launch-ci-ign-launch2-focal-amd64)](https://build.osrfoundation.org/job/ignition_launch-ci-ign-launch2-focal-amd64) Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_launch-ci-ign-launch2-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_launch-ci-ign-launch2-homebrew-amd64) Windows | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_launch-ci-ign-launch2-windows7-amd64)](https://build.osrfoundation.org/job/ignition_launch-ci-ign-launch2-windows7-amd64) -Ignition Launch, a component of [Ignition -Robotics](https://ignitionrobotics.org), provides a command line interface +Gazebo Launch, a component of [Gazebo](https://gazebosim.org), provides a command line interface to run and manager application and plugins. # Table of Contents @@ -50,7 +49,7 @@ to run and manager application and plugins. # Features -Ignition Launch is used to run and manage plugins and programs. A +Gazebo Launch is used to run and manage plugins and programs. A configuration script can be used to specify which programs and plugins to execute. Alternatively, individual programs and plugins can be run from the command line. Example configuration scripts are located in the `examples` @@ -58,7 +57,7 @@ directory. 1. Automatic ERB parsing of configuration files. 1. Pass arguments to launch files from the command line. -1. Plugins to launch Gazebo, joystick interface, and a websocket server for +1. Plugins to launch Gazebo Sim, joystick interface, and a websocket server for simulation. # Install @@ -93,7 +92,7 @@ necessary prerequisites followed by building from source. sudo apt-get -y install cmake build-essential curl cppcheck g++-8 doxygen ruby-ronn libtinyxml2-dev software-properties-common ``` -1. Install required Ignition libraries +1. Install required Gazebo libraries ``` sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list' @@ -120,16 +119,16 @@ necessary prerequisites followed by building from source. 1. Clone the repository ``` - git clone https://github.com/ignitionrobotics/ign-launch + git clone https://github.com/gazebosim/gz-launch ``` 2. Configure and build ``` - cd ign-launch; mkdir build; cd build; cmake ..; make + cd gz-launch; mkdir build; cd build; cmake ..; make ``` -3. Optionally, install Ignition Launch +3. Optionally, install Gazebo Launch ``` sudo make install @@ -137,11 +136,11 @@ necessary prerequisites followed by building from source. # Usage -Sample launch configuration files are in the [examples directory](https://github.com/ignitionrobotics/ign-launch/blob/ign-launch2/examples/). +Sample launch configuration files are in the [examples directory](https://github.com/gazebosim/gz-launch/blob/ign-launch2/examples/). **Example** -1. Run a configuration that launches [Gazebo](https://ignitionrobotics.org/libs/gazebo). +1. Run a configuration that launches [Gazebo Sim](https://gazebosim.org/libs/gazebo). ``` ign launch gazebo.ign @@ -153,7 +152,7 @@ In the event that the installation is a mix of Debian and from source, command line tools from `ign-tools` may not work correctly. A workaround for a single package is to define the environment variable -`IGN_CONFIG_PATH` to point to the location of the Ignition library installation, +`IGN_CONFIG_PATH` to point to the location of the Gazebo library installation, where the YAML file for the package is found, such as ``` export IGN_CONFIG_PATH=/usr/local/share/ignition @@ -162,7 +161,7 @@ export IGN_CONFIG_PATH=/usr/local/share/ignition However, that environment variable only takes a single path, which means if the installations from source are in different locations, only one can be specified. -Another workaround for working with multiple Ignition libraries on the command +Another workaround for working with multiple Gazebo libraries on the command line is using symbolic links to each library's YAML file. ``` mkdir ~/.ignition/tools/configs -p @@ -174,11 +173,11 @@ ln -s /usr/local/share/ignition/transportlog7.yaml . export IGN_CONFIG_PATH=$HOME/.ignition/tools/configs ``` -This issue is tracked [here](https://github.com/ignitionrobotics/ign-tools/issues/8). +This issue is tracked [here](https://github.com/gazebosim/gz-tools/issues/8). # Documentation -API and tutorials can be found at [https://ignitionrobotics.org/libs/launch](https://ignitionrobotics.org/libs/launch). +API and tutorials can be found at [https://gazebosim.org/libs/launch](https://gazebosim.org/libs/launch). You can also generate the documentation from a clone of this repository by following these steps. @@ -191,13 +190,13 @@ You can also generate the documentation from a clone of this repository by follo 2. Clone the repository ``` - git clone https://github.com/ignitionrobotics/ign-launch + git clone https://github.com/gazebosim/gz-launch ``` 3. Configure and build the documentation. ``` - cd ign-launch; mkdir build; cd build; cmake ../; make doc + cd gz-launch; mkdir build; cd build; cmake ../; make doc ``` 4. View the documentation by running the following command from the build directory. @@ -229,7 +228,7 @@ Follow these steps to run tests and static code analysis in your clone of this r Refer to the following table for information about important directories and files in this repository. ``` -ign-launch +gz-launch ├── examples Example launch configurations. ├── include/ignition/launch Header files. ├── src Source files and unit tests. @@ -244,17 +243,17 @@ ign-launch # Contributing -Please see the [contribution guide](https://ignitionrobotics.org/docs/all/contributing). +Please see the [contribution guide](https://gazebosim.org/docs/all/contributing). # Code of Conduct Please see -[CODE_OF_CONDUCT.md](https://github.com/ignitionrobotics/ign-gazebo/blob/main/CODE_OF_CONDUCT.md). +[CODE_OF_CONDUCT.md](https://github.com/gazebosim/gz-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. +This library uses [Semantic Versioning](https://semver.org/). Additionally, this library is part of the [Gazebo project](https://gazebosim.org) which periodically releases a versioned set of compatible and complimentary libraries. See the [Gazebo website](https://gazebosim.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/main/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/gazebosim/gz-launch/blob/main/LICENSE) file. From 6ca4edb88eea1ff0a9dc9a517fb571063b563fcf Mon Sep 17 00:00:00 2001 From: Mabel Zhang Date: Tue, 19 Jul 2022 17:14:16 -0400 Subject: [PATCH 3/3] fix ign_TEST for Fortress (#180) Signed-off-by: Mabel Zhang --- src/cmd/ign_TEST.cc | 5 ++--- src/cmd/launch.bash_completion.sh | 6 +++--- 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/src/cmd/ign_TEST.cc b/src/cmd/ign_TEST.cc index a8d89046..80819eb8 100644 --- a/src/cmd/ign_TEST.cc +++ b/src/cmd/ign_TEST.cc @@ -31,7 +31,6 @@ #endif static const std::string kIgnCommand( - std::string("IGN_CONFIG_PATH=") + IGN_CONFIG_PATH + " " + std::string(BREW_RUBY) + std::string(IGN_PATH) + " launch "); ///////////////////////////////////////////////// @@ -66,7 +65,7 @@ std::string get_config_path(const std::string filename) ///////////////////////////////////////////////// TEST(CmdLine, Ls) { - std::string cmd = kIgnCommand + get_config_path("ls.ign"); + std::string cmd = "ign launch " + get_config_path("ls.ign"); std::string output = customExecStr(cmd); EXPECT_TRUE(output.find("CMakeFiles") != std::string::npos) << output; EXPECT_TRUE(output.find("Makefile") != std::string::npos) << output; @@ -117,7 +116,7 @@ TEST(CmdLine, HelpVsCompletionFlags) // Call the output function in the bash completion script std::string scriptPath = ignition::common::joinPaths( std::string(PROJECT_SOURCE_PATH), - "src", "launch.bash_completion.sh"); + "src", "cmd", "launch.bash_completion.sh"); // Equivalent to: // sh -c "bash -c \". /path/to/launch.bash_completion.sh; _gz_launch_flags\"" diff --git a/src/cmd/launch.bash_completion.sh b/src/cmd/launch.bash_completion.sh index 0a6e4843..90076334 100644 --- a/src/cmd/launch.bash_completion.sh +++ b/src/cmd/launch.bash_completion.sh @@ -21,10 +21,10 @@ # top-level entry point in ign-tools. GZ_LAUNCH_COMPLETION_LIST=" - -v --verbose -h --help - --force-version - --versions + --help-all + --version + -v --verbose " function _gz_launch