Skip to content

Commit

Permalink
Apply scale, and fix codecheck
Browse files Browse the repository at this point in the history
Signed-off-by: Nate Koenig <[email protected]>
  • Loading branch information
Nate Koenig committed Jan 28, 2021
1 parent 7de643d commit e44a66e
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 3 deletions.
4 changes: 2 additions & 2 deletions src/ServerPrivate.cc
Original file line number Diff line number Diff line change
Expand Up @@ -227,15 +227,15 @@ void ServerPrivate::AddRecordPlugin(const ServerConfig &_config)
bool sdfUseLogRecord = (recordPluginElem != nullptr);

bool hasRecordResources {false};
bool hasCompress {false};
bool hasRecordTopics {false};

bool sdfRecordResources;
bool sdfCompress;
std::vector<std::string> sdfRecordTopics;

if (sdfUseLogRecord)
{
bool hasCompress {false};
bool sdfCompress;
std::tie(sdfRecordResources, hasRecordResources) =
recordPluginElem->Get<bool>("record_resources", false);
std::tie(sdfCompress, hasCompress) =
Expand Down
5 changes: 5 additions & 0 deletions src/systems/collada_world_exporter/ColladaWorldExporter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,9 @@ using namespace systems;

class ignition::gazebo::systems::ColladaWorldExporterPrivate
{
// Default constructor
public: ColladaWorldExporterPrivate() = default;

/// \brief Has the world already been exported?.
private: bool exported{false};

Expand Down Expand Up @@ -217,6 +220,8 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate
i = worldMesh.AddMaterial(mat);
}

scale = _geom->Data().MeshShape()->Scale();

addSubmeshFunc(i);
}
}
Expand Down
4 changes: 3 additions & 1 deletion test/integration/diff_drive_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -358,7 +358,8 @@ TEST_P(DiffDriveTest, OdomFrameId)

int sleep = 0;
int maxSleep = 30;
for (; odomPosesCount < 5 && sleep < maxSleep; ++sleep)
// cppcheck-suppress knownConditionTrueFalse
for (; odomPosesCount < 5 && sleep < maxSleep; ++sleep) // NOLINT
{
std::this_thread::sleep_for(std::chrono::milliseconds(100));
}
Expand Down Expand Up @@ -408,6 +409,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

0 comments on commit e44a66e

Please sign in to comment.