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

Fix model frame data #651

Open
wants to merge 1 commit into
base: bullet_kinematic_feature
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all 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
8 changes: 0 additions & 8 deletions dartsim/src/KinematicsFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -64,14 +64,6 @@ FrameData3d KinematicsFeatures::FrameDataRelativeToWorld(
const dart::dynamics::Frame *KinematicsFeatures::SelectFrame(
const FrameID &_id) const
{
const auto model_it = this->models.idToObject.find(_id.ID());
if (model_it != this->models.idToObject.end())
{
// This is a model FreeGroup frame, so we'll use the first root link as the
// frame
return model_it->second->model->getRootBodyNode();
}

auto framesIt = this->frames.find(_id.ID());
if (framesIt == this->frames.end())
{
Expand Down
20 changes: 7 additions & 13 deletions test/common_test/kinematic_features.cc
Original file line number Diff line number Diff line change
Expand Up @@ -217,11 +217,8 @@ TYPED_TEST(KinematicFeaturesTest, LinkFrameSemanticsPose)

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));
}
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);
Expand Down Expand Up @@ -254,14 +251,11 @@ TYPED_TEST(KinematicFeaturesTest, LinkFrameSemanticsPose)
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 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);
Expand Down
Loading