Skip to content

Commit

Permalink
Added gravity feature to bullet-featherstone (#375)
Browse files Browse the repository at this point in the history
Signed-off-by: ahcorde <[email protected]>
  • Loading branch information
ahcorde authored Jul 12, 2022
1 parent 4202ab6 commit b68a0d7
Show file tree
Hide file tree
Showing 7 changed files with 656 additions and 15 deletions.
31 changes: 18 additions & 13 deletions bullet-featherstone/src/SDFFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ Identity SDFFeatures::ConstructSdfWorld(
auto gravity = _sdfWorld.Gravity();
worldInfo->world->setGravity(btVector3(gravity[0], gravity[1], gravity[2]));

for (std::size_t i=0; i < _sdfWorld.ModelCount(); ++i)
for (std::size_t i = 0; i < _sdfWorld.ModelCount(); ++i)
{
const ::sdf::Model *model = _sdfWorld.ModelByIndex(i);

Expand Down Expand Up @@ -636,26 +636,31 @@ bool SDFFeatures::AddSdfCollision(
mu = ode->Mu();
mu2 = ode->Mu2();
}

if (const auto bullet = friction->Element()->GetElement("bullet"))
if (friction->Element())
{
if (const auto f1 = bullet->GetElement("friction"))
mu = f1->Get<double>();
if (const auto bullet = friction->Element()->GetElement("bullet"))
{
if (const auto f1 = bullet->GetElement("friction"))
mu = f1->Get<double>();

if (const auto f2 = bullet->GetElement("friction2"))
mu2 = f2->Get<double>();
if (const auto f2 = bullet->GetElement("friction2"))
mu2 = f2->Get<double>();

// What is fdir1 for in the SDF's <bullet> spec?
// What is fdir1 for in the SDF's <bullet> spec?

if (const auto rolling = bullet->GetElement("rolling_friction"))
rollingFriction = rolling->Get<double>();
if (const auto rolling = bullet->GetElement("rolling_friction"))
rollingFriction = rolling->Get<double>();
}
}
}

if (const auto bounce = surface->Element()->GetElement("bounce"))
if (surface->Element())
{
if (const auto r = bounce->GetElement("restitution_coefficient"))
restitution = r->Get<double>();
if (const auto bounce = surface->Element()->GetElement("bounce"))
{
if (const auto r = bounce->GetElement("restitution_coefficient"))
restitution = r->Get<double>();
}
}
}

Expand Down
58 changes: 58 additions & 0 deletions bullet-featherstone/src/WorldFeatures.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
/*
* 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 <string>

#include <gz/common/Console.hh>

#include "WorldFeatures.hh"

namespace gz {
namespace physics {
namespace bullet_featherstone {

/////////////////////////////////////////////////
void WorldFeatures::SetWorldGravity(
const Identity &_id, const LinearVectorType &_gravity)
{
auto worldInfo = this->ReferenceInterface<WorldInfo>(_id);
if (worldInfo)
worldInfo->world->setGravity(
btVector3(_gravity(0), _gravity(1), _gravity(2)));
}

/////////////////////////////////////////////////
WorldFeatures::LinearVectorType WorldFeatures::GetWorldGravity(
const Identity &_id) const
{
const auto worldInfo = this->ReferenceInterface<WorldInfo>(_id);
if (worldInfo)
{
// auto world = this->ReferenceInterface<dart::simulation::World>(_id);
return WorldFeatures::LinearVectorType(
worldInfo->world->getGravity().x(),
worldInfo->world->getGravity().y(),
worldInfo->world->getGravity().z());
}
else
{
return WorldFeatures::LinearVectorType(0, 0, 0);
}
}
}
}
}
51 changes: 51 additions & 0 deletions bullet-featherstone/src/WorldFeatures.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 GZ_PHYSICS_BULLET_SRC_WORLDFEATURES_HH_
#define GZ_PHYSICS_BULLET_SRC_WORLDFEATURES_HH_

#include <string>

#include <gz/physics/World.hh>

#include "Base.hh"

namespace gz {
namespace physics {
namespace bullet_featherstone {

struct WorldFeatureList : FeatureList<
Gravity
> { };

class WorldFeatures :
public virtual Base,
public virtual Implements3d<WorldFeatureList>
{
// Documentation inherited
public: void SetWorldGravity(
const Identity &_id, const LinearVectorType &_gravity) override;

// Documentation inherited
public: LinearVectorType GetWorldGravity(const Identity &_id) const override;
};

}
}
}

#endif
7 changes: 5 additions & 2 deletions bullet-featherstone/src/plugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include "KinematicsFeatures.hh"
#include "FreeGroupFeatures.hh"
#include "JointFeatures.hh"
#include "WorldFeatures.hh"

namespace gz {
namespace physics {
Expand All @@ -38,7 +39,8 @@ struct BulletFeatures : FeatureList <
FreeGroupFeatureList,
KinematicsFeatureList,
SDFFeatureList,
JointFeatureList
JointFeatureList,
WorldFeatureList
> { };

class Plugin :
Expand All @@ -49,7 +51,8 @@ class Plugin :
public virtual FreeGroupFeatures,
public virtual KinematicsFeatures,
public virtual SDFFeatures,
public virtual JointFeatures
public virtual JointFeatures,
public virtual WorldFeatures
{};

GZ_PHYSICS_ADD_PLUGIN(Plugin, FeaturePolicy3d, BulletFeatures)
Expand Down
1 change: 1 addition & 0 deletions test/common_test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ set(tests
basic_test
construct_empty_world
simulation_features
world_features
)

function(configure_common_test PHYSICS_ENGINE_NAME test_name)
Expand Down
140 changes: 140 additions & 0 deletions test/common_test/world_features.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,140 @@
/*
* 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 <gtest/gtest.h>

#include <gz/common/Console.hh>
#include <gz/plugin/Loader.hh>

#include "../helpers/TestLibLoader.hh"
#include "../Utils.hh"

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

#include <gz/physics/World.hh>
#include <gz/physics/sdf/ConstructWorld.hh>

#include <sdf/Root.hh>


// A predicate-formatter for asserting that two vectors are approximately equal.
class AssertVectorApprox
{
public: explicit AssertVectorApprox(double _tol = 1e-6) : tol(_tol)
{
}

public: ::testing::AssertionResult operator()(
const char *_mExpr, const char *_nExpr, Eigen::Vector3d _m,
Eigen::Vector3d _n)
{
if (gz::physics::test::Equal(_m, _n, this->tol))
return ::testing::AssertionSuccess();

return ::testing::AssertionFailure()
<< _mExpr << " and " << _nExpr << " ([" << _m.transpose()
<< "] and [" << _n.transpose() << "]"
<< ") are not equal";
}

private: double tol;
};


template <class T>
class WorldFeaturesTest:
public testing::Test, public gz::physics::TestLibLoader
{
// Documentation inherited
public: void SetUp() override
{
gz::common::Console::SetVerbosity(4);

loader.LoadLib(WorldFeaturesTest::GetLibToTest());

// TODO(ahcorde): We should also run the 3f, 2d, and 2f variants of
// FindFeatures
pluginNames = gz::physics::FindFeatures3d<T>::From(loader);
if (pluginNames.empty())
{
std::cerr << "No plugins with required features found in "
<< GetLibToTest() << std::endl;
GTEST_SKIP();
}
}

public: std::set<std::string> pluginNames;
public: gz::plugin::Loader loader;
};

using GravityFeatures = gz::physics::FeatureList<
gz::physics::GetEngineInfo,
gz::physics::Gravity,
gz::physics::sdf::ConstructSdfWorld
>;

template <class T>
class GravityFeaturesTestClass : public WorldFeaturesTest<T>{};
TYPED_TEST_CASE(GravityFeaturesTestClass, GravityFeatures);

/////////////////////////////////////////////////
TYPED_TEST(GravityFeaturesTestClass, GravityFeatures)
{
for (const std::string &name : this->pluginNames)
{
std::cout << "Testing plugin: " << name << std::endl;
gz::plugin::PluginPtr plugin = this->loader.Instantiate(name);

auto engine = gz::physics::RequestEngine3d<GravityFeatures>::From(plugin);
ASSERT_NE(nullptr, engine);
EXPECT_TRUE(engine->GetName().find(this->PhysicsEngineName(name)) !=
std::string::npos);

sdf::Root root;
const sdf::Errors errors = root.Load(
gz::common::joinPaths(TEST_WORLD_DIR, "test.world"));
EXPECT_TRUE(errors.empty()) << errors;
const sdf::World *sdfWorld = root.WorldByIndex(0);
EXPECT_NE(nullptr, sdfWorld);

auto graphErrors = sdfWorld->ValidateGraphs();
EXPECT_EQ(0u, graphErrors.size()) << graphErrors;

Eigen::Vector3d gravity = {0, 0, -9.8};//= Eigen::Vector3d::Zero();

gz::physics::World3dPtr<GravityFeatures> world =
engine->ConstructWorld(*sdfWorld);
EXPECT_NE(nullptr, world);

AssertVectorApprox vectorPredicate(1e-6);
EXPECT_PRED_FORMAT2(vectorPredicate, gravity,
world->GetGravity());

world->SetGravity({8, 4, 3});
EXPECT_PRED_FORMAT2(vectorPredicate, Eigen::Vector3d(8, 4, 3),
world->GetGravity());
}
}

int main(int argc, char *argv[])
{
::testing::InitGoogleTest(&argc, argv);
if(!WorldFeaturesTest<GravityFeatures>::init(argc, argv))
return -1;
return RUN_ALL_TESTS();
}
Loading

0 comments on commit b68a0d7

Please sign in to comment.