Skip to content

Commit

Permalink
ign -> gz Header Migration : ign-physics (#346)
Browse files Browse the repository at this point in the history
* Move header files with git mv

Signed-off-by: methylDragon <[email protected]>

* Create redirection aliases

Signed-off-by: methylDragon <[email protected]>

* Migrate sources in src, test, examples, and include

Signed-off-by: methylDragon <[email protected]>

* Migrate CMake files

Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon authored May 9, 2022
1 parent b52a3f2 commit ce03083
Show file tree
Hide file tree
Showing 185 changed files with 9,311 additions and 8,146 deletions.
4 changes: 3 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,9 @@ find_package(ignition-cmake3 REQUIRED)
#============================================================================
# Configure the project
#============================================================================
ign_configure_project(VERSION_SUFFIX pre1)
ign_configure_project(
REPLACE_IGNITION_INCLUDE_PATH gz/physics
VERSION_SUFFIX pre1)

#============================================================================
# Set project-specific options
Expand Down
5 changes: 5 additions & 0 deletions bullet/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,11 @@ target_link_libraries(${bullet_plugin}
# Note that plugins are currently being installed in 2 places: /lib and the engine-plugins dir
install(TARGETS ${bullet_plugin} DESTINATION ${IGNITION_PHYSICS_ENGINE_INSTALL_DIR})

# Install redirection headers
install(
DIRECTORY include/
DESTINATION "${IGN_INCLUDE_INSTALL_DIR_FULL}")

# The library created by `ign_add_component` includes the ign-physics version
# (i.e. libignition-physics1-name-plugin.so), but for portability,
# we also install an unversioned symlink into the same versioned folder.
Expand Down
18 changes: 18 additions & 0 deletions bullet/include/ignition/physics/bullet-plugin/Export.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
/*
* 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/physics/bullet-plugin/Export.hh>
62 changes: 62 additions & 0 deletions dartsim/include/gz/physics/dartsim/World.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
/*
* Copyright (C) 2018 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 GZ_PHYSICS_DARTSIM_WORLD_HH_
#define GZ_PHYSICS_DARTSIM_WORLD_HH_

#include <dart/simulation/World.hpp>

#include <gz/physics/FeatureList.hh>

namespace ignition {
namespace physics {
namespace dartsim {

/////////////////////////////////////////////////
class RetrieveWorld : public virtual Feature
{
public: template <typename PolicyT, typename FeaturesT>
class World : public virtual Feature::World<PolicyT, FeaturesT>
{
/// \brief Get the underlying dartsim world for this World object.
public: dart::simulation::WorldPtr GetDartsimWorld();
};

public: template <typename PolicyT>
class Implementation : public virtual Feature::Implementation<PolicyT>
{
public: virtual dart::simulation::WorldPtr GetDartsimWorld(
const Identity &_worldID) = 0;
};
};

/////////////////////////////////////////////////
//! [feature template]
template <typename PolicyT, typename FeaturesT>
dart::simulation::WorldPtr RetrieveWorld::World<PolicyT, FeaturesT>
::GetDartsimWorld()
{
return this->template Interface<RetrieveWorld>()
->GetDartsimWorld(this->identity);
}
//! [feature template]

}
}
}

#endif
18 changes: 18 additions & 0 deletions dartsim/include/ignition/physics/dartsim-plugin/Export.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
/*
* 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/physics/dartsim-plugin/Export.hh>
48 changes: 2 additions & 46 deletions dartsim/include/ignition/physics/dartsim/World.hh
Original file line number Diff line number Diff line change
Expand Up @@ -13,50 +13,6 @@
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
*/

#ifndef IGNITION_PHYSICS_DARTSIM_WORLD_HH_
#define IGNITION_PHYSICS_DARTSIM_WORLD_HH_

#include <dart/simulation/World.hpp>

#include <ignition/physics/FeatureList.hh>

namespace ignition {
namespace physics {
namespace dartsim {

/////////////////////////////////////////////////
class RetrieveWorld : public virtual Feature
{
public: template <typename PolicyT, typename FeaturesT>
class World : public virtual Feature::World<PolicyT, FeaturesT>
{
/// \brief Get the underlying dartsim world for this World object.
public: dart::simulation::WorldPtr GetDartsimWorld();
};

public: template <typename PolicyT>
class Implementation : public virtual Feature::Implementation<PolicyT>
{
public: virtual dart::simulation::WorldPtr GetDartsimWorld(
const Identity &_worldID) = 0;
};
};

/////////////////////////////////////////////////
//! [feature template]
template <typename PolicyT, typename FeaturesT>
dart::simulation::WorldPtr RetrieveWorld::World<PolicyT, FeaturesT>
::GetDartsimWorld()
{
return this->template Interface<RetrieveWorld>()
->GetDartsimWorld(this->identity);
}
//! [feature template]

}
}
}

#endif
#include <gz/physics/dartsim/World.hh>
10 changes: 5 additions & 5 deletions examples/hello_world_loader/hello_world_loader.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,12 @@
//! [include statements]
#include <iostream>

#include <ignition/plugin/Loader.hh>
#include <ignition/plugin/PluginPtr.hh>
#include <gz/plugin/Loader.hh>
#include <gz/plugin/PluginPtr.hh>

#include <ignition/physics/FindFeatures.hh>
#include <ignition/physics/GetEntities.hh>
#include <ignition/physics/RequestEngine.hh>
#include <gz/physics/FindFeatures.hh>
#include <gz/physics/GetEntities.hh>
#include <gz/physics/RequestEngine.hh>

// The features that an engine must have to be loaded by this loader.
using Features = ignition::physics::FeatureList<
Expand Down
8 changes: 4 additions & 4 deletions examples/hello_world_plugin/HelloWorldPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,10 @@

////////////////////////////////////////////////////////////
//! [include statements]
#include <ignition/physics/FeatureList.hh>
#include <ignition/physics/FeaturePolicy.hh>
#include <ignition/physics/GetEntities.hh>
#include <ignition/physics/Register.hh>
#include <gz/physics/FeatureList.hh>
#include <gz/physics/FeaturePolicy.hh>
#include <gz/physics/GetEntities.hh>
#include <gz/physics/Register.hh>
//! [include statements]

namespace mock
Expand Down
4 changes: 2 additions & 2 deletions examples/simple_plugin/EntityManagementFeatures.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,11 @@

//! [basic include]
#include <string>
#include <ignition/physics/Implements.hh>
#include <gz/physics/Implements.hh>
//! [basic include]

//! [include feature]
#include <ignition/physics/ConstructEmpty.hh>
#include <gz/physics/ConstructEmpty.hh>

namespace ignition {
namespace physics {
Expand Down
4 changes: 2 additions & 2 deletions examples/simple_plugin/EntityManagementFeatures_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@

#include <iostream>

#include <ignition/plugin/Loader.hh>
#include <ignition/physics/RequestEngine.hh>
#include <gz/plugin/Loader.hh>
#include <gz/physics/RequestEngine.hh>
#include "EntityManagementFeatures.hh"

// Simple executable that loads the simple plugin and constructs a world.
Expand Down
6 changes: 3 additions & 3 deletions examples/simple_plugin/plugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,9 @@
*
*/

#include <ignition/physics/FeatureList.hh>
#include <ignition/physics/FeaturePolicy.hh>
#include <ignition/physics/Register.hh>
#include <gz/physics/FeatureList.hh>
#include <gz/physics/FeaturePolicy.hh>
#include <gz/physics/Register.hh>

#include "EntityManagementFeatures.hh"

Expand Down
116 changes: 116 additions & 0 deletions heightmap/include/gz/physics/heightmap/HeightmapShape.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,116 @@
/*
* Copyright (C) 2021 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 GZ_PHYSICS_HEIGHTMAP_HEIGHTMAPSHAPE_HH_
#define GZ_PHYSICS_HEIGHTMAP_HEIGHTMAPSHAPE_HH_

#include <string>

#include <gz/common/geospatial/HeightmapData.hh>

#include <gz/physics/DeclareShapeType.hh>
#include <gz/physics/Geometry.hh>

namespace ignition
{
namespace physics
{
namespace heightmap
{
IGN_PHYSICS_DECLARE_SHAPE_TYPE(HeightmapShape)

/////////////////////////////////////////////////
class GetHeightmapShapeProperties
: public virtual FeatureWithRequirements<HeightmapShapeCast>
{
public: template <typename PolicyT, typename FeaturesT>
class HeightmapShape : public virtual Entity<PolicyT, FeaturesT>
{
public: using Dimensions =
typename FromPolicy<PolicyT>::template Use<LinearVector>;

/// \brief Get the size of the heightmap in meters.
/// \returns The size of the heightmap.
public: Dimensions GetSize() const;
};

public: template <typename PolicyT>
class Implementation : public virtual Feature::Implementation<PolicyT>
{
public: using Dimensions =
typename FromPolicy<PolicyT>::template Use<LinearVector>;

public: virtual Dimensions GetHeightmapShapeSize(
const Identity &_heightmapID) const = 0;
};
};

/////////////////////////////////////////////////
/// \brief Attach a heightmap shape to a link.
class AttachHeightmapShapeFeature
: public virtual FeatureWithRequirements<HeightmapShapeCast>
{
public: template <typename PolicyT, typename FeaturesT>
class Link : public virtual Feature::Link<PolicyT, FeaturesT>
{
public: using PoseType =
typename FromPolicy<PolicyT>::template Use<Pose>;

public: using Dimensions =
typename FromPolicy<PolicyT>::template Use<LinearVector>;

public: using ShapePtrType = HeightmapShapePtr<PolicyT, FeaturesT>;

/// \brief Attach a heightmap shape to a link.
/// \param[in] _name Shape's name.
/// \param[in] _heightmapData Contains the 3D data for the heigthtmap.
/// \param[in] _pose Position in the world.
/// \param[in] _size Heightmap total size in meters.
/// \param[in] _subSampling Increase sampling to improve resolution.
public: ShapePtrType AttachHeightmapShape(
const std::string &_name,
const common::HeightmapData &_heightmapData,
const PoseType &_pose,
const Dimensions &_size,
int _subSampling = 1);
};

public: template <typename PolicyT>
class Implementation : public virtual Feature::Implementation<PolicyT>
{
public: using PoseType =
typename FromPolicy<PolicyT>::template Use<Pose>;

public: using Dimensions =
typename FromPolicy<PolicyT>::template Use<LinearVector>;

public: virtual Identity AttachHeightmapShape(
const Identity &_linkID,
const std::string &_name,
const common::HeightmapData &_heightmapData,
const PoseType &_pose,
const Dimensions &_size,
int _subSampling) = 0;
};
};
}
}
}

#include <gz/physics/heightmap/detail/HeightmapShape.hh>

#endif // GZ_PHYSICS_HEIGHTMAP_HEIGHTMAPSHAPE_HH_
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,12 @@
*
*/

#ifndef IGNITION_PHYSICS_HEIGHTMAP_DETAIL_HEIGHTMAPSHAPE_HH_
#define IGNITION_PHYSICS_HEIGHTMAP_DETAIL_HEIGHTMAPSHAPE_HH_
#ifndef GZ_PHYSICS_HEIGHTMAP_DETAIL_HEIGHTMAPSHAPE_HH_
#define GZ_PHYSICS_HEIGHTMAP_DETAIL_HEIGHTMAPSHAPE_HH_

#include <string>

#include <ignition/physics/heightmap/HeightmapShape.hh>
#include <gz/physics/heightmap/HeightmapShape.hh>

namespace ignition
{
Expand Down Expand Up @@ -56,4 +56,4 @@ namespace heightmap
}
}

#endif // IGNITION_PHYSICS_MESH_DETAIL_MESHSHAPE_HH_
#endif // GZ_PHYSICS_MESH_DETAIL_MESHSHAPE_HH_
Loading

0 comments on commit ce03083

Please sign in to comment.