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

Port IGN macros to GZ #216

Merged
merged 1 commit into from
Jun 20, 2022
Merged
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
2 changes: 1 addition & 1 deletion lrauv_ignition_plugins/src/AcousticCommsPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -355,7 +355,7 @@ void AcousticCommsPlugin::PreUpdate(

}

IGNITION_ADD_PLUGIN(
GZ_ADD_PLUGIN(
tethys::AcousticCommsPlugin,
gz::sim::System,
tethys::AcousticCommsPlugin::ISystemConfigure,
Expand Down
2 changes: 1 addition & 1 deletion lrauv_ignition_plugins/src/ControlPanelPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -110,5 +110,5 @@ void ControlPanel::SetBuoyancyEngine(qreal _volume)
}

// Register this plugin
IGNITION_ADD_PLUGIN(tethys::ControlPanel,
GZ_ADD_PLUGIN(tethys::ControlPanel,
gz::gui::Plugin)
2 changes: 1 addition & 1 deletion lrauv_ignition_plugins/src/HydrodynamicsPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -361,7 +361,7 @@ void HydrodynamicsPlugin::PreUpdate(

};

IGNITION_ADD_PLUGIN(
GZ_ADD_PLUGIN(
tethys::HydrodynamicsPlugin,
gz::sim::System,
tethys::HydrodynamicsPlugin::ISystemConfigure,
Expand Down
2 changes: 1 addition & 1 deletion lrauv_ignition_plugins/src/RangeBearingPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -342,7 +342,7 @@ void RangeBearingPlugin::PreUpdate(

}

IGNITION_ADD_PLUGIN(tethys::RangeBearingPlugin,
GZ_ADD_PLUGIN(tethys::RangeBearingPlugin,
gz::sim::System,
tethys::RangeBearingPlugin::ISystemConfigure,
tethys::RangeBearingPlugin::ISystemPreUpdate)
6 changes: 3 additions & 3 deletions lrauv_ignition_plugins/src/ReferenceAxis.cc
Original file line number Diff line number Diff line change
Expand Up @@ -219,7 +219,7 @@ void ReferenceAxisPrivate::OnPreRender()
{
this->nedVis = this->scene->CreateAxisVisual();
this->scene->RootVisual()->AddChild(this->nedVis);
this->nedVis->SetLocalRotation(IGN_PI, 0, IGN_PI * 0.5);
this->nedVis->SetLocalRotation(GZ_PI, 0, GZ_PI * 0.5);
this->nedVis->SetLocalScale(0.25, 0.25, 0.25);

// Ogre2 doesn't support text yet
Expand Down Expand Up @@ -265,7 +265,7 @@ void ReferenceAxisPrivate::OnPreRender()
vehicleVis->AddChild(fskVis);
// TODO(chapulina) This rotation won't be needed if we update the model
// https://github.com/osrf/lrauv/issues/80
fskVis->SetLocalRotation(IGN_PI, 0, IGN_PI * 0.5);
fskVis->SetLocalRotation(GZ_PI, 0, GZ_PI * 0.5);

// Ogre2 doesn't support text yet
auto textGeom = this->scene->CreateText();
Expand All @@ -288,5 +288,5 @@ void ReferenceAxisPrivate::OnPreRender()
}

// Register this plugin
IGNITION_ADD_PLUGIN(tethys::ReferenceAxis,
GZ_ADD_PLUGIN(tethys::ReferenceAxis,
gz::gui::Plugin)
20 changes: 10 additions & 10 deletions lrauv_ignition_plugins/src/ScienceSensorsSystem.cc
Original file line number Diff line number Diff line change
Expand Up @@ -389,7 +389,7 @@ float ScienceSensorsSystemPrivate::InterpolateInTime(
bool ScienceSensorsSystemPrivate::ReadData(
const gz::sim::EntityComponentManager &_ecm)
{
IGN_PROFILE("ScienceSensorsSystemPrivate::ReadData");
GZ_PROFILE("ScienceSensorsSystemPrivate::ReadData");

if (!this->sphericalCoordinatesInitialized)
{
Expand Down Expand Up @@ -611,7 +611,7 @@ bool ScienceSensorsSystemPrivate::ReadData(
/////////////////////////////////////////////////
void ScienceSensorsSystemPrivate::PublishData()
{
IGN_PROFILE("ScienceSensorsSystemPrivate::PublishData");
GZ_PROFILE("ScienceSensorsSystemPrivate::PublishData");
this->tempPub.Publish(this->tempMsg);
this->chlorPub.Publish(this->chlorMsg);
this->salPub.Publish(this->salMsg);
Expand Down Expand Up @@ -708,8 +708,8 @@ void ScienceSensorsSystem::PreUpdate(
void ScienceSensorsSystem::PostUpdate(const gz::sim::UpdateInfo &_info,
const gz::sim::EntityComponentManager &_ecm)
{
IGN_PROFILE_THREAD_NAME("ScienceSensorsSystem PostUpdate");
IGN_PROFILE("ScienceSensorsSystem::PostUpdate");
GZ_PROFILE_THREAD_NAME("ScienceSensorsSystem PostUpdate");
GZ_PROFILE("ScienceSensorsSystem::PostUpdate");

this->RemoveSensorEntities(_ecm);

Expand Down Expand Up @@ -777,7 +777,7 @@ void ScienceSensorsSystem::PostUpdate(const gz::sim::UpdateInfo &_info,
// to generate data for that sensor.
for (auto &[entity, sensor] : this->entitySensorMap)
{
IGN_PROFILE("ScienceSensorsSystem::LookupInterpolators");
GZ_PROFILE("ScienceSensorsSystem::LookupInterpolators");
auto sensorPosENU = gz::sim::worldPose(entity, _ecm).Pos();
auto spherical = gz::sim::sphericalCoordinates(entity, _ecm).value();
auto sphericalDepthCorrected = gz::math::Vector3d{spherical.X(), spherical.Y(),
Expand Down Expand Up @@ -834,7 +834,7 @@ void ScienceSensorsSystem::PostUpdate(const gz::sim::UpdateInfo &_info,
void ScienceSensorsSystem::RemoveSensorEntities(
const gz::sim::EntityComponentManager &_ecm)
{
IGN_PROFILE("ScienceSensorsSystem::RemoveSensorEntities");
GZ_PROFILE("ScienceSensorsSystem::RemoveSensorEntities");

_ecm.EachRemoved<gz::sim::components::CustomSensor>(
[&](const gz::sim::Entity &_entity,
Expand Down Expand Up @@ -891,7 +891,7 @@ bool ScienceSensorsSystemPrivate::SalinityService(
//////////////////////////////////////////////////
gz::msgs::PointCloudPacked ScienceSensorsSystemPrivate::PointCloudMsg()
{
IGN_PROFILE("ScienceSensorsSystemPrivate::PointCloudMsg");
GZ_PROFILE("ScienceSensorsSystemPrivate::PointCloudMsg");

gz::msgs::PointCloudPacked msg;

Expand Down Expand Up @@ -933,12 +933,12 @@ gz::msgs::PointCloudPacked ScienceSensorsSystemPrivate::PointCloudMsg()
return msg;
}

IGNITION_ADD_PLUGIN(
GZ_ADD_PLUGIN(
tethys::ScienceSensorsSystem,
gz::sim::System,
tethys::ScienceSensorsSystem::ISystemConfigure,
tethys::ScienceSensorsSystem::ISystemPreUpdate,
tethys::ScienceSensorsSystem::ISystemPostUpdate)

IGNITION_ADD_PLUGIN_ALIAS(tethys::ScienceSensorsSystem,
"tethys::ScienceSensorsSystem")
GZ_ADD_PLUGIN_ALIAS(tethys::ScienceSensorsSystem,
"tethys::ScienceSensorsSystem")
2 changes: 1 addition & 1 deletion lrauv_ignition_plugins/src/SpawnPanelPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -94,5 +94,5 @@ void SpawnPanel::Update(const gz::sim::UpdateInfo &,
}

// Register this plugin
IGNITION_ADD_PLUGIN(tethys::SpawnPanel,
GZ_ADD_PLUGIN(tethys::SpawnPanel,
gz::gui::Plugin)
2 changes: 1 addition & 1 deletion lrauv_ignition_plugins/src/TethysCommPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -710,7 +710,7 @@ void TethysCommPlugin::PostUpdate(
}
}

IGNITION_ADD_PLUGIN(
GZ_ADD_PLUGIN(
tethys::TethysCommPlugin,
gz::sim::System,
tethys::TethysCommPlugin::ISystemConfigure,
Expand Down
2 changes: 1 addition & 1 deletion lrauv_ignition_plugins/src/TimeAnalysisPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,7 @@ void TimeAnalysisPlugin::PostUpdate(
}
}

IGNITION_ADD_PLUGIN(
GZ_ADD_PLUGIN(
tethys::TimeAnalysisPlugin,
gz::sim::System,
tethys::TimeAnalysisPlugin::ISystemConfigure,
Expand Down
4 changes: 2 additions & 2 deletions lrauv_ignition_plugins/src/WorldCommPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -203,7 +203,7 @@ void WorldCommPlugin::SpawnCallback(
// The robot model is facing its own -X, so with zero ENU orientation it faces
// West. We add an extra 90 degree yaw so zero means North, to conform with
// NED.
auto rotRobot = gz::math::Quaterniond(0.0, 0.0, -IGN_PI * 0.5) * rotENU;
auto rotRobot = gz::math::Quaterniond(0.0, 0.0, -GZ_PI * 0.5) * rotENU;

gz::msgs::Set(factoryReq.mutable_pose()->mutable_orientation(), rotRobot);

Expand Down Expand Up @@ -313,7 +313,7 @@ std::string WorldCommPlugin::TethysSdfString(const lrauv_ignition_plugins::msgs:
return sdfStr;
}

IGNITION_ADD_PLUGIN(
GZ_ADD_PLUGIN(
tethys::WorldCommPlugin,
gz::sim::System,
tethys::WorldCommPlugin::ISystemConfigure)
2 changes: 1 addition & 1 deletion lrauv_ignition_plugins/src/WorldConfigPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -66,5 +66,5 @@ void WorldConfig::SetFilePath(QUrl _filePath)

}
// Register this plugin
IGNITION_ADD_PLUGIN(tethys::WorldConfig,
GZ_ADD_PLUGIN(tethys::WorldConfig,
gz::gui::Plugin)
Original file line number Diff line number Diff line change
Expand Up @@ -123,6 +123,6 @@ class SimpleAcousticModel : public ICommsModel
}
};

IGNITION_ADD_PLUGIN(SimpleAcousticModel,
GZ_ADD_PLUGIN(SimpleAcousticModel,
SimpleAcousticModel::ICommsModel)
}
2 changes: 1 addition & 1 deletion lrauv_system_tests/test/dynamics/test_hydrodynamics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ TEST(HydrodynamicsTest, DampForwardThrust)
gz::msgs::Double thrustCommand;
// Vehicle is supposed to move at around 1 m/s with a 300 RPM thrust.
// 300 RPM = 300 * 2 pi / 60 = 10 pi rad/s
thrustCommand.set_data(10. * IGN_PI);
thrustCommand.set_data(10. * GZ_PI);
for (auto &publisher : fixture.ThrustPublishers())
{
using namespace std::literals::chrono_literals;
Expand Down
4 changes: 2 additions & 2 deletions lrauv_system_tests/test/missions/test_depth_vbs_mission.cc
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,8 @@ TEST(MissionTest, DepthVBS)
if (times[i] > 3min) // Initialization is complete
{
// Vehicle should not go vertical when tilting nose
EXPECT_LT(poses[i].Rot().Euler().X(), IGN_DTOR(10));
EXPECT_GT(poses[i].Rot().Euler().X(), IGN_DTOR(-10));
EXPECT_LT(poses[i].Rot().Euler().X(), GZ_DTOR(10));
EXPECT_GT(poses[i].Rot().Euler().X(), GZ_DTOR(-10));
}

// Vehicle should not exceed 20m depth
Expand Down
12 changes: 6 additions & 6 deletions lrauv_system_tests/test/missions/test_pitch_mass_mission.cc
Original file line number Diff line number Diff line change
Expand Up @@ -80,13 +80,13 @@ TEST(MissionTest, PitchMass)
// Max Pitch 20 degrees, allowing for an error of
// up to 5 degrees to accomodate for oscillations
// during pitch control.
EXPECT_LT(poses[i].Rot().Euler().X(), IGN_DTOR(25));
EXPECT_GT(poses[i].Rot().Euler().X(), IGN_DTOR(-5));
EXPECT_LT(poses[i].Rot().Euler().X(), GZ_DTOR(25));
EXPECT_GT(poses[i].Rot().Euler().X(), GZ_DTOR(-5));
}

// No roll or yaw
EXPECT_NEAR(poses[i].Rot().Euler().Y(), IGN_DTOR(0), 1e-2);
EXPECT_NEAR(poses[i].Rot().Euler().Z(), IGN_DTOR(0), 1e-2);
EXPECT_NEAR(poses[i].Rot().Euler().Y(), GZ_DTOR(0), 1e-2);
EXPECT_NEAR(poses[i].Rot().Euler().Z(), GZ_DTOR(0), 1e-2);

// Used later for oscillation check.
if (!firstPitch)
Expand All @@ -96,7 +96,7 @@ TEST(MissionTest, PitchMass)
}

// Check if we cross the 20 degree mark
if (prevPitch <= IGN_DTOR(20) && poses[i].Rot().Euler().X() >= IGN_DTOR(20))
if (prevPitch <= GZ_DTOR(20) && poses[i].Rot().Euler().X() >= GZ_DTOR(20))
{
reachedTarget = true;
}
Expand All @@ -110,7 +110,7 @@ TEST(MissionTest, PitchMass)
// Check for oscillation by summing over abs delta in pitch
// Essentially \Sigma abs(f'(x)) < C. In this case C should be near 2*20
// degrees as the vehicle first pitches down and then comes back up.
EXPECT_LE(totalPitchChange, IGN_DTOR(20) * 2.);
EXPECT_LE(totalPitchChange, GZ_DTOR(20) * 2.);

// Make sure the vehicle actually pitched to 20 degrees.
EXPECT_TRUE(reachedTarget);
Expand Down
4 changes: 2 additions & 2 deletions lrauv_system_tests/test/missions/test_yoyo_circle_mission.cc
Original file line number Diff line number Diff line change
Expand Up @@ -62,8 +62,8 @@ TEST(MissionTest, YoYoCircle)
for (size_t i = 0; i < times.size(); ++i)
{
// Pitch should be between -20 and 20 degrees
EXPECT_LT(IGN_DTOR(-20), poses[i].Rot().Pitch());
EXPECT_GT(IGN_DTOR(20), poses[i].Rot().Pitch());
EXPECT_LT(GZ_DTOR(-20), poses[i].Rot().Pitch());
EXPECT_GT(GZ_DTOR(20), poses[i].Rot().Pitch());

if (times[i] > 2min)
{
Expand Down
14 changes: 7 additions & 7 deletions lrauv_system_tests/test/simulation/test_spawn.cc
Original file line number Diff line number Diff line change
Expand Up @@ -93,8 +93,8 @@ TEST(VehicleSpawnTest, Spawn)
ASSERT_TRUE(WaitForConnections(spawnPublisher, 5s));

// No specific orientation, vehicle will face North
const gz::math::Angle lat1 = IGN_DTOR(20.0);
const gz::math::Angle lon1 = IGN_DTOR(20.0);
const gz::math::Angle lat1 = GZ_DTOR(20.0);
const gz::math::Angle lon1 = GZ_DTOR(20.0);
{
lrauv_ignition_plugins::msgs::LRAUVInit spawnMessage;
spawnMessage.mutable_id_()->set_data("vehicle1");
Expand All @@ -118,9 +118,9 @@ TEST(VehicleSpawnTest, Spawn)

// Spawn vehicle facing South
// Orientation is in NED, so 180 degrees yaw is South
const gz::math::Angle lat2 = IGN_DTOR(20.1);
const gz::math::Angle lon2 = IGN_DTOR(20.1);
const gz::math::Angle yaw2 = IGN_DTOR(180);
const gz::math::Angle lat2 = GZ_DTOR(20.1);
const gz::math::Angle lon2 = GZ_DTOR(20.1);
const gz::math::Angle yaw2 = GZ_DTOR(180);
const double depth2 = 10.0;
{
lrauv_ignition_plugins::msgs::LRAUVInit spawnMessage;
Expand Down Expand Up @@ -171,7 +171,7 @@ TEST(VehicleSpawnTest, Spawn)
// Facing North (-90 rotation from default West orientation)
EXPECT_NEAR(0.0, lastPose1.Rot().Roll(), tightTol);
EXPECT_NEAR(0.0, lastPose1.Rot().Pitch(), tightTol);
EXPECT_NEAR(-IGN_PI*0.5, lastPose1.Rot().Yaw(), tightTol);
EXPECT_NEAR(-GZ_PI*0.5, lastPose1.Rot().Yaw(), tightTol);

const auto &lastLatLon1 = observer1.SphericalCoordinates().back();
EXPECT_NEAR(lat1.Degree(), lastLatLon1.X(), tightTol);
Expand Down Expand Up @@ -202,5 +202,5 @@ TEST(VehicleSpawnTest, Spawn)
// it has a 90 degree yaw in ENU
EXPECT_NEAR(0.0, lastPose2.Rot().Roll(), tightTol);
EXPECT_NEAR(0.0, lastPose2.Rot().Pitch(), tightTol);
EXPECT_NEAR(IGN_DTOR(90), lastPose2.Rot().Yaw(), tightTol);
EXPECT_NEAR(GZ_DTOR(90), lastPose2.Rot().Yaw(), tightTol);
}
12 changes: 6 additions & 6 deletions lrauv_system_tests/test/simulation/test_state.cc
Original file line number Diff line number Diff line change
Expand Up @@ -46,9 +46,9 @@ class VehicleStateTest : public ::testing::Test

protected: lrauv_system_tests::VehicleStateTestFixture fixture;

protected: const gz::math::Angle initialLat{IGN_DTOR(35.5999984741211)};
protected: const gz::math::Angle initialLat{GZ_DTOR(35.5999984741211)};

protected: const gz::math::Angle initialLon{IGN_DTOR(-121.779998779297)};
protected: const gz::math::Angle initialLon{GZ_DTOR(-121.779998779297)};
};

// Checks that don't change throughout the test
Expand Down Expand Up @@ -124,7 +124,7 @@ TEST_F(VehicleStateTest, ThrustState)
// Propel vehicle forward by giving the propeller a positive
// angular velocity. Vehicle is supposed to move at around
// 1 m/s with 300 RPM. 300 RPM = 300 * 2 pi / 60 = 10 pi rad/s
command.set_propomegaaction_(10 * IGN_PI);
command.set_propomegaaction_(10 * GZ_PI);

// Neutral buoyancy
command.set_buoyancyaction_(0.0005);
Expand Down Expand Up @@ -153,7 +153,7 @@ TEST_F(VehicleStateTest, ThrustState)
CheckInvariants(latestState);

// Actuators
EXPECT_NEAR(10.0 * IGN_PI, latestState.propomega_(), 1e-6);
EXPECT_NEAR(10.0 * GZ_PI, latestState.propomega_(), 1e-6);
EXPECT_NEAR(0.0, latestState.rudderangle_(), 1e-3);
EXPECT_NEAR(0.0005, latestState.buoyancyposition_(), 1e-6);

Expand Down Expand Up @@ -196,7 +196,7 @@ TEST_F(VehicleStateTest, ThrustAndTurnState)
// Propel vehicle forward by giving the propeller a positive
// angular velocity. Vehicle is supposed to move at around
// 1 m/s with 300 RPM. 300 RPM = 300 * 2 pi / 60 = 10 pi rad/s
command.set_propomegaaction_(10 * IGN_PI);
command.set_propomegaaction_(10 * GZ_PI);

// Neutral buoyancy
command.set_buoyancyaction_(0.0005);
Expand Down Expand Up @@ -236,7 +236,7 @@ TEST_F(VehicleStateTest, ThrustAndTurnState)
CheckInvariants(latestState);

// Actuators
EXPECT_NEAR(10.0 * IGN_PI, latestState.propomega_(), 1e-3);
EXPECT_NEAR(10.0 * GZ_PI, latestState.propomega_(), 1e-3);
EXPECT_NEAR(-0.5, latestState.rudderangle_(), 0.06);
EXPECT_NEAR(0.0005, latestState.buoyancyposition_(), 1e-6);

Expand Down
Loading