diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 600ccc84f2..eff16149ea 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -1875,7 +1875,8 @@ void RenderUtilPrivate::RemoveSensor(const Entity _entity) auto sensorEntityIt = this->sensorEntities.find(_entity); if (sensorEntityIt != this->sensorEntities.end()) { - this->removeSensorCb(_entity); + if (this->removeSensorCb) + this->removeSensorCb(_entity); this->sensorEntities.erase(sensorEntityIt); } } diff --git a/src/systems/diff_drive/DiffDrive.cc b/src/systems/diff_drive/DiffDrive.cc index 25aa51e381..27226d01af 100644 --- a/src/systems/diff_drive/DiffDrive.cc +++ b/src/systems/diff_drive/DiffDrive.cc @@ -509,8 +509,7 @@ void DiffDrivePrivate::UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, // Construct the Pose_V/tf message and publish it. msgs::Pose_V tfMsg; - ignition::msgs::Pose *tfMsgPose = nullptr; - tfMsgPose = tfMsg.add_pose(); + ignition::msgs::Pose *tfMsgPose = tfMsg.add_pose(); tfMsgPose->mutable_header()->CopyFrom(*msg.mutable_header()); tfMsgPose->mutable_position()->CopyFrom(msg.mutable_pose()->position()); tfMsgPose->mutable_orientation()->CopyFrom(msg.mutable_pose()->orientation()); diff --git a/test/integration/diff_drive_system.cc b/test/integration/diff_drive_system.cc index 20df077115..2a91cba74a 100644 --- a/test/integration/diff_drive_system.cc +++ b/test/integration/diff_drive_system.cc @@ -440,6 +440,7 @@ TEST_P(DiffDriveTest, OdomCustomFrameId) int sleep = 0; int maxSleep = 30; + // cppcheck-suppress knownConditionTrueFalse for (; odomPosesCount < 5 && sleep < maxSleep; ++sleep) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); @@ -499,6 +500,7 @@ TEST_P(DiffDriveTest, Pose_VFrameId) int sleep = 0; int maxSleep = 30; + // cppcheck-suppress knownConditionTrueFalse for (; odomPosesCount < 5 && sleep < maxSleep; ++sleep) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); @@ -558,6 +560,7 @@ TEST_P(DiffDriveTest, Pose_VCustomFrameId) int sleep = 0; int maxSleep = 30; + // cppcheck-suppress knownConditionTrueFalse for (; odomPosesCount < 5 && sleep < maxSleep; ++sleep) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); diff --git a/test/integration/odometry_publisher.cc b/test/integration/odometry_publisher.cc index 248f33e18d..1488dbd14e 100644 --- a/test/integration/odometry_publisher.cc +++ b/test/integration/odometry_publisher.cc @@ -260,6 +260,7 @@ class OdometryPublisherTest : public ::testing::TestWithParam int sleep = 0; int maxSleep = 30; + // cppcheck-suppress knownConditionTrueFalse for (; odomPosesCount < 5 && sleep < maxSleep; ++sleep) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); diff --git a/test/integration/optical_tactile_plugin.cc b/test/integration/optical_tactile_plugin.cc index ea6ec02e85..45ac53609c 100644 --- a/test/integration/optical_tactile_plugin.cc +++ b/test/integration/optical_tactile_plugin.cc @@ -161,6 +161,7 @@ TEST_F(OpticalTactilePluginTest, // Give some time for messages to propagate sleep = 0; + // cppcheck-suppress knownConditionTrueFalse while (!receivedMsg && sleep < maxSleep) { std::this_thread::sleep_for(std::chrono::milliseconds(100));