diff --git a/bullet-featherstone/src/Base.hh b/bullet-featherstone/src/Base.hh index fcf82e70d..667210328 100644 --- a/bullet-featherstone/src/Base.hh +++ b/bullet-featherstone/src/Base.hh @@ -86,9 +86,13 @@ struct ModelInfo std::string name; Identity world; int indexInWorld; + Eigen::Isometry3d modelToRootLinkTf; Eigen::Isometry3d baseInertiaToLinkFrame; + Eigen::Isometry3d nestedModelFromRootModelTf; std::shared_ptr body; + bool isNestedModel = false; + std::vector linkEntityIds; std::vector jointEntityIds; std::vector nestedModelEntityIds; @@ -103,11 +107,15 @@ struct ModelInfo ModelInfo( std::string _name, Identity _world, + Eigen::Isometry3d _modelToRootLinkTf, Eigen::Isometry3d _baseInertiaToLinkFrame, + Eigen::Isometry3d _nestedModelFromRootModelTf, std::shared_ptr _body) : name(std::move(_name)), world(std::move(_world)), + modelToRootLinkTf(_modelToRootLinkTf), baseInertiaToLinkFrame(_baseInertiaToLinkFrame), + nestedModelFromRootModelTf(_nestedModelFromRootModelTf), body(std::move(_body)) { // Do nothing @@ -310,8 +318,8 @@ class Base : public Implements3d> auto worldID = this->GenerateIdentity(id, world); auto worldModel = std::make_shared( - world->name, worldID, - Eigen::Isometry3d::Identity(), nullptr); + world->name, worldID, Eigen::Isometry3d::Identity(), + Eigen::Isometry3d::Identity(), Eigen::Isometry3d::Identity(), nullptr); this->models[id] = worldModel; world->modelNameToEntityId[worldModel->name] = id; worldModel->indexInWorld = -1; @@ -323,13 +331,17 @@ class Base : public Implements3d> public: inline Identity AddModel( std::string _name, Identity _worldID, + Eigen::Isometry3d _modelToRootLinkTf, Eigen::Isometry3d _baseInertialToLinkFrame, std::shared_ptr _body) { const auto id = this->GetNextEntity(); auto model = std::make_shared( std::move(_name), std::move(_worldID), - std::move(_baseInertialToLinkFrame), std::move(_body)); + std::move(_modelToRootLinkTf), + std::move(_baseInertialToLinkFrame), + Eigen::Isometry3d::Identity(), + std::move(_body)); this->models[id] = model; auto *world = this->ReferenceInterface(model->world); @@ -348,14 +360,20 @@ class Base : public Implements3d> std::string _name, Identity _parentID, Identity _worldID, + Eigen::Isometry3d _modelToRootLinkTf, Eigen::Isometry3d _baseInertialToLinkFrame, + Eigen::Isometry3d _nestedModelFromRootModelTf, std::shared_ptr _body) { const auto id = this->GetNextEntity(); auto model = std::make_shared( std::move(_name), std::move(_worldID), - std::move(_baseInertialToLinkFrame), std::move(_body)); + std::move(_modelToRootLinkTf), + std::move(_baseInertialToLinkFrame), + std::move(_nestedModelFromRootModelTf), + std::move(_body)); + model->isNestedModel = true; this->models[id] = model; const auto parentModel = this->models.at(_parentID); parentModel->nestedModelEntityIds.push_back(id); diff --git a/bullet-featherstone/src/KinematicsFeatures.cc b/bullet-featherstone/src/KinematicsFeatures.cc index c65cc5b48..82fb6421d 100644 --- a/bullet-featherstone/src/KinematicsFeatures.cc +++ b/bullet-featherstone/src/KinematicsFeatures.cc @@ -113,10 +113,17 @@ FrameData3d KinematicsFeatures::FrameDataRelativeToWorld( FrameData data; if (model && model->body) { - data.pose = convert(model->body->getBaseWorldTransform()); - if (!isModel) - data.pose = data.pose * model->baseInertiaToLinkFrame; - if (isCollision) + data.pose = convert(model->body->getBaseWorldTransform()) + * model->baseInertiaToLinkFrame; + if (isModel) + { + data.pose = model->modelToRootLinkTf.inverse() * data.pose; + if (model->isNestedModel) + { + data.pose = data.pose * model->nestedModelFromRootModelTf; + } + } + else if (isCollision) data.pose = data.pose * collisionPoseOffset; data.linearVelocity = convert(model->body->getBaseVel()); data.angularVelocity = convert(model->body->getBaseOmega()); diff --git a/bullet-featherstone/src/SDFFeatures.cc b/bullet-featherstone/src/SDFFeatures.cc index ebb7c686c..4629b51b9 100644 --- a/bullet-featherstone/src/SDFFeatures.cc +++ b/bullet-featherstone/src/SDFFeatures.cc @@ -492,6 +492,12 @@ Identity SDFFeatures::ConstructSdfModelImpl( const bool isStatic = _sdfModel.Static(); WorldInfo *world = nullptr; + + const auto modelToRootLink = + ResolveSdfPose(structure.rootLink->SemanticPose()); + if (!modelToRootLink) + return this->GenerateInvalidId(); + const auto rootInertialToLink = gz::math::eigen3::convert(structure.linkToPrincipalAxesPose).inverse(); @@ -501,7 +507,31 @@ Identity SDFFeatures::ConstructSdfModelImpl( std::unordered_map modelIDs; std::size_t rootModelID = 0u; std::shared_ptr rootMultiBody; - // Add all models, including nested models + + auto getModelScopedName = [&](const ::sdf::Model *_targetModel, + const ::sdf::Model *_parentModel, const std::string &_prefix, + std::string &_modelScopedName, auto &&_getModelScopedName) + { + for (std::size_t i = 0u; i < _parentModel->ModelCount(); ++i) + { + auto childModel = _parentModel->ModelByIndex(i); + if (childModel == _targetModel) + { + _modelScopedName = _prefix + childModel->Name(); + return true; + } + else + { + if (_getModelScopedName(_targetModel, childModel, + _prefix + childModel->Name() + "::", _modelScopedName, + _getModelScopedName)) + return true; + } + } + return false; + }; + + // Add all models, including nested models auto addModels = [&](std::size_t _modelOrWorldID, const ::sdf::Model *_model, auto &&_addModels) { @@ -517,8 +547,22 @@ Identity SDFFeatures::ConstructSdfModelImpl( auto worldIdentity = modelIt->second->world; auto modelIdentity = this->GenerateIdentity(_modelOrWorldID, modelIt->second); + + std::string modelScopedName; + math::Pose3d modelPose; + if (!getModelScopedName(_model, &_sdfModel, + _sdfModel.Name() + "::", modelScopedName, getModelScopedName)) + this->GenerateInvalidId(); + auto errors = _sdfModel.SemanticPose().Resolve(modelPose, + modelScopedName); + if (!errors.empty()) + this->GenerateInvalidId(); + auto modelToNestedModel = math::eigen3::convert(modelPose).inverse(); + return this->AddNestedModel( - _model->Name(), modelIdentity, worldIdentity, rootInertialToLink, + _model->Name(), modelIdentity, worldIdentity, + *modelToRootLink, rootInertialToLink, + modelToNestedModel, rootMultiBody); } else @@ -533,7 +577,9 @@ Identity SDFFeatures::ConstructSdfModelImpl( true); world = this->ReferenceInterface(worldIdentity); auto id = this->AddModel( - _model->Name(), worldIdentity, rootInertialToLink, + _model->Name(), worldIdentity, + *modelToRootLink, + rootInertialToLink, rootMultiBody); rootModelID = id; return id; @@ -829,31 +875,9 @@ Identity SDFFeatures::ConstructSdfModelImpl( // get the scoped name of the model // This is used to resolve the model pose std::string modelScopedName; - auto getModelScopedName = [&](const ::sdf::Model *_targetModel, - const ::sdf::Model *_parentModel, const std::string &_prefix, - auto &&_getModelScopedName) - { - for (std::size_t i = 0u; i < _parentModel->ModelCount(); ++i) - { - auto childModel = _parentModel->ModelByIndex(i); - if (childModel == _targetModel) - { - modelScopedName = _prefix + childModel->Name(); - return true; - } - else - { - if (_getModelScopedName(_targetModel, childModel, - _prefix + childModel->Name() + "::", _getModelScopedName)) - return true; - } - } - return false; - }; - math::Pose3d modelPose; if (!getModelScopedName(structure.model, &_sdfModel, - _sdfModel.Name() + "::", getModelScopedName)) + _sdfModel.Name() + "::", modelScopedName, getModelScopedName)) return this->GenerateInvalidId(); auto errors = _sdfModel.SemanticPose().Resolve(modelPose, @@ -863,11 +887,6 @@ Identity SDFFeatures::ConstructSdfModelImpl( modelToNestedModel = math::eigen3::convert(modelPose).inverse(); } - const auto modelToRootLink = - ResolveSdfPose(structure.rootLink->SemanticPose()); - if (!modelToRootLink) - return this->GenerateInvalidId(); - const auto worldToRootCom = *worldToModel * modelToNestedModel * *modelToRootLink * rootInertialToLink.inverse(); diff --git a/test/common_test/kinematic_features.cc b/test/common_test/kinematic_features.cc index 3b5459bee..c2f047513 100644 --- a/test/common_test/kinematic_features.cc +++ b/test/common_test/kinematic_features.cc @@ -76,11 +76,13 @@ struct KinematicFeaturesList : gz::physics::FeatureList< gz::physics::sdf::ConstructSdfWorld, gz::physics::GetShapeFromLink, gz::physics::GetModelFromWorld, + gz::physics::GetNestedModelFromModel, gz::physics::GetLinkFromModel, gz::physics::GetJointFromModel, gz::physics::JointFrameSemantics, gz::physics::LinkFrameSemantics, - gz::physics::ShapeFrameSemantics + gz::physics::ShapeFrameSemantics, + gz::physics::ModelFrameSemantics > { }; using KinematicFeaturesTestTypes = @@ -206,7 +208,20 @@ TYPED_TEST(KinematicFeaturesTest, LinkFrameSemanticsPose) auto linkCol = nonBaseLink->GetShape("link_collision"); ASSERT_NE(nullptr, linkCol); + auto nestedModel = model->GetNestedModel("nested_model"); + ASSERT_NE(nullptr, nestedModel); + auto nestedLink = nestedModel->GetLink("nested_link"); + ASSERT_NE(nullptr, nestedLink); + auto nestedLinkCol = nestedLink->GetShape("nested_link_collision"); + ASSERT_NE(nullptr, nestedLinkCol); + gz::math::Pose3d actualModelPose(1, 0, 0, 0, 0, 0); + auto modelFrameData = model->FrameDataRelativeToWorld(); + if (this->PhysicsEngineName(name) == "bullet-featherstone") + { + EXPECT_EQ(actualModelPose, + gz::math::eigen3::convert(modelFrameData.pose)); + } auto baseLinkFrameData = baseLink->FrameDataRelativeToWorld(); auto baseLinkPose = gz::math::eigen3::convert(baseLinkFrameData.pose); gz::math::Pose3d actualLinkLocalPose(0, 1, 0, 0, 0, 0); @@ -237,6 +252,33 @@ TYPED_TEST(KinematicFeaturesTest, LinkFrameSemanticsPose) EXPECT_EQ(expectedColWorldPose.Pos(), linkColPose.Pos()); EXPECT_EQ(expectedColWorldPose.Rot().Euler(), linkColPose.Rot().Euler()); + + gz::math::Pose3d actualNestedModelLocalPose(0, 0, 1, 0, 0, 0); + if (this->PhysicsEngineName(name) == "bullet-featherstone") + { + auto nestedModelFrameData = nestedModel->FrameDataRelativeToWorld(); + gz::math::Pose3d expectedNestedModelWorldPose = + actualModelPose * actualNestedModelLocalPose; + EXPECT_EQ(expectedNestedModelWorldPose, + gz::math::eigen3::convert(nestedModelFrameData.pose)); + } + + auto nestedLinkFrameData = nestedLink->FrameDataRelativeToWorld(); + auto nestedLinkPose = gz::math::eigen3::convert(nestedLinkFrameData.pose); + gz::math::Pose3d actualNestedLinkLocalPose(0, 2, 0, 0, 0, 0); + gz::math::Pose3d expectedNestedLinkWorldPose = + actualModelPose * actualNestedModelLocalPose * + actualNestedLinkLocalPose; + EXPECT_EQ(expectedNestedLinkWorldPose, nestedLinkPose); + + auto nestedLinkColFrameData = nestedLinkCol->FrameDataRelativeToWorld(); + auto nestedLinkColPose = + gz::math::eigen3::convert(nestedLinkColFrameData.pose); + auto actualNestedColLocalPose = gz::math::Pose3d(-0.5, 0, 0, 0, 1.5708, 0); + auto expectedNestedColWorldPose = + actualModelPose * actualNestedModelLocalPose * + actualNestedLinkLocalPose * actualNestedColLocalPose; + EXPECT_EQ(expectedNestedColWorldPose, nestedLinkColPose); } } diff --git a/test/common_test/worlds/pose_offset.sdf b/test/common_test/worlds/pose_offset.sdf index 97b2145cd..2eb70f968 100644 --- a/test/common_test/worlds/pose_offset.sdf +++ b/test/common_test/worlds/pose_offset.sdf @@ -6,6 +6,7 @@ 0 1 0 0 0 0 + 0 0 3 0 0 0 100 @@ -34,6 +35,27 @@ + + + 0 0 1 0 0 0 + + + 0 2 0 0 0 0 + + 0 0 0.5 0 0 0 + + + -0.5 0 0 0 1.5708 0 + + + 0.1 + 0.3 + + + + + + base link @@ -41,6 +63,15 @@ 1.0 0 0 + + + link + nested_model::nested_link + + 0.0 0 1 + + +