Skip to content

Commit

Permalink
ign -> gz: namespaces, env var (#163)
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon authored May 29, 2022
1 parent 08b72e8 commit 8a74fac
Show file tree
Hide file tree
Showing 57 changed files with 731 additions and 615 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ ign_configure_project(
# Set project-specific options
#============================================================================

set(IGN_LAUNCH_PLUGIN_INSTALL_PATH "${CMAKE_INSTALL_PREFIX}/${IGN_LIB_INSTALL_DIR}/ign-${IGN_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins/")
set(GZ_LAUNCH_PLUGIN_INSTALL_PATH "${CMAKE_INSTALL_PREFIX}/${IGN_LIB_INSTALL_DIR}/ign-${IGN_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins/")

#============================================================================
# Search for project-specific dependencies
Expand Down
2 changes: 1 addition & 1 deletion CODE_OF_CONDUCT.md
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ further defined and clarified by project maintainers.
## Enforcement

Instances of abusive, harassing, or otherwise unacceptable behavior may be
reported by contacting the project team at [https://ignitionrobotics.org/support](https://ignitionrobotics.org/support). All
reported by contacting the project team at [https://gazebosim.org/support](https://gazebosim.org/support). All
complaints will be reviewed and investigated and will result in a response that
is deemed necessary and appropriate to the circumstances. The project team is
obligated to maintain confidentiality with regard to the reporter of an incident.
Expand Down
2 changes: 1 addition & 1 deletion CONTRIBUTING.md
Original file line number Diff line number Diff line change
@@ -1 +1 @@
See the [Ignition Robotics contributing guide](https://ignitionrobotics.org/docs/all/contributing).
See the [Gazebo contributing guide](https://gazebosim.org/docs/all/contributing).
212 changes: 106 additions & 106 deletions Changelog.md

Large diffs are not rendered by default.

18 changes: 15 additions & 3 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,23 @@ 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
## Gazebo Launch 5.X to 6.X

- Environment variable `IGN_LAUNCH_CONFIG_PATH` started to be treated as a path
- The `ignition` namespace is deprecated and will be removed in future versions.
Use `gz` instead.

- Header files under `ignition/...` are deprecated and will be removed in future versions.
Use `gz/...` instead.

- Migrate `IGN_LAUNCH_PLUGIN_PATH` environment variable to `GZ_LAUNCH_PLUGIN_PATH` for finding
plugin.
With tick-tock.

## Gazebo Launch 2.2.2

- Environment variable `GZ_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
## Gazebo Launch 0.X to N.M
38 changes: 19 additions & 19 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,21 +1,21 @@
# 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/main/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-launch)
Test coverage | [![codecov](https://codecov.io/gh/gazebosim/gz-launch/branch/main/graph/badge.svg)](https://codecov.io/gh/gazebosim/gz-launch)
Ubuntu Focal | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_launch-ci-main-focal-amd64)](https://build.osrfoundation.org/job/ignition_launch-ci-main-focal-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-ign-5-win/badge/icon)](https://build.osrfoundation.org/job/ign_launch-ign-5-win/)

Ignition Launch, a component of [Ignition
Robotics](https://ignitionrobotics.org), provides a command line interface
Gazebo Launch, a component of [Ignition
Robotics](https://gazebosim.org), provides a command line interface
to run and manager application and plugins.

# Table of Contents
Expand All @@ -42,7 +42,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`
Expand All @@ -55,15 +55,15 @@ directory.

# Install

See the [installation tutorial](https://ignitionrobotics.org/api/launch/5.0/install.html).
See the [installation tutorial](https://gazebosim.org/api/launch/5.0/install.html).

# Usage

Sample launch configuration files are in the [examples directory](https://github.com/ignitionrobotics/ign-launch/blob/main/examples/).
Sample launch configuration files are in the [examples directory](https://github.com/gazebosim/gz-launch/blob/main/examples/).

**Example**

1. Run a configuration that launches [Gazebo](https://ignitionrobotics.org/libs/gazebo).
1. Run a configuration that launches [Gazebo](https://gazebosim.org/libs/gazebo).

```
ign launch gazebo.ign
Expand All @@ -75,10 +75,10 @@ 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,
`GZ_CONFIG_PATH` to point to the location of the Ignition library installation,
where the YAML file for the package is found, such as
```
export IGN_CONFIG_PATH=/usr/local/share/ignition
export GZ_CONFIG_PATH=/usr/local/share/ignition
```
However, that environment variable only takes a single path, which means if the
Expand All @@ -93,14 +93,14 @@ ln -s /usr/local/share/ignition/fuel4.yaml .
ln -s /usr/local/share/ignition/transport7.yaml .
ln -s /usr/local/share/ignition/transportlog7.yaml .
...
export IGN_CONFIG_PATH=$HOME/.ignition/tools/configs
export GZ_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
See the [installation tutorial](https://ignitionrobotics.org/api/launch/5.0/install.html).
See the [installation tutorial](https://gazebosim.org/api/launch/5.0/install.html).
# Folder Structure
Expand All @@ -124,17 +124,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-sim/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.
2 changes: 1 addition & 1 deletion api.md.in
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
## Ignition @IGN_DESIGNATION_CAP@

Ignition @IGN_DESIGNATION_CAP@ is a component in Ignition Robotics, a set of libraries
Ignition @IGN_DESIGNATION_CAP@ is a component in Gazebo, a set of libraries
designed to rapidly develop robot and simulation applications.

## License
Expand Down
6 changes: 3 additions & 3 deletions examples/factory.ign
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<ignition version='1.0'>
<plugin name="ignition::launch::GazeboFactory"
<plugin name="gz::launch::GazeboFactory"
filename="ignition-launch-gazebo-factory">
<spawn>
<name>x2</name>
Expand All @@ -11,7 +11,7 @@
<include>
<uri>https://fuel.ignitionrobotics.org/1.0/openrobotics/models/X2 UGV/1</uri>
<plugin filename="ignition-gazebo-diff-drive-system"
name="ignition::gazebo::systems::DiffDrive">
name="gz::sim::systems::DiffDrive">
<left_joint>front_left_wheel_joint</left_joint>
<left_joint>rear_left_wheel_joint</left_joint>
<right_joint>front_right_wheel_joint</right_joint>
Expand All @@ -22,7 +22,7 @@

<!-- Publish robot joint state information -->
<plugin filename="ignition-gazebo-state-publisher-system"
name="ignition::gazebo::systems::JointStatePublisher"></plugin>
name="gz::sim::systems::JointStatePublisher"></plugin>
</include>
</sdf>
</spawn>
Expand Down
22 changes: 11 additions & 11 deletions examples/gazebo_plugins.ign
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
<ignition version='1.0'>
<!-- Load a joystick plugin that will read from a device and output to a
topic -->
<plugin name="ignition::launch::Joystick"
<plugin name="gz::launch::Joystick"
filename="ignition-launch-joystick">
<device>/dev/input/js0</device>
<sticky_buttons>false</sticky_buttons>
Expand All @@ -30,22 +30,22 @@

<!-- Load a plugin that transforms a joystick message to a
twist message -->
<plugin name="ignition::launch::JoyToTwist"
<plugin name="gz::launch::JoyToTwist"
filename="ignition-launch-joytotwist">
<input_topic>/joy</input_topic>
<output_topic>/model/vehicle_green/cmd_vel</output_topic>
</plugin>

<!-- Load a plugin that transforms a joystick message to a
twist message -->
<plugin name="ignition::launch::JoyToTwist"
<plugin name="gz::launch::JoyToTwist"
filename="ignition-launch-joytotwist">
<input_topic>/joy</input_topic>
<output_topic>/model/vehicle_blue/cmd_vel</output_topic>
</plugin>

<!-- Run the gazebo server with a set of plugins -->
<plugin name="ignition::launch::GazeboServer"
<plugin name="gz::launch::GazeboServer"
filename="ignition-launch-gazebo">
<world_file><%= worldName %>.sdf</world_file>
<run>true</run>
Expand Down Expand Up @@ -79,18 +79,18 @@
<plugin entity_name="<%= worldName %>"
entity_type="world"
filename="ignition-gazebo1-physics-system"
name="ignition::gazebo::systems::Physics">
name="gz::sim::systems::Physics">
</plugin>
<plugin entity_name="<%= worldName %>"
entity_type="world"
filename="ignition-gazebo1-scene-broadcaster-system"
name="ignition::gazebo::systems::SceneBroadcaster">
name="gz::sim::systems::SceneBroadcaster">
</plugin>
<plugin entity_name="vehicle_green"
entity_type="model"
filename="ignition-gazebo1-diff-drive-system"
name="ignition::gazebo::systems::DiffDrive">
name="gz::sim::systems::DiffDrive">
<left_joint>left_wheel_joint</left_joint>
<right_joint>right_wheel_joint</right_joint>
<wheel_separation>1.25</wheel_separation>
Expand All @@ -100,7 +100,7 @@
<plugin entity_name="vehicle_blue"
entity_type="model"
filename="ignition-gazebo1-diff-drive-system"
name="ignition::gazebo::systems::DiffDrive">
name="gz::sim::systems::DiffDrive">
<left_joint>left_wheel_joint</left_joint>
<right_joint>right_wheel_joint</right_joint>
<wheel_separation>1.25</wheel_separation>
Expand All @@ -111,14 +111,14 @@
</plugin>

<executable_wrapper>
<plugin name="ignition::launch::GazeboGui"
<plugin name="gz::launch::GazeboGui"
filename="ignition-launch-gazebogui">

<!-- Override default window title (Gazebo) -->
<window_title>Ignition Launch</window_title>
<window_title>Gazebo Launch</window_title>

<!-- Override default icon.
In this example, setting to a resource file shipped with Ignition GUI -->
In this example, setting to a resource file shipped with Gazebo GUI -->
<window_icon>:/qml/images/drawer.png</window_icon>
<plugin filename="GzScene3D" name="3D View">
<ignition-gui>
Expand Down
2 changes: 1 addition & 1 deletion examples/multi_factory.ign
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<ignition version='1.0'>
<plugin name="ignition::launch::GazeboFactory"
<plugin name="gz::launch::GazeboFactory"
filename="ignition-launch-gazebo-factory">
<spawn>
<name>x2</name>
Expand Down
10 changes: 5 additions & 5 deletions examples/plugins.ign
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

<!-- Load a joystick plugin that will read from a device and output to a
topic -->
<plugin name="ignition::launch::Joystick"
<plugin name="gz::launch::Joystick"
filename="ignition-launch-joystick">
<device>/dev/input/js0</device>
<sticky_buttons>false</sticky_buttons>
Expand All @@ -14,20 +14,20 @@

<!-- Load a plugin that transforms a joystick message to a
twist message -->
<plugin name="ignition::launch::JoyToTwist"
<plugin name="gz::launch::JoyToTwist"
filename="ignition-launch-joytotwist">
<input_topic>/joy</input_topic>
<output_topic>/model/vehicle_green/cmd_vel</output_topic>
</plugin>

<!-- Load a plugin that transforms a joystick message to a
twist message -->
<plugin name="ignition::launch::JoyToTwist"
<plugin name="gz::launch::JoyToTwist"
filename="ignition-launch-joytotwist">
<!-- Incoming topic that publishes ignition::msgs::Joystick messages -->
<!-- Incoming topic that publishes gz::msgs::Joystick messages -->
<input_topic>/joy</input_topic>

<!-- Outgoing topic that publishes ignition::msgs::Twist messages -->
<!-- Outgoing topic that publishes gz::msgs::Twist messages -->
<output_topic>/model/vehicle_blue/cmd_vel</output_topic>

<!-- Button which must be pressed to enable publishing, defaults to 0 -->
Expand Down
4 changes: 2 additions & 2 deletions examples/websocket.ign
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version='1.0'?>
<ignition version='1.0'>

<!-- Load a websocket server that provides access to Ignition Transport
<!-- Load a websocket server that provides access to Gazebo Transport
topics through websockets.-->
<plugin name="ignition::launch::WebsocketServer"
<plugin name="gz::launch::WebsocketServer"
filename="ignition-launch-websocket-server">
<publication_hz>30</publication_hz>
<port>9002</port>
Expand Down
8 changes: 4 additions & 4 deletions include/gz/launch/Plugin.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,12 +21,12 @@
#include <gz/plugin/SpecializedPluginPtr.hh>
#include <gz/launch/Export.hh>

namespace ignition
namespace gz
{
namespace launch
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_LAUNCH_VERSION_NAMESPACE {
inline namespace GZ_LAUNCH_VERSION_NAMESPACE {
/// \brief Base class for launch plugins.
class Plugin
{
Expand All @@ -38,8 +38,8 @@ namespace ignition
};

/// \brief Pointer to a launch plugin.
using PluginPtr = ignition::plugin::SpecializedPluginPtr<
ignition::launch::Plugin>;
using PluginPtr = gz::plugin::SpecializedPluginPtr<
gz::launch::Plugin>;
}
}
}
Expand Down
Loading

0 comments on commit 8a74fac

Please sign in to comment.