Skip to content

Commit

Permalink
Add redirection headers
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon committed Aug 19, 2022
1 parent eb8efaf commit 11f6ffc
Show file tree
Hide file tree
Showing 299 changed files with 2,570 additions and 1,386 deletions.
5 changes: 4 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,10 @@ find_package(ignition-cmake2 2.14.0 REQUIRED)
#============================================================================
# Configure the project
#============================================================================
ign_configure_project(VERSION_SUFFIX)
ign_configure_project(
REPLACE_IGNITION_INCLUDE_PATH gz/physics
VERSION_SUFFIX pre1
)

#============================================================================
# Set project-specific options
Expand Down
2 changes: 2 additions & 0 deletions dartsim/include/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
add_subdirectory(gz)
install(DIRECTORY ignition DESTINATION ${IGN_INCLUDE_INSTALL_DIR_FULL})
6 changes: 3 additions & 3 deletions dartsim/include/gz/physics/dartsim/World.hh
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,14 @@
*
*/

#ifndef IGNITION_PHYSICS_DARTSIM_WORLD_HH_
#define IGNITION_PHYSICS_DARTSIM_WORLD_HH_
#ifndef GZ_PHYSICS_DARTSIM_WORLD_HH_
#define GZ_PHYSICS_DARTSIM_WORLD_HH_

#include <dart/simulation/World.hpp>

#include <ignition/physics/FeatureList.hh>

namespace ignition {
namespace gz {
namespace physics {
namespace dartsim {

Expand Down
19 changes: 19 additions & 0 deletions dartsim/include/ignition/physics/dartsim-plugin/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/physics/dartsim-plugin/Export.hh>
#include <ignition/physics/config.hh>
19 changes: 19 additions & 0 deletions dartsim/include/ignition/physics/dartsim/World.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/physics/dartsim/World.hh>
#include <ignition/physics/config.hh>
6 changes: 3 additions & 3 deletions dartsim/src/Base.hh
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
*
*/

#ifndef IGNITION_PHYSICS_DARTSIM_BASE_HH_
#define IGNITION_PHYSICS_DARTSIM_BASE_HH_
#ifndef GZ_PHYSICS_DARTSIM_BASE_HH_
#define GZ_PHYSICS_DARTSIM_BASE_HH_

#include <dart/dynamics/BodyNode.hpp>
#include <dart/dynamics/SimpleFrame.hpp>
Expand All @@ -33,7 +33,7 @@
#include <ignition/common/Console.hh>
#include <ignition/physics/Implements.hh>

namespace ignition {
namespace gz {
namespace physics {
namespace dartsim {

Expand Down
2 changes: 1 addition & 1 deletion dartsim/src/Base_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
#include "EntityManagementFeatures.hh"
#include "SDFFeatures.hh"

using namespace ignition::physics;
using namespace gz::physics;



Expand Down
50 changes: 25 additions & 25 deletions dartsim/src/Collisions_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -35,43 +35,43 @@

#include <ignition/common/MeshManager.hh>

using TestFeatureList = ignition::physics::FeatureList<
ignition::physics::LinkFrameSemantics,
ignition::physics::ForwardStep,
ignition::physics::GetEntities,
ignition::physics::ConstructEmptyWorldFeature,
ignition::physics::ConstructEmptyModelFeature,
ignition::physics::ConstructEmptyLinkFeature,
ignition::physics::mesh::AttachMeshShapeFeature,
ignition::physics::AttachPlaneShapeFeature,
ignition::physics::SetFreeJointRelativeTransformFeature,
ignition::physics::AttachFixedJointFeature
using TestFeatureList = gz::physics::FeatureList<
gz::physics::LinkFrameSemantics,
gz::physics::ForwardStep,
gz::physics::GetEntities,
gz::physics::ConstructEmptyWorldFeature,
gz::physics::ConstructEmptyModelFeature,
gz::physics::ConstructEmptyLinkFeature,
gz::physics::mesh::AttachMeshShapeFeature,
gz::physics::AttachPlaneShapeFeature,
gz::physics::SetFreeJointRelativeTransformFeature,
gz::physics::AttachFixedJointFeature
>;

using TestWorldPtr = ignition::physics::World3dPtr<TestFeatureList>;
using TestEnginePtr = ignition::physics::Engine3dPtr<TestFeatureList>;
using TestWorldPtr = gz::physics::World3dPtr<TestFeatureList>;
using TestEnginePtr = gz::physics::Engine3dPtr<TestFeatureList>;

using WorldConstructor = std::function<TestWorldPtr(const TestEnginePtr&)>;

std::unordered_set<TestWorldPtr> LoadWorlds(
const std::string &_library,
const WorldConstructor &_constructor)
{
ignition::plugin::Loader loader;
gz::plugin::Loader loader;
loader.LoadLib(_library);

const std::set<std::string> pluginNames =
ignition::physics::FindFeatures3d<TestFeatureList>::From(loader);
gz::physics::FindFeatures3d<TestFeatureList>::From(loader);

std::unordered_set<TestWorldPtr> worlds;
for (const std::string &name : pluginNames)
{
ignition::plugin::PluginPtr plugin = loader.Instantiate(name);
gz::plugin::PluginPtr plugin = loader.Instantiate(name);

std::cout << " -- Plugin name: " << name << std::endl;

auto engine =
ignition::physics::RequestEngine3d<TestFeatureList>::From(plugin);
gz::physics::RequestEngine3d<TestFeatureList>::From(plugin);
EXPECT_NE(nullptr, engine);

worlds.insert(_constructor(engine));
Expand All @@ -86,11 +86,11 @@ class Collisions_TEST
{};

INSTANTIATE_TEST_CASE_P(PhysicsPlugins, Collisions_TEST,
::testing::ValuesIn(ignition::physics::test::g_PhysicsPluginLibraries),); // NOLINT
::testing::ValuesIn(gz::physics::test::g_PhysicsPluginLibraries),); // NOLINT

TestWorldPtr ConstructMeshPlaneWorld(
const ignition::physics::Engine3dPtr<TestFeatureList> &_engine,
const ignition::common::Mesh &_mesh)
const gz::physics::Engine3dPtr<TestFeatureList> &_engine,
const gz::common::Mesh &_mesh)
{
auto world = _engine->ConstructEmptyWorld("world");

Expand All @@ -109,7 +109,7 @@ TestWorldPtr ConstructMeshPlaneWorld(
model = world->ConstructEmptyModel("plane");
link = model->ConstructEmptyLink("link");

link->AttachPlaneShape("plane", ignition::physics::LinearVector3d::UnitZ());
link->AttachPlaneShape("plane", gz::physics::LinearVector3d::UnitZ());
link->AttachFixedJoint(nullptr);

return world;
Expand All @@ -122,7 +122,7 @@ TEST_P(Collisions_TEST, MeshAndPlane)
return;

const std::string meshFilename = IGNITION_PHYSICS_RESOURCE_DIR "/chassis.dae";
auto &meshManager = *ignition::common::MeshManager::Instance();
auto &meshManager = *gz::common::MeshManager::Instance();
auto *mesh = meshManager.Load(meshFilename);

std::cout << "Testing library " << library << std::endl;
Expand All @@ -138,9 +138,9 @@ TEST_P(Collisions_TEST, MeshAndPlane)
EXPECT_NEAR(
0.0, link->FrameDataRelativeToWorld().pose.translation()[2], 1e-6);

ignition::physics::ForwardStep::Output output;
ignition::physics::ForwardStep::State state;
ignition::physics::ForwardStep::Input input;
gz::physics::ForwardStep::Output output;
gz::physics::ForwardStep::State state;
gz::physics::ForwardStep::Input input;
for (std::size_t i = 0; i < 1000; ++i)
{
world->Step(output, state, input);
Expand Down
2 changes: 1 addition & 1 deletion dartsim/src/CustomFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include "CustomFeatures.hh"

namespace ignition {
namespace gz {
namespace physics {
namespace dartsim {

Expand Down
2 changes: 1 addition & 1 deletion dartsim/src/CustomFeatures.hh
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@

#include "Base.hh"

namespace ignition {
namespace gz {
namespace physics {
namespace dartsim {

Expand Down
18 changes: 9 additions & 9 deletions dartsim/src/CustomMeshShape.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,18 +23,18 @@
#include <ignition/common/Console.hh>
#include <ignition/common/SubMesh.hh>

namespace ignition {
namespace gz {
namespace physics {
namespace dartsim {

namespace {
/////////////////////////////////////////////////
unsigned int CheckNumVerticesPerFaces(
const ignition::common::SubMesh &_inputSubmesh,
const gz::common::SubMesh &_inputSubmesh,
const unsigned int _submeshIndex,
const std::string &_path)
{
using namespace ignition::common;
using namespace gz::common;

const SubMesh::PrimitiveType type = _inputSubmesh.SubMeshPrimitiveType();

Expand Down Expand Up @@ -76,9 +76,9 @@ unsigned int CheckNumVerticesPerFaces(

/////////////////////////////////////////////////
unsigned int GetPrimitiveType(
const ignition::common::SubMesh &_inputSubmesh)
const gz::common::SubMesh &_inputSubmesh)
{
using namespace ignition::common;
using namespace gz::common;

const SubMesh::PrimitiveType type = _inputSubmesh.SubMeshPrimitiveType();

Expand All @@ -97,7 +97,7 @@ unsigned int GetPrimitiveType(

/////////////////////////////////////////////////
CustomMeshShape::CustomMeshShape(
const ignition::common::Mesh &_input,
const gz::common::Mesh &_input,
const Eigen::Vector3d &_scale)
: dart::dynamics::MeshShape(_scale, nullptr)
{
Expand All @@ -123,7 +123,7 @@ CustomMeshShape::CustomMeshShape(
// Fill in submesh contents
for (unsigned int i = 0; i < numSubMeshes; ++i)
{
const ignition::common::SubMeshPtr &inputSubmesh =
const gz::common::SubMeshPtr &inputSubmesh =
_input.SubMeshByIndex(i).lock();

scene->mMeshes[i] = nullptr;
Expand Down Expand Up @@ -205,11 +205,11 @@ CustomMeshShape::CustomMeshShape(

for (unsigned int j = 0; j < numVertices; ++j)
{
const ignition::math::Vector3d &v = inputSubmesh->Vertex(j);
const gz::math::Vector3d &v = inputSubmesh->Vertex(j);
for (unsigned int k = 0; k < 3; ++k)
mesh->mVertices[j][k] = static_cast<ai_real>(v[k]);

const ignition::math::Vector3d &n = inputSubmesh->Normal(j);
const gz::math::Vector3d &n = inputSubmesh->Normal(j);
for (unsigned int k = 0; k < 3; ++k)
mesh->mNormals[j][k] = static_cast<ai_real>(n[k]);
}
Expand Down
12 changes: 6 additions & 6 deletions dartsim/src/CustomMeshShape.hh
Original file line number Diff line number Diff line change
Expand Up @@ -15,28 +15,28 @@
*
*/

#ifndef IGNITION_PHYSICS_DARTSIM_SRC_CUSTOMMESHSHAPE_HH_
#define IGNITION_PHYSICS_DARTSIM_SRC_CUSTOMMESHSHAPE_HH_
#ifndef GZ_PHYSICS_DARTSIM_SRC_CUSTOMMESHSHAPE_HH_
#define GZ_PHYSICS_DARTSIM_SRC_CUSTOMMESHSHAPE_HH_

#include <dart/dynamics/MeshShape.hpp>
#include <ignition/common/Mesh.hh>

namespace ignition {
namespace gz {
namespace physics {
namespace dartsim {

/// \brief This class creates a custom derivative of dartsim's MeshShape class
/// which allows an ignition::common::Mesh to be converted into a MeshShape that
/// which allows an gz::common::Mesh to be converted into a MeshShape that
/// can be used by dartsim.
class CustomMeshShape : public dart::dynamics::MeshShape
{
public: CustomMeshShape(
const ignition::common::Mesh &_input,
const gz::common::Mesh &_input,
const Eigen::Vector3d &_scale);
};

}
}
}

#endif // IGNITION_PHYSICS_DARTSIM_SRC_CUSTOMMESHSHAPE_HH_
#endif // GZ_PHYSICS_DARTSIM_SRC_CUSTOMMESHSHAPE_HH_
2 changes: 1 addition & 1 deletion dartsim/src/EntityManagementFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
#include <dart/collision/CollisionFilter.hpp>
#include <dart/collision/CollisionObject.hpp>

namespace ignition {
namespace gz {
namespace physics {
namespace dartsim {

Expand Down
6 changes: 3 additions & 3 deletions dartsim/src/EntityManagementFeatures.hh
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
*
*/

#ifndef IGNITION_PHYSICS_DARTSIM_SRC_GETENTITIESFEATURE_HH_
#define IGNITION_PHYSICS_DARTSIM_SRC_GETENTITIESFEATURE_HH_
#ifndef GZ_PHYSICS_DARTSIM_SRC_GETENTITIESFEATURE_HH_
#define GZ_PHYSICS_DARTSIM_SRC_GETENTITIESFEATURE_HH_

#include <string>

Expand All @@ -28,7 +28,7 @@

#include "Base.hh"

namespace ignition {
namespace gz {
namespace physics {
namespace dartsim {

Expand Down
Loading

0 comments on commit 11f6ffc

Please sign in to comment.