Skip to content

Commit

Permalink
Citadel: Removed warnings (#1753)
Browse files Browse the repository at this point in the history
Signed-off-by: ahcorde <[email protected]>
  • Loading branch information
ahcorde authored Oct 10, 2022
1 parent 6fd2cde commit 25ddf2f
Show file tree
Hide file tree
Showing 4 changed files with 2 additions and 6 deletions.
2 changes: 1 addition & 1 deletion src/Util_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -722,7 +722,7 @@ TEST_F(UtilTest, EntityFromMsg)
ecm.CreateComponent(actorDEntity, components::ParentEntity(worldEntity));

// Check entities
auto createMsg = [&ecm](Entity _id, const std::string &_name = "",
auto createMsg = [&](Entity _id, const std::string &_name = "",
msgs::Entity::Type _type = msgs::Entity::NONE) -> msgs::Entity
{
msgs::Entity msg;
Expand Down
1 change: 0 additions & 1 deletion src/systems/altimeter/Altimeter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -245,7 +245,6 @@ void AltimeterPrivate::UpdateAltimeters(const EntityComponentManager &_ecm)
auto it = this->entitySensorMap.find(_entity);
if (it != this->entitySensorMap.end())
{
math::Vector3d linearVel;
math::Pose3d worldPose = _worldPose->Data();
it->second->SetPosition(worldPose.Pos().Z());
it->second->SetVerticalVelocity(_worldLinearVel->Data().Z());
Expand Down
2 changes: 1 addition & 1 deletion src/systems/camera_video_recorder/CameraVideoRecorder.hh
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ namespace systems
///
/// <bitrate> Video recorder bitrate (bps). The default value is
/// 2070000 bps, and the supported type is unsigned int.
class CameraVideoRecorder:
class CameraVideoRecorder final:
public System,
public ISystemConfigure,
public ISystemPostUpdate
Expand Down
3 changes: 0 additions & 3 deletions test/integration/wheel_slip.cc
Original file line number Diff line number Diff line change
Expand Up @@ -238,7 +238,6 @@ TEST_F(WheelSlipTest, TireDrum)
// const double kp = surfaceContactOde->GetElement("kp")->Get<double>();
// ASSERT_EQ(kp, 250e3);

double modelMass = 0.0;
for (const auto &linkName : linksToCheck)
{
Entity linkEntity = ecm->EntityByComponents(
Expand All @@ -249,8 +248,6 @@ TEST_F(WheelSlipTest, TireDrum)
auto inertialComp = ecm->Component<components::Inertial>(linkEntity);

EXPECT_NE(nullptr, inertialComp);

modelMass += inertialComp->Data().MassMatrix().Mass();
}

// Get axle wheel and steer joint of wheel model
Expand Down

0 comments on commit 25ddf2f

Please sign in to comment.