Skip to content

Commit

Permalink
Add redirection headers
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <methylDragon@gmail.com>
  • Loading branch information
methylDragon committed Aug 19, 2022
1 parent 9f50db5 commit 4037852
Show file tree
Hide file tree
Showing 41 changed files with 321 additions and 183 deletions.
4 changes: 3 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,9 @@ set(IGN_CMAKE_VER ${ignition-cmake2_VERSION_MAJOR})
#============================================================================
# Configure the project
#============================================================================
ign_configure_project()
ign_configure_project(
REPLACE_IGNITION_INCLUDE_PATH gz/launch
)

#============================================================================
# Set project-specific options
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
18 changes: 9 additions & 9 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,7 +111,7 @@
</plugin>

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

<!-- Override default window title (Gazebo) -->
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
2 changes: 1 addition & 1 deletion examples/websocket.ign
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

<!-- Load a websocket server that provides access to Ignition 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
3 changes: 2 additions & 1 deletion include/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1 +1,2 @@
add_subdirectory(ignition)
add_subdirectory(gz)
install(DIRECTORY ignition DESTINATION ${IGN_INCLUDE_INSTALL_DIR_FULL})
10 changes: 5 additions & 5 deletions include/gz/launch/Plugin.hh
Original file line number Diff line number Diff line change
Expand Up @@ -14,14 +14,14 @@
* limitations under the License.
*
*/
#ifndef IGNITION_LAUNCH_PLUGIN_HH_
#define IGNITION_LAUNCH_PLUGIN_HH_
#ifndef GZ_LAUNCH_PLUGIN_HH_
#define GZ_LAUNCH_PLUGIN_HH_

#include <tinyxml2.h>
#include <ignition/plugin/SpecializedPluginPtr.hh>
#include <ignition/launch/Export.hh>

namespace ignition
namespace gz
{
namespace launch
{
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
19 changes: 19 additions & 0 deletions include/ignition/launch.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
/*
* 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.
*
*/

#include <gz/launch.hh>
#include <ignition/launch/config.hh>
19 changes: 19 additions & 0 deletions include/ignition/launch/Export.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
/*
* 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.
*
*/

#include <gz/launch/Export.hh>
#include <ignition/launch/config.hh>
19 changes: 19 additions & 0 deletions include/ignition/launch/Plugin.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
/*
* 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.
*
*/

#include <gz/launch/Plugin.hh>
#include <ignition/launch/config.hh>
51 changes: 51 additions & 0 deletions include/ignition/launch/config.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
/*
* 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.
*
*/

#ifndef IGNITION_LAUNCH__CONFIG_HH_
#define IGNITION_LAUNCH__CONFIG_HH_

#include <gz/launch/config.hh>

/* Version number */
// #define IGNITION_LAUNCH_MAJOR_VERSION GZ_LAUNCH_MAJOR_VERSION
// #define IGNITION_LAUNCH_MINOR_VERSION GZ_LAUNCH_MINOR_VERSION
// #define IGNITION_LAUNCH_PATCH_VERSION GZ_LAUNCH_PATCH_VERSION

// #define IGNITION_LAUNCH_VERSION GZ_LAUNCH_VERSION
// #define IGNITION_LAUNCH_VERSION_FULL GZ_LAUNCH_VERSION_FULL

// #define IGNITION_LAUNCH_VERSION_HEADER GZ_LAUNCH_VERSION_HEADER

// #define IGNITION_LAUNCH_INITIAL_CONFIG_PATH GZ_LAUNCH_INITIAL_CONFIG_PATH

// #define IGNITION_LAUNCH_PLUGIN_INSTALL_PATH GZ_LAUNCH_PLUGIN_INSTALL_PATH

/* #undef BUILD_TYPE_PROFILE */
/* #undef BUILD_TYPE_DEBUG */
/* #undef BUILD_TYPE_RELEASE */

namespace gz
{
}

namespace ignition
{
using namespace gz;
}


#endif
4 changes: 2 additions & 2 deletions plugins/gazebo_factory/GazeboFactory.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,8 @@
#include <ignition/common/Console.hh>
#include "GazeboFactory.hh"

using namespace ignition;
using namespace ignition::launch;
using namespace gz;
using namespace gz::launch;

/////////////////////////////////////////////////
GazeboFactory::GazeboFactory()
Expand Down
14 changes: 7 additions & 7 deletions plugins/gazebo_factory/GazeboFactory.hh
Original file line number Diff line number Diff line change
Expand Up @@ -14,22 +14,22 @@
* limitations under the License.
*
*/
#ifndef IGNITION_LAUNCH_GAZEBOFACTORY_HH_
#define IGNITION_LAUNCH_GAZEBOFACTORY_HH_
#ifndef GZ_LAUNCH_GAZEBOFACTORY_HH_
#define GZ_LAUNCH_GAZEBOFACTORY_HH_

#include <memory>
#include <ignition/plugin/Register.hh>
#include <ignition/transport/Node.hh>
#include "ignition/launch/Plugin.hh"

namespace ignition
namespace gz
{
namespace launch
{
/// \brief Spawns entities into simulation.
///
/// # Example usage
/// <plugin name="ignition::launch::GazeboFactory"
/// <plugin name="gz::launch::GazeboFactory"
/// filename="ignition-launch-gazebo-factory">
///
/// <spawn>
Expand All @@ -50,7 +50,7 @@ namespace ignition
/// <uri>https://fuel.ignitionrobotics.org/1.0/openrobotics/models/X2 UGV/1</uri>
/// <!-- Publish robot state information -->
/// <plugin filename="ignition-gazebo-state-publisher-system"
/// name="ignition::gazebo::systems::StatePublisher"></plugin>
/// name="gz::sim::systems::StatePublisher"></plugin>
/// </include>
/// </sdf>
/// </spawn>
Expand All @@ -59,7 +59,7 @@ namespace ignition
/// ...
/// </spawn>
/// </plugin>
class GazeboFactory : public ignition::launch::Plugin
class GazeboFactory : public gz::launch::Plugin
{
/// \brief Constructor.
public: GazeboFactory();
Expand Down Expand Up @@ -90,6 +90,6 @@ namespace ignition
}

// Register the plugin
IGNITION_ADD_PLUGIN(ignition::launch::GazeboFactory, ignition::launch::Plugin)
IGNITION_ADD_PLUGIN(gz::launch::GazeboFactory, gz::launch::Plugin)

#endif
6 changes: 3 additions & 3 deletions plugins/gazebo_gui/GazeboGui.cc
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@

#include "GazeboGui.hh"

using namespace ignition;
using namespace ignition::launch;
using namespace gz;
using namespace gz::launch;

/////////////////////////////////////////////////
GazeboGui::GazeboGui()
Expand Down Expand Up @@ -97,7 +97,7 @@ bool GazeboGui::Load(const tinyxml2::XMLElement *_elem)
}
}

auto app = gazebo::gui::createGui(argc, argv, defaultConfigFile.c_str(),
auto app = sim::gui::createGui(argc, argv, defaultConfigFile.c_str(),
defaultConfigFile.c_str(), false);

auto win = app->findChild<gui::MainWindow *>()->QuickWindow();
Expand Down
Loading

0 comments on commit 4037852

Please sign in to comment.