Skip to content

Commit 838f350

Browse files
committed
codecheck
Signed-off-by: Louise Poubel <[email protected]>
1 parent 1cb545b commit 838f350

File tree

2 files changed

+19
-21
lines changed

2 files changed

+19
-21
lines changed

src/EntityComponentManager.cc

+9-6
Original file line numberDiff line numberDiff line change
@@ -213,10 +213,11 @@ class ignition::gazebo::EntityComponentManagerPrivate
213213
/// After cloning is done, these maps can be used to update the cloned model's
214214
/// canonical link to be the cloned canonical link instead of the original
215215
/// model's canonical link. We populate maps during cloning and then update
216-
/// canonical links after cloning since cloning is done top-down, and canonical
217-
/// links are children of models (when a model is cloned, its canonical link
218-
/// has not been cloned yet, so we have no way of knowing what to set the
219-
/// cloned model's canonical link to until the canonical link has been cloned).
216+
/// canonical links after cloning since cloning is done top-down, and
217+
/// canonical links are children of models (when a model is cloned, its
218+
/// canonical link has not been cloned yet, so we have no way of knowing what
219+
/// to set the cloned model's canonical link to until the canonical link has
220+
/// been cloned).
220221
/// \TODO(anyone) We shouldn't be giving canonical links special treatment.
221222
/// This may happen to any component that holds an Entity, so we should figure
222223
/// out a way to generalize this for any such component.
@@ -307,7 +308,8 @@ Entity EntityComponentManager::Clone(Entity _entity, Entity _parent,
307308
for (const auto &[clonedModel, oldCanonicalLink] :
308309
this->dataPtr->oldModelCanonicalLink)
309310
{
310-
auto iter = this->dataPtr->oldToClonedCanonicalLink.find(oldCanonicalLink);
311+
auto iter = this->dataPtr->oldToClonedCanonicalLink.find(
312+
oldCanonicalLink);
311313
if (iter == this->dataPtr->oldToClonedCanonicalLink.end())
312314
{
313315
ignerr << "Error: attempted to clone model(s) with canonical link(s), "
@@ -399,7 +401,8 @@ Entity EntityComponentManager::CloneImpl(Entity _entity, Entity _parent,
399401
{
400402
// we're cloning a model, so we map the cloned model to the original
401403
// model's canonical link
402-
this->dataPtr->oldModelCanonicalLink[clonedEntity] = modelCanonLinkComp->Data();
404+
this->dataPtr->oldModelCanonicalLink[clonedEntity] =
405+
modelCanonLinkComp->Data();
403406
}
404407
else if (this->Component<components::CanonicalLink>(clonedEntity))
405408
{

src/rendering/RenderUtil.cc

+10-15
Original file line numberDiff line numberDiff line change
@@ -1424,9 +1424,8 @@ void RenderUtilPrivate::CreateRenderingEntities(
14241424
sdf::Model model;
14251425
model.SetName(_name->Data());
14261426
model.SetRawPose(_pose->Data());
1427-
this->newModels.push_back(
1428-
std::make_tuple(_entity, model, _parent->Data(),
1429-
_info.iterations));
1427+
this->newModels.push_back(std::make_tuple(_entity, model,
1428+
_parent->Data(), _info.iterations));
14301429
this->modelToModelEntities[_parent->Data()].push_back(_entity);
14311430
return true;
14321431
});
@@ -1493,9 +1492,8 @@ void RenderUtilPrivate::CreateRenderingEntities(
14931492
if (auto temp = _ecm.Component<components::Temperature>(_entity))
14941493
{
14951494
// get the uniform temperature for the entity
1496-
this->entityTemp[_entity] =
1497-
std::make_tuple<float, float, std::string>(
1498-
temp->Data().Kelvin(), 0.0, "");
1495+
this->entityTemp[_entity] = std::make_tuple
1496+
<float, float, std::string>(temp->Data().Kelvin(), 0.0, "");
14991497
}
15001498
else
15011499
{
@@ -1529,9 +1527,8 @@ void RenderUtilPrivate::CreateRenderingEntities(
15291527
const components::Name *_name,
15301528
const components::ParentEntity *_parent) -> bool
15311529
{
1532-
this->newActors.push_back(
1533-
std::make_tuple(_entity, _actor->Data(), _name->Data(),
1534-
_parent->Data()));
1530+
this->newActors.push_back(std::make_tuple(_entity, _actor->Data(),
1531+
_name->Data(), _parent->Data()));
15351532
return true;
15361533
});
15371534

@@ -1709,9 +1706,8 @@ void RenderUtilPrivate::CreateRenderingEntities(
17091706
sdf::Model model;
17101707
model.SetName(_name->Data());
17111708
model.SetRawPose(_pose->Data());
1712-
this->newModels.push_back(
1713-
std::make_tuple(_entity, model, _parent->Data(),
1714-
_info.iterations));
1709+
this->newModels.push_back(std::make_tuple(_entity, model,
1710+
_parent->Data(), _info.iterations));
17151711
this->modelToModelEntities[_parent->Data()].push_back(_entity);
17161712
return true;
17171713
});
@@ -1778,9 +1774,8 @@ void RenderUtilPrivate::CreateRenderingEntities(
17781774
if (auto temp = _ecm.Component<components::Temperature>(_entity))
17791775
{
17801776
// get the uniform temperature for the entity
1781-
this->entityTemp[_entity] =
1782-
std::make_tuple<float, float, std::string>(
1783-
temp->Data().Kelvin(), 0.0, "");
1777+
this->entityTemp[_entity] = std::make_tuple
1778+
<float, float, std::string>(temp->Data().Kelvin(), 0.0, "");
17841779
}
17851780
else
17861781
{

0 commit comments

Comments
 (0)