Skip to content

Commit

Permalink
codecheck
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina committed Sep 22, 2021
1 parent 1cb545b commit 838f350
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 21 deletions.
15 changes: 9 additions & 6 deletions src/EntityComponentManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -213,10 +213,11 @@ class ignition::gazebo::EntityComponentManagerPrivate
/// After cloning is done, these maps can be used to update the cloned model's
/// canonical link to be the cloned canonical link instead of the original
/// model's canonical link. We populate maps during cloning and then update
/// canonical links after cloning since cloning is done top-down, and canonical
/// links are children of models (when a model is cloned, its canonical link
/// has not been cloned yet, so we have no way of knowing what to set the
/// cloned model's canonical link to until the canonical link has been cloned).
/// canonical links after cloning since cloning is done top-down, and
/// canonical links are children of models (when a model is cloned, its
/// canonical link has not been cloned yet, so we have no way of knowing what
/// to set the cloned model's canonical link to until the canonical link has
/// been cloned).
/// \TODO(anyone) We shouldn't be giving canonical links special treatment.
/// This may happen to any component that holds an Entity, so we should figure
/// out a way to generalize this for any such component.
Expand Down Expand Up @@ -307,7 +308,8 @@ Entity EntityComponentManager::Clone(Entity _entity, Entity _parent,
for (const auto &[clonedModel, oldCanonicalLink] :
this->dataPtr->oldModelCanonicalLink)
{
auto iter = this->dataPtr->oldToClonedCanonicalLink.find(oldCanonicalLink);
auto iter = this->dataPtr->oldToClonedCanonicalLink.find(
oldCanonicalLink);
if (iter == this->dataPtr->oldToClonedCanonicalLink.end())
{
ignerr << "Error: attempted to clone model(s) with canonical link(s), "
Expand Down Expand Up @@ -399,7 +401,8 @@ Entity EntityComponentManager::CloneImpl(Entity _entity, Entity _parent,
{
// we're cloning a model, so we map the cloned model to the original
// model's canonical link
this->dataPtr->oldModelCanonicalLink[clonedEntity] = modelCanonLinkComp->Data();
this->dataPtr->oldModelCanonicalLink[clonedEntity] =
modelCanonLinkComp->Data();
}
else if (this->Component<components::CanonicalLink>(clonedEntity))
{
Expand Down
25 changes: 10 additions & 15 deletions src/rendering/RenderUtil.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1424,9 +1424,8 @@ void RenderUtilPrivate::CreateRenderingEntities(
sdf::Model model;
model.SetName(_name->Data());
model.SetRawPose(_pose->Data());
this->newModels.push_back(
std::make_tuple(_entity, model, _parent->Data(),
_info.iterations));
this->newModels.push_back(std::make_tuple(_entity, model,
_parent->Data(), _info.iterations));
this->modelToModelEntities[_parent->Data()].push_back(_entity);
return true;
});
Expand Down Expand Up @@ -1493,9 +1492,8 @@ void RenderUtilPrivate::CreateRenderingEntities(
if (auto temp = _ecm.Component<components::Temperature>(_entity))
{
// get the uniform temperature for the entity
this->entityTemp[_entity] =
std::make_tuple<float, float, std::string>(
temp->Data().Kelvin(), 0.0, "");
this->entityTemp[_entity] = std::make_tuple
<float, float, std::string>(temp->Data().Kelvin(), 0.0, "");
}
else
{
Expand Down Expand Up @@ -1529,9 +1527,8 @@ void RenderUtilPrivate::CreateRenderingEntities(
const components::Name *_name,
const components::ParentEntity *_parent) -> bool
{
this->newActors.push_back(
std::make_tuple(_entity, _actor->Data(), _name->Data(),
_parent->Data()));
this->newActors.push_back(std::make_tuple(_entity, _actor->Data(),
_name->Data(), _parent->Data()));
return true;
});

Expand Down Expand Up @@ -1709,9 +1706,8 @@ void RenderUtilPrivate::CreateRenderingEntities(
sdf::Model model;
model.SetName(_name->Data());
model.SetRawPose(_pose->Data());
this->newModels.push_back(
std::make_tuple(_entity, model, _parent->Data(),
_info.iterations));
this->newModels.push_back(std::make_tuple(_entity, model,
_parent->Data(), _info.iterations));
this->modelToModelEntities[_parent->Data()].push_back(_entity);
return true;
});
Expand Down Expand Up @@ -1778,9 +1774,8 @@ void RenderUtilPrivate::CreateRenderingEntities(
if (auto temp = _ecm.Component<components::Temperature>(_entity))
{
// get the uniform temperature for the entity
this->entityTemp[_entity] =
std::make_tuple<float, float, std::string>(
temp->Data().Kelvin(), 0.0, "");
this->entityTemp[_entity] = std::make_tuple
<float, float, std::string>(temp->Data().Kelvin(), 0.0, "");
}
else
{
Expand Down

0 comments on commit 838f350

Please sign in to comment.