@@ -1424,9 +1424,8 @@ void RenderUtilPrivate::CreateRenderingEntities(
1424
1424
sdf::Model model;
1425
1425
model.SetName (_name->Data ());
1426
1426
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 ));
1430
1429
this ->modelToModelEntities [_parent->Data ()].push_back (_entity);
1431
1430
return true ;
1432
1431
});
@@ -1493,9 +1492,8 @@ void RenderUtilPrivate::CreateRenderingEntities(
1493
1492
if (auto temp = _ecm.Component <components::Temperature>(_entity))
1494
1493
{
1495
1494
// 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 , " " );
1499
1497
}
1500
1498
else
1501
1499
{
@@ -1529,9 +1527,8 @@ void RenderUtilPrivate::CreateRenderingEntities(
1529
1527
const components::Name *_name,
1530
1528
const components::ParentEntity *_parent) -> bool
1531
1529
{
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 ()));
1535
1532
return true ;
1536
1533
});
1537
1534
@@ -1709,9 +1706,8 @@ void RenderUtilPrivate::CreateRenderingEntities(
1709
1706
sdf::Model model;
1710
1707
model.SetName (_name->Data ());
1711
1708
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 ));
1715
1711
this ->modelToModelEntities [_parent->Data ()].push_back (_entity);
1716
1712
return true ;
1717
1713
});
@@ -1778,9 +1774,8 @@ void RenderUtilPrivate::CreateRenderingEntities(
1778
1774
if (auto temp = _ecm.Component <components::Temperature>(_entity))
1779
1775
{
1780
1776
// 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 , " " );
1784
1779
}
1785
1780
else
1786
1781
{
0 commit comments