From dceb67dcf3bd378685c31600284fee576f3591a7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= <ahcorde@gmail.com> Date: Thu, 21 Apr 2022 00:14:23 +0200 Subject: [PATCH] Use message field visualize_visual (#1453) Signed-off-by: ahcorde <ahcorde@gmail.com> --- src/Conversions.cc | 29 ++----------------- src/Conversions_TEST.cc | 3 ++ .../component_inspector/ComponentInspector.cc | 26 ++--------------- src/rendering/RenderUtil.cc | 19 +----------- src/systems/user_commands/UserCommands.cc | 23 +-------------- test/integration/user_commands.cc | 9 ++++++ 6 files changed, 18 insertions(+), 91 deletions(-) diff --git a/src/Conversions.cc b/src/Conversions.cc index 549c1e527f..057a834911 100644 --- a/src/Conversions.cc +++ b/src/Conversions.cc @@ -579,15 +579,7 @@ msgs::Light ignition::gazebo::convert(const sdf::Light &_in) std::string *value = header->add_value(); *value = std::to_string(_in.LightOn()); } - - { - // todo(ahcorde) Use the field visualize_visual in light.proto from - // Garden on. - auto header = out.mutable_header()->add_data(); - header->set_key("visualizeVisual"); - std::string *value = header->add_value(); - *value = std::to_string(_in.Visualize()); - } + out.set_visualize_visual(_in.Visualize()); if (_in.Type() == sdf::LightType::POINT) out.set_type(msgs::Light_LightType_POINT); @@ -618,24 +610,7 @@ 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()); - - // todo(ahcorde) Use the field is_light_off in light.proto from - // Garden on. - bool visualizeVisual = 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() == - "visualizeVisual") - { - visualizeVisual = ignition::math::parseInt( - _in.header().data(i).value(0)); - } - } - } - out.SetVisualize(visualizeVisual); + out.SetVisualize(_in.visualize_visual()); // todo(ahcorde) Use the field is_light_off in light.proto from // Garden on. diff --git a/src/Conversions_TEST.cc b/src/Conversions_TEST.cc index bfc7f691cf..1756122440 100644 --- a/src/Conversions_TEST.cc +++ b/src/Conversions_TEST.cc @@ -55,6 +55,7 @@ TEST(Conversions, Light) light.SetRawPose({3, 2, 1, 0, IGN_PI, 0}); light.SetPoseRelativeTo("world"); light.SetCastShadows(true); + light.SetVisualize(true); light.SetDiffuse(ignition::math::Color(0.4f, 0.5f, 0.6f, 1.0)); light.SetSpecular(ignition::math::Color(0.8f, 0.9f, 0.1f, 1.0)); light.SetAttenuationRange(3.2); @@ -76,6 +77,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_TRUE(lightMsg.visualize_visual()); EXPECT_EQ(math::Color(0.4f, 0.5f, 0.6f, 1), msgs::Convert(lightMsg.diffuse())); EXPECT_EQ(math::Color(0.8f, 0.9f, 0.1f, 1), @@ -97,6 +99,7 @@ TEST(Conversions, Light) /// \todo(anyone) add pose frame fields in ign-msgs? // EXPECT_EQ("world", newLight.PoseRelativeTo()); EXPECT_TRUE(newLight.CastShadows()); + EXPECT_TRUE(newLight.Visualize()); EXPECT_EQ(math::Color(0.4f, 0.5f, 0.6f, 1.0f), newLight.Diffuse()); EXPECT_EQ(math::Color(0.8f, 0.9f, 0.1f, 1.0f), newLight.Specular()); EXPECT_FLOAT_EQ(3.2f, newLight.AttenuationRange()); diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index 5bf8124493..c58d4c15d9 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -141,21 +141,6 @@ void ignition::gazebo::setData(QStandardItem *_item, const msgs::Light &_data) lightType = 2; } - bool visualizeVisual = 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() == - "visualizeVisual") - { - visualizeVisual = ignition::math::parseInt( - _data.header().data(i).value(0)); - } - } - } - bool isLightOn = true; for (int i = 0; i < _data.header().data_size(); ++i) { @@ -196,7 +181,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const msgs::Light &_data) QVariant(_data.intensity()), QVariant(lightType), QVariant(isLightOn), - QVariant(visualizeVisual) + QVariant(_data.visualize_visual()) }), ComponentsModel::RoleNames().key("data")); } @@ -1038,14 +1023,6 @@ void ComponentInspector::OnLight( std::string *value = header->add_value(); *value = std::to_string(_isLightOn); } - { - // todo(ahcorde) Use the field visualize_visual in light.proto from - // Garden on. - auto header = req.mutable_header()->add_data(); - header->set_key("visualizeVisual"); - std::string *value = header->add_value(); - *value = std::to_string(_visualizeVisual); - } req.set_name(this->dataPtr->entityName); req.set_id(this->dataPtr->entity); @@ -1059,6 +1036,7 @@ void ComponentInspector::OnLight( req.set_attenuation_quadratic(_attQuadratic); req.set_cast_shadows(_castShadows); req.set_intensity(_intensity); + req.set_visualize_visual(_visualizeVisual); if (_type == 0) req.set_type(ignition::msgs::Light::POINT); else if (_type == 1) diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 62522936ad..ee970193ec 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -2855,28 +2855,11 @@ void RenderUtilPrivate::UpdateLights( auto l = std::dynamic_pointer_cast<rendering::Light>(node); if (l) { - // todo(ahcorde) Use the field visualize_visual in light.proto from - // Garden on. - bool visualizeVisual = 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() == - "visualizeVisual") - { - visualizeVisual = ignition::math::parseInt( - light.second.header().data(i).value(0)); - } - } - } - rendering::VisualPtr lightVisual = this->sceneManager.VisualById( this->matchLightWithVisuals[light.first]); if (lightVisual) - lightVisual->SetVisible(visualizeVisual); + lightVisual->SetVisible(light.second.visualize_visual()); // todo(ahcorde) Use the field is_light_off in light.proto from // Garden on. diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 9ac7892eaa..b9c228e61e 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -227,27 +227,6 @@ 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 getVisualizeVisual = [](const msgs::Light &_light) -> bool - { - bool visualizeVisual = 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() == - "visualizeVisual") - { - visualizeVisual = ignition::math::parseInt( - _light.header().data(i).value(0)); - } - } - } - return visualizeVisual; - }; - // todo(ahcorde) Use the field is_light_off in light.proto from // Garden on. auto getIsLightOn = [](const msgs::Light &_light) -> bool @@ -269,8 +248,8 @@ class LightCommand : public UserCommandBase return isLightOn; }; return - getVisualizeVisual(_a) == getVisualizeVisual(_b) && getIsLightOn(_a) == getIsLightOn(_b) && + _a.visualize_visual() == _b.visualize_visual() && _a.type() == _b.type() && _a.name() == _b.name() && math::equal( diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index 8a3992b43c..a6da212fad 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -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().Visualize()); req.Clear(); ignition::msgs::Set(req.mutable_diffuse(), @@ -835,6 +836,7 @@ 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_visualize_visual(false); // todo(ahcorde) Use the field is_light_off in light.proto from // Garden on. @@ -864,6 +866,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_FALSE(pointLightComp->Data().Visualize()); EXPECT_EQ(sdf::LightType::POINT, pointLightComp->Data().Type()); // Check directional light entity has not been edited yet - Initial values @@ -891,6 +894,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().Visualize()); EXPECT_EQ(sdf::LightType::POINT, pointLightComp->Data().Type()); req.Clear(); @@ -905,6 +909,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_visualize_visual(false); ignition::msgs::Set(req.mutable_direction(), ignition::math::Vector3d(1, 2, 3)); EXPECT_TRUE(node.Request(service, req, timeout, res, result)); @@ -933,6 +938,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_FALSE(directionalLightComp->Data().Visualize()); EXPECT_EQ(sdf::LightType::DIRECTIONAL, directionalLightComp->Data().Type()); @@ -958,6 +964,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Light)) 0.001, spotLightComp->Data().QuadraticAttenuationFactor(), 0.001); EXPECT_EQ(math::Vector3d(0, 0, -1), spotLightComp->Data().Direction()); EXPECT_FALSE(spotLightComp->Data().CastShadows()); + EXPECT_TRUE(spotLightComp->Data().Visualize()); EXPECT_EQ(sdf::LightType::SPOT, spotLightComp->Data().Type()); EXPECT_NEAR(0.1, spotLightComp->Data().SpotInnerAngle().Radian(), 0.1); EXPECT_NEAR(0.5, spotLightComp->Data().SpotOuterAngle().Radian(), 0.1); @@ -975,6 +982,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_visualize_visual(true); ignition::msgs::Set(req.mutable_direction(), ignition::math::Vector3d(1, 2, 3)); req.set_spot_inner_angle(1.5f); @@ -1003,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_TRUE(spotLightComp->Data().Visualize()); EXPECT_EQ(sdf::LightType::SPOT, spotLightComp->Data().Type()); EXPECT_NEAR(1.5, spotLightComp->Data().SpotInnerAngle().Radian(), 0.1); EXPECT_NEAR(0.3, spotLightComp->Data().SpotOuterAngle().Radian(), 0.1);