Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Support SDFormat 1.8 Composition #542

Merged
merged 16 commits into from
Mar 10, 2021
Merged
Changes from 14 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
102 changes: 90 additions & 12 deletions src/SdfEntityCreator.cc
Original file line number Diff line number Diff line change
@@ -111,6 +111,30 @@ static math::Pose3d ResolveSdfPose(const sdf::SemanticPose &_semPose)
return pose;
}

static std::optional<sdf::JointAxis> ResolveJointAxis(
const sdf::JointAxis &_unresolvedAxis)
{
math::Vector3d axisXyz;
const sdf::Errors resolveAxisErrors = _unresolvedAxis.ResolveXyz(axisXyz);
if (!resolveAxisErrors.empty())
{
ignerr << "Failed to resolve axis" << std::endl;
return std::nullopt;
}

sdf::JointAxis resolvedAxis = _unresolvedAxis;

const sdf::Errors setXyzErrors = resolvedAxis.SetXyz(axisXyz);
if (!setXyzErrors.empty())
{
ignerr << "Failed to resolve axis" << std::endl;
return std::nullopt;
}

resolvedAxis.SetXyzExpressedIn("");
return resolvedAxis;
}

//////////////////////////////////////////////////
SdfEntityCreator::SdfEntityCreator(EntityComponentManager &_ecm,
EventManager &_eventManager)
@@ -293,6 +317,8 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Model *_model,

// Links
bool canonicalLinkCreated = false;
const auto *canonicalLink = _model->CanonicalLink();

for (uint64_t linkIndex = 0; linkIndex < _model->LinkCount();
++linkIndex)
{
@@ -301,9 +327,7 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Model *_model,

this->SetParent(linkEntity, modelEntity);

if (_createCanonicalLink &&
((_model->CanonicalLinkName().empty() && linkIndex == 0) ||
(link == _model->CanonicalLink())))
if (_createCanonicalLink && canonicalLink == link)
{
this->dataPtr->ecm->CreateComponent(linkEntity,
components::CanonicalLink());
@@ -336,10 +360,19 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Model *_model,

// Create nested model. Make sure to only create canonical link component
// in the nested model if a canonical link has not been created in this
// model yet. Also override static propery of the nested model if this model
// is static
// model yet and the canonical link of the top-level model is actually in
// the nested model. Also override static propery of the nested model if
// this model is static

const bool canonicalLinkInNestedModel =
(canonicalLink == nestedModel->CanonicalLink());
const bool createCanonicalLinkInNestedModel =
_createCanonicalLink
&& !canonicalLinkCreated
&& canonicalLinkInNestedModel;

auto nestedModelEntity = this->CreateEntities(nestedModel,
(_createCanonicalLink && !canonicalLinkCreated), isStatic);
createCanonicalLinkInNestedModel, isStatic);

this->SetParent(nestedModelEntity, modelEntity);
}
@@ -481,14 +514,30 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Joint *_joint)

if (_joint->Axis(0))
{
auto resolvedAxis = ResolveJointAxis(*_joint->Axis(0));
if (!resolvedAxis)
{
ignerr << "Failed to resolve joint axis 0 for joint '" << _joint->Name()
<< "'" << std::endl;
return kNullEntity;
azeey marked this conversation as resolved.
Show resolved Hide resolved
}

this->dataPtr->ecm->CreateComponent(jointEntity,
components::JointAxis(*_joint->Axis(0)));
components::JointAxis(std::move(*resolvedAxis)));
}

if (_joint->Axis(1))
{
auto resolvedAxis = ResolveJointAxis(*_joint->Axis(1));
if (!resolvedAxis)
{
ignerr << "Failed to resolve joint axis 1 for joint '" << _joint->Name()
<< "'" << std::endl;
return kNullEntity;
}

this->dataPtr->ecm->CreateComponent(jointEntity,
components::JointAxis2(*_joint->Axis(1)));
components::JointAxis2(std::move(*resolvedAxis)));
}

this->dataPtr->ecm->CreateComponent(jointEntity,
@@ -497,10 +546,39 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Joint *_joint)
components::Name(_joint->Name()));
this->dataPtr->ecm->CreateComponent(jointEntity ,
components::ThreadPitch(_joint->ThreadPitch()));
this->dataPtr->ecm->CreateComponent(jointEntity,
components::ParentLinkName(_joint->ParentLinkName()));
this->dataPtr->ecm->CreateComponent(jointEntity,
components::ChildLinkName(_joint->ChildLinkName()));

std::string resolvedParentLinkName;
const auto resolveParentErrors =
_joint->ResolveParentLink(resolvedParentLinkName);
if (!resolveParentErrors.empty())
{
ignerr << "Failed to resolve parent link for joint '" << _joint->Name()
<< "' with parent name '" << _joint->ParentLinkName() << "'"
<< std::endl;

return kNullEntity;
}
this->dataPtr->ecm->CreateComponent(
jointEntity, components::ParentLinkName(resolvedParentLinkName));

std::string resolvedChildLinkName;
const auto resolveChildErrors =
_joint->ResolveChildLink(resolvedChildLinkName);
if (!resolveChildErrors.empty())
{
ignerr << "Failed to resolve child link for joint '" << _joint->Name()
<< "' with child name '" << _joint->ChildLinkName() << "'"
<< std::endl;
azeey marked this conversation as resolved.
Show resolved Hide resolved
for (const auto &error : resolveChildErrors)
{
ignerr << error << std::endl;
}

return kNullEntity;
}

this->dataPtr->ecm->CreateComponent(
jointEntity, components::ChildLinkName(resolvedChildLinkName));

return jointEntity;
}
2 changes: 2 additions & 0 deletions src/rendering/RenderUtil.cc
Original file line number Diff line number Diff line change
@@ -2050,6 +2050,8 @@ void RenderUtilPrivate::HighlightNode(const rendering::NodePtr &_node)
else
{
ignition::rendering::WireBoxPtr wireBox = wireBoxIt->second;
ignition::math::AxisAlignedBox aabb = vis->LocalBoundingBox();
wireBox->SetBox(aabb);
auto visParent = wireBox->Parent();
if (visParent)
visParent->SetVisible(true);
1 change: 1 addition & 0 deletions test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -34,6 +34,7 @@ set(tests
model.cc
multicopter.cc
multiple_servers.cc
nested_model_physics.cc
network_handshake.cc
particle_emitter.cc
performer_detector.cc
135 changes: 135 additions & 0 deletions test/integration/nested_model_physics.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,135 @@
/*
* 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.
*
*/
#include <gtest/gtest.h>

#include <ignition/common/Console.hh>
#include <ignition/common/Util.hh>

#include "ignition/math/Pose3.hh"
#include "ignition/gazebo/Server.hh"
#include "ignition/gazebo/SystemLoader.hh"
#include "ignition/gazebo/components/Link.hh"
#include "ignition/gazebo/components/Name.hh"
#include "ignition/gazebo/components/Pose.hh"
#include "ignition/gazebo/components/Model.hh"

#include "ignition/gazebo/test_config.hh"
#include "../helpers/Relay.hh"

using namespace ignition;
using namespace gazebo;

class NestedModelPhysicsTest : public ::testing::Test
{
// Documentation inherited
protected: void SetUp() override
{
ignition::common::Console::SetVerbosity(4);
ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str());
}
};

/////////////////////////////////////////////////
/// Test that a tower of 3 boxes built with an <include> and further nesting
/// moves appropriately with joints in dartsim
TEST_F(NestedModelPhysicsTest, Movement)
{
// Start server
ServerConfig serverConfig;
const auto sdfFile = std::string(PROJECT_SOURCE_PATH) +
"/test/worlds/include_connected_nested_models.sdf";
std::string path = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/models";
ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", path.c_str());
serverConfig.SetResourceCache(path);
serverConfig.SetPhysicsEngine("libignition-physics-dartsim-plugin.so");
serverConfig.SetSdfFile(sdfFile);

Server server(serverConfig);
EXPECT_FALSE(server.Running());
EXPECT_FALSE(*server.Running(0));

using namespace std::chrono_literals;
server.SetUpdatePeriod(1ms);

std::size_t iterations = 1000;

bool finished = false;
test::Relay testSystem;
testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info,
const gazebo::EntityComponentManager &_ecm)
{
// Check pose
Entity baseLink = _ecm.EntityByComponents(
components::Link(),
components::Name("base_link"));
ASSERT_NE(baseLink, kNullEntity);

Entity link01 = _ecm.EntityByComponents(
components::Link(), components::Name("link_01"));
ASSERT_NE(link01, kNullEntity);

// Get the top level model
auto topModel = _ecm.EntityByComponents(
components::Name(
"include_connected_nested_new_name"),
components::Model());
ASSERT_NE(topModel, kNullEntity);

auto baseLinkPose = _ecm.Component<components::Pose>(baseLink);
ASSERT_NE(baseLinkPose , nullptr);

auto link01Pose = _ecm.Component<components::Pose>(link01);
ASSERT_NE(link01Pose , nullptr);

constexpr double epsilon = 1e-2;
// base_link does not move in this world
const ignition::math::Pose3d expectedBazeLinkPose(0, 0, 0.5, 0, 0, 0);
const ignition::math::Pose3d expectedLink01StartPose(0, 2, 0, 0, 0, 0);

EXPECT_NEAR(
expectedBazeLinkPose.X(), baseLinkPose->Data().Pos().X(), epsilon);
EXPECT_NEAR(
expectedBazeLinkPose.Y(), baseLinkPose->Data().Pos().Y(), epsilon);
EXPECT_NEAR(
expectedBazeLinkPose.Z(), baseLinkPose->Data().Pos().Z(), epsilon);

if (_info.iterations == 0)
{
EXPECT_NEAR(
expectedLink01StartPose.X(), link01Pose->Data().Pos().X(), epsilon);
EXPECT_NEAR(
expectedLink01StartPose.Y(), link01Pose->Data().Pos().Y(), epsilon);
EXPECT_NEAR(
expectedLink01StartPose.Z(), link01Pose->Data().Pos().Z(), epsilon);
}
else if (_info.iterations == iterations)
{
EXPECT_NEAR(
expectedLink01StartPose.X(), link01Pose->Data().Pos().X(), epsilon);

// Rough approximation on its whereabouts after 1 second
EXPECT_NEAR(-0.36, link01Pose->Data().Pos().Y(), 0.1);
EXPECT_NEAR(1.03, link01Pose->Data().Pos().Z(), 0.1);
finished = true;
}
});

server.AddSystem(testSystem.systemPtr);
server.Run(true, iterations, false);
EXPECT_TRUE(finished);
}
Loading