Skip to content

Commit

Permalink
Fix codecheck (#887)
Browse files Browse the repository at this point in the history
Signed-off-by: Nate Koenig <[email protected]>

Co-authored-by: Nate Koenig <[email protected]>
  • Loading branch information
nkoenig and Nate Koenig authored Jun 25, 2021
1 parent 1a7c606 commit 5d2c076
Show file tree
Hide file tree
Showing 5 changed files with 8 additions and 3 deletions.
3 changes: 2 additions & 1 deletion src/rendering/RenderUtil.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
}
Expand Down
3 changes: 1 addition & 2 deletions src/systems/diff_drive/DiffDrive.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Expand Down
3 changes: 3 additions & 0 deletions test/integration/diff_drive_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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));
Expand Down Expand Up @@ -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));
Expand Down Expand Up @@ -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));
Expand Down
1 change: 1 addition & 0 deletions test/integration/odometry_publisher.cc
Original file line number Diff line number Diff line change
Expand Up @@ -260,6 +260,7 @@ class OdometryPublisherTest : public ::testing::TestWithParam<int>

int sleep = 0;
int maxSleep = 30;
// cppcheck-suppress knownConditionTrueFalse
for (; odomPosesCount < 5 && sleep < maxSleep; ++sleep)
{
std::this_thread::sleep_for(std::chrono::milliseconds(100));
Expand Down
1 change: 1 addition & 0 deletions test/integration/optical_tactile_plugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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));
Expand Down

0 comments on commit 5d2c076

Please sign in to comment.