Skip to content

Commit

Permalink
🕐 Tock: Remove Fortress deprecations (#1605)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina authored Aug 12, 2022
1 parent d90fab2 commit bfbe868
Show file tree
Hide file tree
Showing 42 changed files with 254 additions and 5,957 deletions.
4 changes: 2 additions & 2 deletions examples/plugin/rendering_plugins/RenderingGuiPlugin.hh
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@
#include <gz/rendering/Scene.hh>

/// \brief Example of a GUI plugin that uses Gazebo Rendering.
/// This plugin works with either Gazebo GUI's Scene3D or Gazebo Sim's
/// Scene3D.
/// This plugin works with Gazebo GUI's MinimalScene or any plugin providing
/// similar functionality.
class RenderingGuiPlugin : public gz::gui::Plugin
{
Q_OBJECT
Expand Down
3 changes: 0 additions & 3 deletions examples/scripts/log_video_recorder/log_video_recorder.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -128,9 +128,6 @@
<lockstep>true</lockstep>
<bitrate>4000000</bitrate>
</record_video>

<!-- disable legacy features used to connect this plugin to GzScene3D -->
<legacy>false</legacy>
</plugin>
</gui>
</world>
Expand Down
78 changes: 46 additions & 32 deletions examples/worlds/conveyor.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -222,41 +222,55 @@

<gui fullscreen="0">
<!-- 3D scene -->
<plugin filename="GzScene3D" name="3D View">
<gz-gui>
<title>3D View</title>
<property type="bool" key="showTitleBar">false</property>
<property type="string" key="state">docked</property>
</gz-gui>
<plugin filename="MinimalScene" name="3D View">
<gz-gui>
<title>3D View</title>
<property type="bool" key="showTitleBar">false</property>
<property type="string" key="state">docked</property>
</gz-gui>

<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.4 0.4 0.4</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.4 0.4 0.4</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
</plugin>

<!-- World control -->
<plugin filename="WorldControl" name="World control">
<gz-gui>
<title>World control</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</property>
<property type="double" key="height">72</property>
<property type="double" key="width">121</property>
<property type="double" key="z">1</property>

<property type="string" key="state">floating</property>
<anchors target="3D View">
<line own="left" target="left"/>
<line own="bottom" target="bottom"/>
</anchors>
</gz-gui>

<play_pause>true</play_pause>
<step>true</step>
<start_paused>true</start_paused>

<!-- Plugins that add functionality to the scene -->
<plugin filename="EntityContextMenuPlugin" name="Entity context menu">
<gz-gui>
<property key="state" type="string">floating</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="GzSceneManager" name="Scene Manager">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="InteractiveViewControl" name="Interactive view control">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="CameraTracking" name="Camera Tracking">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>

<!-- World statistics -->
Expand Down
19 changes: 19 additions & 0 deletions examples/worlds/deprecated_ignition.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
<!--
This example shows that loading plugins with deprecated ignition prefixes still
work, but the user should see warnings printed on the terminal.
It's also attempting to load the GzScene3D GUI plugin, and loads MinimalScene
plus other plugins instead.
-->
<sdf version="1.6">
<world name="empty">
Expand All @@ -18,6 +21,22 @@
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>

<gui fullscreen="0">
<plugin filename="GzScene3D" name="3D View">
<gz-gui>
<title>3D View</title>
<property type="bool" key="showTitleBar">false</property>
<property type="string" key="state">docked</property>
</gz-gui>

<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.4 0.4 0.4</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
</plugin>
</gui>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
Expand Down
9 changes: 0 additions & 9 deletions examples/worlds/minimal_scene.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -214,9 +214,6 @@ Features:
<property key="showTitleBar" type="bool">false</property>
<property key="cardBackground" type="string">#777777</property>
</gz-gui>

<!-- disable legacy features used to connect this plugin to GzScene3D -->
<legacy>false</legacy>
</plugin>

<!-- Screenshot -->
Expand Down Expand Up @@ -251,9 +248,6 @@ Features:
<lockstep>true</lockstep>
<bitrate>4000000</bitrate>
</record_video>

<!-- disable legacy features used to connect this plugin to GzScene3D -->
<legacy>false</legacy>
</plugin>

<!-- Inspector -->
Expand All @@ -275,9 +269,6 @@ Features:
<gz-gui>
<property type="string" key="state">docked_collapsed</property>
</gz-gui>

<!-- disable legacy features used to connect this plugin to GzScene3D -->
<legacy>false</legacy>
</plugin>

</gui>
Expand Down
3 changes: 0 additions & 3 deletions examples/worlds/spherical_coordinates.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -213,9 +213,6 @@ gz service -s /world/spherical_coordinates/set_spherical_coordinates \
<property key="showTitleBar" type="bool">false</property>
<property key="cardBackground" type="string">#777777</property>
</gz-gui>

<!-- disable legacy features used to connect this plugin to GzScene3D -->
<legacy>false</legacy>
</plugin>

<!-- Entity tree -->
Expand Down
63 changes: 51 additions & 12 deletions examples/worlds/tracked_vehicle_simple.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -1723,17 +1723,56 @@
</include>

<gui fullscreen='0'>
<plugin name='3D View' filename='GzScene3D'>
<gz-gui>
<title>3D View</title>
<property type='bool' key='showTitleBar'>0</property>
<property type='string' key='state'>docked</property>
</gz-gui>
<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.4 0.4 0.4</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
<!-- 3D scene -->
<plugin filename="MinimalScene" name="3D View">
<gz-gui>
<title>3D View</title>
<property type="bool" key="showTitleBar">false</property>
<property type="string" key="state">docked</property>
</gz-gui>

<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.4 0.4 0.4</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
</plugin>

<!-- Plugins that add functionality to the scene -->
<plugin filename="EntityContextMenuPlugin" name="Entity context menu">
<gz-gui>
<property key="state" type="string">floating</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="GzSceneManager" name="Scene Manager">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="InteractiveViewControl" name="Interactive view control">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="CameraTracking" name="Camera Tracking">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin name='World control' filename='WorldControl'>
<gz-gui>
Expand Down Expand Up @@ -1819,4 +1858,4 @@
<magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
<atmosphere type='adiabatic'/>
</world>
</sdf>
</sdf>
3 changes: 0 additions & 3 deletions examples/worlds/tunnel.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -89,9 +89,6 @@
<property key="showTitleBar" type="bool">false</property>
<property key="cardBackground" type="string">#666666</property>
</gz-gui>

<!-- disable legacy features used to connect this plugin to GzScene3D -->
<legacy>false</legacy>
</plugin>

<!-- Insert simple shapes -->
Expand Down
6 changes: 0 additions & 6 deletions examples/worlds/video_record_dbl_pendulum.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -134,9 +134,6 @@
<property key="showTitleBar" type="bool">false</property>
<property key="cardBackground" type="string">#777777</property>
</gz-gui>

<!-- disable legacy features used to connect this plugin to GzScene3D -->
<legacy>false</legacy>
</plugin>
<!-- Screenshot -->
<plugin filename="Screenshot" name="Screenshot">
Expand Down Expand Up @@ -225,9 +222,6 @@
<lockstep>true</lockstep>
<bitrate>4000000</bitrate>
</record_video>

<!-- disable legacy features used to connect this plugin to GzScene3D -->
<legacy>false</legacy>
</plugin>
</gui>

Expand Down
43 changes: 0 additions & 43 deletions include/gz/sim/EntityComponentManager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -201,13 +201,6 @@ namespace gz
/// \return True if the provided _typeId has been created.
public: bool HasComponentType(const ComponentTypeId _typeId) const;

/// \brief Check whether an entity has a specific component.
/// \param[in] _entity The entity to check.
/// \param[in] _key The component to check.
/// \return True if the component key belongs to the entity.
public: bool GZ_DEPRECATED(6) EntityHasComponent(const Entity _entity,
const ComponentKey &_key) const;

/// \brief Check whether an entity has a specific component type.
/// \param[in] _entity The entity to check.
/// \param[in] _typeId Component type id to check.
Expand All @@ -223,14 +216,6 @@ namespace gz
public: bool EntityMatches(Entity _entity,
const std::set<ComponentTypeId> &_types) const;

/// \brief Remove a component from an entity based on a key.
/// \param[in] _entity The entity.
/// \param[in] _key A key that uniquely identifies a component.
/// \return True if the entity and component existed and the component was
/// removed.
public: bool GZ_DEPRECATED(6) RemoveComponent(
const Entity _entity, const ComponentKey &_key);

/// \brief Remove a component from an entity based on a type id.
/// \param[in] _entity The entity.
/// \param[in] _typeId Component's type Id.
Expand Down Expand Up @@ -280,22 +265,6 @@ namespace gz
public: template<typename ComponentTypeT>
ComponentTypeT *Component(const Entity _entity);

/// \brief Get a component based on a key.
/// \param[in] _key A key that uniquely identifies a component.
/// \return The component associated with the key, or nullptr if the
/// component could not be found.
public: template<typename ComponentTypeT>
const ComponentTypeT GZ_DEPRECATED(6) * Component(
const ComponentKey &_key) const;

/// \brief Get a mutable component based on a key.
/// \param[in] _key A key that uniquely identifies a component.
/// \return The component associated with the key, or nullptr if the
/// component could not be found.
public: template<typename ComponentTypeT>
ComponentTypeT GZ_DEPRECATED(6) * Component(
const ComponentKey &_key);

/// \brief Get a mutable component assigned to an entity based on a
/// component type. If the component doesn't exist, create it and
/// initialize with the given default value.
Expand Down Expand Up @@ -341,18 +310,6 @@ namespace gz
public: std::unordered_set<ComponentTypeId> ComponentTypes(
Entity _entity) const;

/// \brief The first component instance of the specified type.
/// This function is now deprecated, and will always return nullptr.
/// \return nullptr.
public: template<typename ComponentTypeT>
const ComponentTypeT GZ_DEPRECATED(6) * First() const;

/// \brief The first component instance of the specified type.
/// This function is now deprecated, and will always return nullptr.
/// \return nullptr.
public: template<typename ComponentTypeT>
ComponentTypeT GZ_DEPRECATED(6) * First();

/// \brief Get an entity which matches the value of all the given
/// components. For example, the following will return the entity which
/// has a name component equal to "name" and has a model component:
Expand Down
17 changes: 0 additions & 17 deletions include/gz/sim/Types.hh
Original file line number Diff line number Diff line change
Expand Up @@ -77,32 +77,15 @@ namespace gz
OneTimeChange = 2
};

/// \brief A unique identifier for a component instance. The uniqueness
/// of a ComponentId is scoped to the component's type.
/// \sa ComponentKey.
/// \deprecated Deprecated on version 6, removed on version 7. Use
/// ComponentTypeId + Entity instead.
using ComponentId = int;

/// \brief A unique identifier for a component type. A component type
/// must be derived from `components::BaseComponent` and can contain plain
/// data or something more complex like `gz::math::Pose3d`.
using ComponentTypeId = uint64_t;

/// \brief A key that uniquely identifies, at the global scope, a component
/// instance
/// \note On version 6, the 2nd element was changed to the entity ID.
/// \deprecated Deprecated on version 6, removed on version 7. Use
/// ComponentTypeId + Entity instead.
using ComponentKey = std::pair<ComponentTypeId, Entity>;

/// \brief typedef for query callbacks
using EntityQueryCallback = std::function<void (const UpdateInfo,
EntityComponentManager &)>;

/// \brief Id that indicates an invalid component.
static const ComponentId kComponentIdInvalid = -1;

/// \brief Id that indicates an invalid component type.
static const ComponentTypeId kComponentTypeIdInvalid = UINT64_MAX;
}
Expand Down
Loading

0 comments on commit bfbe868

Please sign in to comment.