Skip to content

Commit

Permalink
Merge pull request #54 from ignitionrobotics/bump_2.1
Browse files Browse the repository at this point in the history
Bump to 2.1 ⬆️

Signed-off-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
chapulina authored May 8, 2020
2 parents 6e96306 + 975aad3 commit 53fae7c
Show file tree
Hide file tree
Showing 13 changed files with 885 additions and 16 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.5.1 FATAL_ERROR)
#============================================================================
# Initialize the project
#============================================================================
project(ignition-physics2 VERSION 2.0.0)
project(ignition-physics2 VERSION 2.1.0)

#============================================================================
# Find ignition-cmake
Expand Down
46 changes: 46 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@

### Ignition Physics 2.x.x (20XX-XX-XX)

### Ignition Physics 2.1.0 (2020-05-07)

1. Add RequestFeatures API for casting the features of an entity to a new feature set when possible.
* [BitBucket pull request 130](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-physics/pull-requests/130)

Expand All @@ -17,6 +19,39 @@
1. Added support for collision bitmasks for collision filtering
* [BitBucket pull request 116](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-physics/pull-requests/116)

1. Clean up internal resources when a model gets removed
* [BitBucket pull request 115](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-physics/pull-requests/115)

1. Trivial Physics Engine - partial implementation
* [BitBucket pull request 125](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-physics/pull-requests/125)
* [BitBucket pull request 126](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-physics/pull-requests/126)
* [Pull request 30](https://github.com/ignitionrobotics/ign-physics/pull/30)
* [Pull request 45](https://github.com/ignitionrobotics/ign-physics/pull/45)

1. Add simple example of physics plugin and loader
* [BitBucket pull request 115](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-physics/pull-requests/115)

1. Update BitBucket links, add .gitignore, CODEOWNERS, workflow
* [Pull request 34](https://github.com/ignitionrobotics/ign-physics/pull/34)
* [Pull request 39](https://github.com/ignitionrobotics/ign-physics/pull/39)
* [Pull request 47](https://github.com/ignitionrobotics/ign-physics/pull/47)
* [Pull request 52](https://github.com/ignitionrobotics/ign-physics/pull/52)

1. Physics Plugin Documentation
* [Pull request 36](https://github.com/ignitionrobotics/ign-physics/pull/36)

1. Reduce the symbol load caused by feature templates
* [Pull request 41](https://github.com/ignitionrobotics/ign-physics/pull/41)

1. Fix collision issue with detachable joints
* [Pull request 31](https://github.com/ignitionrobotics/ign-physics/pull/31)

1. Add PlaneShape feature and implement in dartsim with test.
* [BitBucket pull request 66](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-physics/pull-requests/66)

1. Restore detached BodyNodes to original skeleton
* [Pull request 42](https://github.com/ignitionrobotics/ign-physics/pull/42)

### Ignition Physics 2.0.0 (2019-12-10)

1. Support compiling against dart 6.9.
Expand All @@ -36,6 +71,17 @@

### Ignition Physics 1.x.x (20XX-XX-XX)

1. Restore detached BodyNodes to original skeleton
* [Pull request 42](https://github.com/ignitionrobotics/ign-physics/pull/42)

1. Fix collision issue with detachable joints
* [Pull request 31](https://github.com/ignitionrobotics/ign-physics/pull/31)

1. Add PlaneShape feature and implement in dartsim with test.
* [BitBucket pull request 66](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-physics/pull-requests/66)

### Ignition Physics 1.7.0 (2020-04-13)

1. Add RequestFeatures API for casting the features of an entity to a new feature set when possible.
* [BitBucket pull request 130](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-physics/pull-requests/130)

Expand Down
17 changes: 17 additions & 0 deletions dartsim/src/Base.hh
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,10 @@ struct ModelInfo
struct LinkInfo
{
dart::dynamics::BodyNodePtr link;
/// \brief It may be necessary for dartsim to rename a BodyNode (eg. when
/// moving the BodyNode to a new skeleton), so we store the Gazebo-specified
/// name of the Link here.
std::string name;
};

struct JointInfo
Expand Down Expand Up @@ -125,6 +129,16 @@ struct EntityStorage
return idToObject.at(_id);
}

Value1 &at(const Key2 &_key)
{
return idToObject.at(objectToID.at(_key));
}

const Value1 &at(const Key2 &_key) const
{
return idToObject.at(objectToID.at(_key));
}

std::size_t size() const
{
return idToObject.size();
Expand Down Expand Up @@ -275,6 +289,9 @@ class Base : public Implements3d<FeatureList<Feature>>
const std::size_t id = this->GetNextEntity();
this->links.idToObject[id] = std::make_shared<LinkInfo>();
this->links.idToObject[id]->link = _bn;
// The name of the BodyNode during creation is assumed to be the
// Gazebo-specified name.
this->links.idToObject[id]->name = _bn->getName();
this->links.objectToID[_bn] = id;
this->frames[id] = _bn;

Expand Down
163 changes: 163 additions & 0 deletions dartsim/src/Collisions_TEST.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,163 @@
/*
* Copyright (C) 2019 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 <gtest/gtest.h>

#include <test/PhysicsPluginsList.hh>

#include <ignition/physics/FindFeatures.hh>
#include <ignition/physics/RequestEngine.hh>
#include <ignition/plugin/Loader.hh>

// Features
#include <ignition/physics/ConstructEmpty.hh>
#include <ignition/physics/ForwardStep.hh>
#include <ignition/physics/FrameSemantics.hh>
#include <ignition/physics/FreeJoint.hh>
#include <ignition/physics/GetEntities.hh>
#include <ignition/physics/mesh/MeshShape.hh>
#include <ignition/physics/PlaneShape.hh>
#include <ignition/physics/FixedJoint.hh>

#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 TestWorldPtr = ignition::physics::World3dPtr<TestFeatureList>;
using TestEnginePtr = ignition::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;
loader.LoadLib(_library);

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

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

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

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

worlds.insert(_constructor(engine));
}

return worlds;
}

class Collisions_TEST
: public ::testing::Test,
public ::testing::WithParamInterface<std::string>
{};

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

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

Eigen::Isometry3d tf = Eigen::Isometry3d::Identity();
tf.translation()[2] = 2.0;

auto model = world->ConstructEmptyModel("mesh");
auto link = model->ConstructEmptyLink("link");
// TODO(anyone): This test is somewhat awkward because we lift up the mesh
// from the center of the link instead of lifting up the link or the model.
// We're doing this because we don't currently have an API for moving models
// or links around. See the conversation here for more:
// https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-physics/pull-requests/46/page/1#comment-87592809
link->AttachMeshShape("mesh", _mesh, tf);

model = world->ConstructEmptyModel("plane");
link = model->ConstructEmptyLink("link");

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

return world;
}

TEST_P(Collisions_TEST, MeshAndPlane)
{
const std::string library = GetParam();
if (library.empty())
return;

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

std::cout << "Testing library " << library << std::endl;
auto worlds = LoadWorlds(library, [&](const TestEnginePtr &_engine)
{
return ConstructMeshPlaneWorld(_engine, *mesh);
});

for (const auto &world : worlds)
{
const auto link = world->GetModel(0)->GetLink(0);

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;
for (std::size_t i = 0; i < 1000; ++i)
{
world->Step(output, state, input);
}

// Make sure the mesh was stopped by the plane. In 2000 time steps at the
// default step size of 0.001, a free falling body should drop approximately
// 19.6 meters. As long as the body is somewhere near 1.91, then it has been
// stopped by the plane (the exact value might vary because the body might
// be rocking side-to-side after falling).
EXPECT_NEAR(
-1.91, link->FrameDataRelativeToWorld().pose.translation()[2], 0.05);
}
}

int main(int argc, char *argv[])
{
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
2 changes: 1 addition & 1 deletion dartsim/src/EntityManagementFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -384,7 +384,7 @@ Identity EntityManagementFeatures::GetJoint(
const std::string &EntityManagementFeatures::GetLinkName(
const Identity &_linkID) const
{
return this->ReferenceInterface<LinkInfo>(_linkID)->link->getName();
return this->ReferenceInterface<LinkInfo>(_linkID)->name;
}

/////////////////////////////////////////////////
Expand Down
Loading

0 comments on commit 53fae7c

Please sign in to comment.