Skip to content

Commit

Permalink
ign -> gz Shared Lib Migration : gz-launch (#170)
Browse files Browse the repository at this point in the history
  • Loading branch information
methylDragon authored Jul 12, 2022
1 parent cec9c00 commit e05d212
Show file tree
Hide file tree
Showing 27 changed files with 127 additions and 118 deletions.
4 changes: 2 additions & 2 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -280,7 +280,7 @@

### Gazebo Launch 1.2.0

1. Support for custom random seed in the GazeboServer plugin.
1. Support for custom random seed in the SimServer plugin.
* [BitBucket pull request 33](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-launch/pull-requests/33)

1. Allow specifying a custom window title
Expand All @@ -293,7 +293,7 @@

### Gazebo Launch 1.0.1 (2019-05-22)

1. Fix GazeboFactory set performer topic
1. Fix SimFactory set performer topic
* [BitBucket pull request 26](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-launch/pull-requests/26)

### Gazebo Launch 1.0.0 (2019-05-21)
Expand Down
3 changes: 3 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,9 @@ release will remove the deprecated code.
- The default config file path has been hard-tocked to `~/.gz/launch/gui.config`.
`~/.ignition/launch/gui.config` will no longer work.

- The shared libraries have `gz` where there used to be `ignition`.
- Using the un-migrated version is still possible due to tick-tocks, but will be removed in future versions.

## Gazebo Launch 2.2.2

- Environment variable `GZ_LAUNCH_CONFIG_PATH` started to be treated as a path
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ Sample launch configuration files are in the [examples directory](https://github
1. Run a configuration that launches [Gazebo](https://gazebosim.org/libs/gazebo).

```
gz launch gazebo.ign
gz launch sim.ign
```

## Known issue of command line tools
Expand Down
12 changes: 6 additions & 6 deletions examples/factory.ign
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<ignition version='1.0'>
<plugin name="gz::launch::GazeboFactory"
filename="ignition-launch-gazebo-factory">
<gz version='1.0'>
<plugin name="gz::launch::SimFactory"
filename="gz-launch-sim-factory">
<spawn>
<name>x2</name>
<allow_renaming>true</allow_renaming>
Expand All @@ -10,7 +10,7 @@
<sdf version='1.6'>
<include>
<uri>https://fuel.ignitionrobotics.org/1.0/openrobotics/models/X2 UGV/1</uri>
<plugin filename="ignition-gazebo-diff-drive-system"
<plugin filename="gz-sim-diff-drive-system"
name="gz::sim::systems::DiffDrive">
<left_joint>front_left_wheel_joint</left_joint>
<left_joint>rear_left_wheel_joint</left_joint>
Expand All @@ -21,10 +21,10 @@
</plugin>

<!-- Publish robot joint state information -->
<plugin filename="ignition-gazebo-state-publisher-system"
<plugin filename="gz-sim-state-publisher-system"
name="gz::sim::systems::JointStatePublisher"></plugin>
</include>
</sdf>
</spawn>
</plugin>
</ignition>
</gz>
4 changes: 2 additions & 2 deletions examples/ls.ign
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version='1.0'?>
<ignition version='1.0'>
<gz version='1.0'>
<executable name='ls'>
<command>ls</command>
</executable>
</ignition>
</gz>
8 changes: 4 additions & 4 deletions examples/multi_factory.ign
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<ignition version='1.0'>
<plugin name="gz::launch::GazeboFactory"
filename="ignition-launch-gazebo-factory">
<gz version='1.0'>
<plugin name="gz::launch::SimFactory"
filename="gz-launch-sim-factory">
<spawn>
<name>x2</name>
<allow_renaming>true</allow_renaming>
Expand All @@ -25,4 +25,4 @@
</sdf>
</spawn>
</plugin>
</ignition>
</gz>
12 changes: 6 additions & 6 deletions examples/plugins.ign
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
<?xml version='1.0'?>
<ignition version='1.0'>
<gz version='1.0'>

<!-- Load a joystick plugin that will read from a device and output to a
topic -->
<plugin name="gz::launch::Joystick"
filename="ignition-launch-joystick">
filename="gz-launch-joystick">
<device>/dev/input/js0</device>
<sticky_buttons>false</sticky_buttons>
<dead_zone>0.05</dead_zone>
Expand All @@ -15,15 +15,15 @@
<!-- Load a plugin that transforms a joystick message to a
twist message -->
<plugin name="gz::launch::JoyToTwist"
filename="ignition-launch-joytotwist">
filename="gz-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="gz::launch::JoyToTwist"
filename="ignition-launch-joytotwist">
filename="gz-launch-joytotwist">
<!-- Incoming topic that publishes gz::msgs::Joystick messages -->
<input_topic>/joy</input_topic>

Expand Down Expand Up @@ -56,8 +56,8 @@
<enable_turbo_button>4</enable_turbo_button>
</plugin>

<executable name='gazebo'>
<executable name='sim'>
<command>gz sim diff_drive.sdf</command>
</executable>

</ignition>
</gz>
8 changes: 4 additions & 4 deletions examples/gazebo.ign → examples/sim.ign
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
<?xml version='1.0'?>
<ignition version='1.0'>
<executable name='gazebo-server'>
<gz version='1.0'>
<executable name='sim-server'>
<command>gz sim -s</command>
</executable>

<executable name='gazebo-client'>
<executable name='sim-client'>
<command>gz sim -g</command>
<auto_restart>true</auto_restart>
</executable>

</ignition>
</gz>
26 changes: 13 additions & 13 deletions examples/gazebo_plugins.ign → examples/sim_plugins.ign
Original file line number Diff line number Diff line change
Expand Up @@ -16,11 +16,11 @@
%>

<!-- Requires gz-sim branch support_loading_plugins_programmatically -->
<ignition version='1.0'>
<gz version='1.0'>
<!-- Load a joystick plugin that will read from a device and output to a
topic -->
<plugin name="gz::launch::Joystick"
filename="ignition-launch-joystick">
filename="gz-launch-joystick">
<device>/dev/input/js0</device>
<sticky_buttons>false</sticky_buttons>
<dead_zone>0.05</dead_zone>
Expand All @@ -31,22 +31,22 @@
<!-- Load a plugin that transforms a joystick message to a
twist message -->
<plugin name="gz::launch::JoyToTwist"
filename="ignition-launch-joytotwist">
filename="gz-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="gz::launch::JoyToTwist"
filename="ignition-launch-joytotwist">
filename="gz-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="gz::launch::GazeboServer"
filename="ignition-launch-gazebo">
<plugin name="gz::launch::SimServer"
filename="gz-launch-sim">
<world_file><%= worldName %>.sdf</world_file>
<run>true</run>
<!-- 3000 Hz == 300% RTF == 3x real time -->
Expand Down Expand Up @@ -78,18 +78,18 @@
necessary plugin
<plugin entity_name="<%= worldName %>"
entity_type="world"
filename="ignition-gazebo1-physics-system"
filename="gz-sim-physics-system"
name="gz::sim::systems::Physics">
</plugin>
<plugin entity_name="<%= worldName %>"
entity_type="world"
filename="ignition-gazebo1-scene-broadcaster-system"
filename="gz-sim-scene-broadcaster-system"
name="gz::sim::systems::SceneBroadcaster">
</plugin>
<plugin entity_name="vehicle_green"
entity_type="model"
filename="ignition-gazebo1-diff-drive-system"
filename="gz-sim-diff-drive-system"
name="gz::sim::systems::DiffDrive">
<left_joint>left_wheel_joint</left_joint>
<right_joint>right_wheel_joint</right_joint>
Expand All @@ -99,7 +99,7 @@
<plugin entity_name="vehicle_blue"
entity_type="model"
filename="ignition-gazebo1-diff-drive-system"
filename="gz-sim-diff-drive-system"
name="gz::sim::systems::DiffDrive">
<left_joint>left_wheel_joint</left_joint>
<right_joint>right_wheel_joint</right_joint>
Expand All @@ -111,8 +111,8 @@
</plugin>

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

<!-- Override default window title (Gazebo) -->
<window_title>Gazebo Launch</window_title>
Expand Down Expand Up @@ -194,4 +194,4 @@
</plugin>
</executable_wrapper>

</ignition>
</gz>
6 changes: 3 additions & 3 deletions examples/websocket.ign
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
<?xml version='1.0'?>
<ignition version='1.0'>
<gz version='1.0'>

<!-- Load a websocket server that provides access to Gazebo Transport
topics through websockets.-->
<plugin name="gz::launch::WebsocketServer"
filename="ignition-launch-websocket-server">
filename="gz-launch-websocket-server">
<publication_hz>30</publication_hz>
<port>9002</port>

Expand All @@ -28,4 +28,4 @@
</ssl> -->
</plugin>

</ignition>
</gz>
6 changes: 3 additions & 3 deletions plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
set (plugins
joy_to_twist
gazebo_gui
gazebo_factory
gazebo_server
sim_gui
sim_factory
sim_server
websocket_server
)

Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
set (plugin gz-launch-gazebo-factory)
set (sources GazeboFactory.cc)
set (plugin gz-launch-sim-factory)
set (sources SimFactory.cc)

string (TOLOWER ${plugin} plugin_lower)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,19 +20,19 @@

#include <gz/common/Util.hh>
#include <gz/common/Console.hh>
#include "GazeboFactory.hh"
#include "SimFactory.hh"

using namespace gz;
using namespace gz::launch;

/////////////////////////////////////////////////
GazeboFactory::GazeboFactory()
SimFactory::SimFactory()
: gz::launch::Plugin()
{
}

/////////////////////////////////////////////////
void GazeboFactory::ProcessSpawn(const tinyxml2::XMLElement *_elem)
void SimFactory::ProcessSpawn(const tinyxml2::XMLElement *_elem)
{
const tinyxml2::XMLElement *elem;

Expand Down Expand Up @@ -132,7 +132,7 @@ void GazeboFactory::ProcessSpawn(const tinyxml2::XMLElement *_elem)
}

/////////////////////////////////////////////////
bool GazeboFactory::Load(const tinyxml2::XMLElement *_elem)
bool SimFactory::Load(const tinyxml2::XMLElement *_elem)
{
const tinyxml2::XMLElement *elem;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@ namespace gz
/// \brief Spawns entities into simulation.
///
/// # Example usage
/// <plugin name="gz::launch::GazeboFactory"
/// filename="gz-launch-gazebo-factory">
/// <plugin name="gz::launch::SimFactory"
/// filename="gz-launch-sim-factory">
///
/// <spawn>
/// <!-- Name to give the model -->
Expand Down Expand Up @@ -59,13 +59,13 @@ namespace gz
/// ...
/// </spawn>
/// </plugin>
class GazeboFactory : public gz::launch::Plugin
class SimFactory : public gz::launch::Plugin
{
/// \brief Constructor.
public: GazeboFactory();
public: SimFactory();

/// \brief Destructor.
public: virtual ~GazeboFactory() = default;
public: virtual ~SimFactory() = default;

// Documentation inherited.
public: virtual bool Load(
Expand All @@ -90,6 +90,6 @@ namespace gz
}

// Register the plugin
GZ_ADD_PLUGIN(gz::launch::GazeboFactory, gz::launch::Plugin)
GZ_ADD_PLUGIN(gz::launch::SimFactory, gz::launch::Plugin)

#endif
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
set (plugin gz-launch-gazebogui)
set (sources GazeboGui.cc)
set (plugin gz-launch-simgui)
set (sources SimGui.cc)

string (TOLOWER ${plugin} plugin_lower)

Expand Down
Loading

0 comments on commit e05d212

Please sign in to comment.