Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Used Light ign-msgs is_light_off #1449

Merged
merged 5 commits into from
Apr 22, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
29 changes: 2 additions & 27 deletions src/Conversions.cc
Original file line number Diff line number Diff line change
Expand Up @@ -570,15 +570,7 @@ msgs::Light ignition::gazebo::convert(const sdf::Light &_in)
out.set_spot_inner_angle(_in.SpotInnerAngle().Radian());
out.set_spot_outer_angle(_in.SpotOuterAngle().Radian());
out.set_spot_falloff(_in.SpotFalloff());

{
// todo(ahcorde) Use the field is_light_off in light.proto from
// Garden on.
auto header = out.mutable_header()->add_data();
header->set_key("isLightOn");
std::string *value = header->add_value();
*value = std::to_string(_in.LightOn());
}
out.set_is_light_off(!_in.LightOn());
out.set_visualize_visual(_in.Visualize());

if (_in.Type() == sdf::LightType::POINT)
Expand Down Expand Up @@ -610,26 +602,9 @@ sdf::Light ignition::gazebo::convert(const msgs::Light &_in)
out.SetSpotInnerAngle(math::Angle(_in.spot_inner_angle()));
out.SetSpotOuterAngle(math::Angle(_in.spot_outer_angle()));
out.SetSpotFalloff(_in.spot_falloff());
out.SetLightOn(!_in.is_light_off());
out.SetVisualize(_in.visualize_visual());

// todo(ahcorde) Use the field is_light_off in light.proto from
// Garden on.
bool isLightOn = true;
for (int i = 0; i < _in.header().data_size(); ++i)
{
for (int j = 0;
j < _in.header().data(i).value_size(); ++j)
{
if (_in.header().data(i).key() ==
"isLightOn")
{
isLightOn = ignition::math::parseInt(
_in.header().data(i).value(0));
}
}
}
out.SetLightOn(isLightOn);

if (_in.type() == msgs::Light_LightType_POINT)
out.SetType(sdf::LightType::POINT);
else if (_in.type() == msgs::Light_LightType_SPOT)
Expand Down
2 changes: 2 additions & 0 deletions src/Conversions_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@ TEST(Conversions, Light)
light.SetSpotOuterAngle(3.3);
light.SetSpotFalloff(0.9);
light.SetIntensity(1.7);
light.SetLightOn(true);

msgs::Light lightMsg;
lightMsg = convert<msgs::Light>(light);
Expand All @@ -77,6 +78,7 @@ TEST(Conversions, Light)
/// \todo(anyone) add pose frame fields in ign-msgs?
// EXPECT_EQ("world", lightMsg.pose_frame());
EXPECT_TRUE(lightMsg.cast_shadows());
EXPECT_FALSE(lightMsg.is_light_off());
EXPECT_TRUE(lightMsg.visualize_visual());
EXPECT_EQ(math::Color(0.4f, 0.5f, 0.6f, 1),
msgs::Convert(lightMsg.diffuse()));
Expand Down
27 changes: 2 additions & 25 deletions src/gui/plugins/component_inspector/ComponentInspector.cc
Original file line number Diff line number Diff line change
Expand Up @@ -141,21 +141,6 @@ void ignition::gazebo::setData(QStandardItem *_item, const msgs::Light &_data)
lightType = 2;
}

bool isLightOn = true;
for (int i = 0; i < _data.header().data_size(); ++i)
{
for (int j = 0;
j < _data.header().data(i).value_size(); ++j)
{
if (_data.header().data(i).key() ==
"isLightOn")
{
isLightOn = ignition::math::parseInt(
_data.header().data(i).value(0));
}
}
}

_item->setData(QString("Light"),
ComponentsModel::RoleNames().key("dataType"));
_item->setData(QList({
Expand All @@ -180,7 +165,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const msgs::Light &_data)
QVariant(_data.spot_falloff()),
QVariant(_data.intensity()),
QVariant(lightType),
QVariant(isLightOn),
QVariant(!_data.is_light_off()),
QVariant(_data.visualize_visual())
}), ComponentsModel::RoleNames().key("data"));
}
Expand Down Expand Up @@ -1015,15 +1000,6 @@ void ComponentInspector::OnLight(
};

ignition::msgs::Light req;
{
// todo(ahcorde) Use the field is_light_off in light.proto from
// Garden on.
auto header = req.mutable_header()->add_data();
header->set_key("isLightOn");
std::string *value = header->add_value();
*value = std::to_string(_isLightOn);
}

req.set_name(this->dataPtr->entityName);
req.set_id(this->dataPtr->entity);
ignition::msgs::Set(req.mutable_diffuse(),
Expand All @@ -1036,6 +1012,7 @@ void ComponentInspector::OnLight(
req.set_attenuation_quadratic(_attQuadratic);
req.set_cast_shadows(_castShadows);
req.set_intensity(_intensity);
req.set_is_light_off(!_isLightOn);
req.set_visualize_visual(_visualizeVisual);
if (_type == 0)
req.set_type(ignition::msgs::Light::POINT);
Expand Down
19 changes: 1 addition & 18 deletions src/rendering/RenderUtil.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2861,24 +2861,7 @@ void RenderUtilPrivate::UpdateLights(
if (lightVisual)
lightVisual->SetVisible(light.second.visualize_visual());

// todo(ahcorde) Use the field is_light_off in light.proto from
// Garden on.
bool isLightOn = true;
for (int i = 0; i < light.second.header().data_size(); ++i)
{
for (int j = 0;
j < light.second.header().data(i).value_size(); ++j)
{
if (light.second.header().data(i).key() ==
"isLightOn")
{
isLightOn = ignition::math::parseInt(
light.second.header().data(i).value(0));
}
}
}

if (isLightOn)
if (!light.second.is_light_off())
{
if (!ignition::math::equal(
l->Intensity(),
Expand Down
22 changes: 1 addition & 21 deletions src/systems/user_commands/UserCommands.cc
Original file line number Diff line number Diff line change
Expand Up @@ -227,28 +227,8 @@ class LightCommand : public UserCommandBase
public: std::function<bool(const msgs::Light &, const msgs::Light &)>
lightEql { [](const msgs::Light &_a, const msgs::Light &_b)
{
// todo(ahcorde) Use the field is_light_off in light.proto from
// Garden on.
auto getIsLightOn = [](const msgs::Light &_light) -> bool
{
bool isLightOn = true;
for (int i = 0; i < _light.header().data_size(); ++i)
{
for (int j = 0;
j < _light.header().data(i).value_size(); ++j)
{
if (_light.header().data(i).key() ==
"isLightOn")
{
isLightOn = ignition::math::parseInt(
_light.header().data(i).value(0));
}
}
}
return isLightOn;
};
return
getIsLightOn(_a) == getIsLightOn(_b) &&
_a.is_light_off() == _b.is_light_off() &&
_a.visualize_visual() == _b.visualize_visual() &&
_a.type() == _b.type() &&
_a.name() == _b.name() &&
Expand Down
15 changes: 8 additions & 7 deletions test/integration/user_commands.cc
Original file line number Diff line number Diff line change
Expand Up @@ -822,6 +822,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Light))
EXPECT_NEAR(0.2, pointLightComp->Data().ConstantAttenuationFactor(), 0.1);
EXPECT_NEAR(0.01, pointLightComp->Data().QuadraticAttenuationFactor(), 0.1);
EXPECT_FALSE(pointLightComp->Data().CastShadows());
EXPECT_TRUE(pointLightComp->Data().LightOn());
EXPECT_TRUE(pointLightComp->Data().Visualize());

req.Clear();
Expand All @@ -836,15 +837,9 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Light))
req.set_attenuation_constant(0.6f);
req.set_attenuation_quadratic(0.001f);
req.set_cast_shadows(true);
req.set_is_light_off(false);
req.set_visualize_visual(false);

// todo(ahcorde) Use the field is_light_off in light.proto from
// Garden on.
auto header = req.mutable_header()->add_data();
header->set_key("isLightOn");
std::string *value = header->add_value();
*value = std::to_string(true);

EXPECT_TRUE(node.Request(service, req, timeout, res, result));
EXPECT_TRUE(result);
EXPECT_TRUE(res.data());
Expand All @@ -866,6 +861,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Light))
EXPECT_NEAR(0.6, pointLightComp->Data().ConstantAttenuationFactor(), 0.1);
EXPECT_NEAR(0.001, pointLightComp->Data().QuadraticAttenuationFactor(), 0.1);
EXPECT_TRUE(pointLightComp->Data().CastShadows());
EXPECT_TRUE(pointLightComp->Data().LightOn());
EXPECT_FALSE(pointLightComp->Data().Visualize());
EXPECT_EQ(sdf::LightType::POINT, pointLightComp->Data().Type());

Expand Down Expand Up @@ -894,6 +890,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Light))
EXPECT_EQ(
math::Vector3d(0.5, 0.2, -0.9), directionalLightComp->Data().Direction());
EXPECT_TRUE(directionalLightComp->Data().CastShadows());
EXPECT_TRUE(directionalLightComp->Data().LightOn());
EXPECT_TRUE(directionalLightComp->Data().Visualize());
EXPECT_EQ(sdf::LightType::POINT, pointLightComp->Data().Type());

Expand All @@ -909,6 +906,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Light))
req.set_attenuation_constant(0.6f);
req.set_attenuation_quadratic(1.0f);
req.set_cast_shadows(false);
req.set_is_light_off(false);
req.set_visualize_visual(false);
ignition::msgs::Set(req.mutable_direction(),
ignition::math::Vector3d(1, 2, 3));
Expand Down Expand Up @@ -938,6 +936,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Light))
1, directionalLightComp->Data().QuadraticAttenuationFactor(), 0.1);
EXPECT_EQ(math::Vector3d(1, 2, 3), directionalLightComp->Data().Direction());
EXPECT_FALSE(directionalLightComp->Data().CastShadows());
EXPECT_TRUE(directionalLightComp->Data().LightOn());
EXPECT_FALSE(directionalLightComp->Data().Visualize());
EXPECT_EQ(sdf::LightType::DIRECTIONAL,
directionalLightComp->Data().Type());
Expand Down Expand Up @@ -982,6 +981,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Light))
req.set_attenuation_constant(0.6f);
req.set_attenuation_quadratic(1.0f);
req.set_cast_shadows(true);
req.set_is_light_off(true);
req.set_visualize_visual(true);
ignition::msgs::Set(req.mutable_direction(),
ignition::math::Vector3d(1, 2, 3));
Expand Down Expand Up @@ -1011,6 +1011,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Light))
EXPECT_NEAR(1, spotLightComp->Data().QuadraticAttenuationFactor(), 0.1);
EXPECT_EQ(math::Vector3d(1, 2, 3), spotLightComp->Data().Direction());
EXPECT_TRUE(spotLightComp->Data().CastShadows());
EXPECT_FALSE(spotLightComp->Data().LightOn());
EXPECT_TRUE(spotLightComp->Data().Visualize());
EXPECT_EQ(sdf::LightType::SPOT, spotLightComp->Data().Type());
EXPECT_NEAR(1.5, spotLightComp->Data().SpotInnerAngle().Radian(), 0.1);
Expand Down