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

Optional orientation when spawning entity using spherical coordinates #1263

Merged
merged 8 commits into from
Jan 14, 2022
20 changes: 14 additions & 6 deletions src/systems/user_commands/UserCommands.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1112,13 +1112,14 @@ bool CreateCommand::Execute()
this->iface->creator->SetParent(entity, this->iface->worldEntity);

// Pose
math::Pose3d createPose;
if (createMsg->has_pose())
{
auto poseComp = this->iface->ecm->Component<components::Pose>(entity);
*poseComp = components::Pose(msgs::Convert(createMsg->pose()));
createPose = msgs::Convert(createMsg->pose());
}

// Spherical coordinates
else if (createMsg->has_spherical_coordinates())
if (createMsg->has_spherical_coordinates())
{
auto scComp = this->iface->ecm->Component<components::SphericalCoordinates>(
this->iface->worldEntity);
Expand All @@ -1141,12 +1142,19 @@ bool CreateCommand::Execute()
math::SphericalCoordinates::SPHERICAL,
math::SphericalCoordinates::LOCAL2);

auto poseComp = this->iface->ecm->Component<components::Pose>(entity);
*poseComp = components::Pose({pos.X(), pos.Y(), pos.Z(), 0, 0,
IGN_DTOR(createMsg->spherical_coordinates().heading_deg())});
// Override pos and add to yaw
createPose.SetX(pos.X());
createPose.SetY(pos.Y());
createPose.SetZ(pos.Z());
createPose.Rot() = math::Quaterniond(0, 0,
IGN_DTOR(createMsg->spherical_coordinates().heading_deg())) *
createPose.Rot();
}
}

auto poseComp = this->iface->ecm->Component<components::Pose>(entity);
*poseComp = components::Pose(createPose);

igndbg << "Created entity [" << entity << "] named [" << desiredName << "]"
<< std::endl;

Expand Down
14 changes: 14 additions & 0 deletions test/integration/spherical_coordinates.cc
Original file line number Diff line number Diff line change
Expand Up @@ -271,6 +271,7 @@ TEST_F(SphericalCoordinatesTest, CreateEntity)
Entity modelEntity{kNullEntity};
math::SphericalCoordinates worldLatLon;
math::Vector3d modelLatLon;
math::Pose3d modelPose;
fixture.OnPostUpdate(
[&](
const ignition::gazebo::UpdateInfo &,
Expand All @@ -289,6 +290,8 @@ TEST_F(SphericalCoordinatesTest, CreateEntity)
auto modelCoord = sphericalCoordinates(modelEntity, _ecm);
EXPECT_TRUE(modelCoord);
modelLatLon = modelCoord.value();

modelPose = worldPose(modelEntity, _ecm);
}

iterations++;
Expand All @@ -305,13 +308,21 @@ TEST_F(SphericalCoordinatesTest, CreateEntity)

double desiredLat{-23.0};
double desiredLon{-43.3};
double desiredHeading{0.2};
double desiredRoll{0.1};
double desiredPitch{0.2};
double desiredYaw{0.3};

msgs::EntityFactory req;
req.set_sdf(modelStr);

msgs::Set(req.mutable_pose(),
{0, 0, 0, desiredRoll, desiredPitch, desiredYaw});

auto scMsg = req.mutable_spherical_coordinates();
scMsg->set_latitude_deg(desiredLat);
scMsg->set_longitude_deg(desiredLon);
scMsg->set_heading_deg(IGN_RTOD(desiredHeading));

msgs::Boolean res;
bool result;
Expand All @@ -336,4 +347,7 @@ TEST_F(SphericalCoordinatesTest, CreateEntity)
EXPECT_NE(kNullEntity, modelEntity);
EXPECT_NEAR(modelLatLon.X(), desiredLat, 1e-6);
EXPECT_NEAR(modelLatLon.Y(), desiredLon, 1e-6);
EXPECT_DOUBLE_EQ(modelPose.Rot().Roll(), desiredRoll);
EXPECT_DOUBLE_EQ(modelPose.Rot().Pitch(), desiredPitch);
EXPECT_DOUBLE_EQ(modelPose.Rot().Yaw(), desiredHeading + desiredYaw);
}