diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 1b30ab5a33..c79e392551 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -119,6 +119,9 @@ class UserCommandsInterface /// \return True if a contact sensor is connected to the collision entity, /// false otherwise public: bool HasContactSensor(const Entity _collision); + + /// \brief Bool to set all matching light entities. + public: bool setAllLightEntities = false; }; /// \brief All user commands should inherit from this class so they can be @@ -610,7 +613,7 @@ bool UserCommandsInterface::HasContactSensor(const Entity _collision) ////////////////////////////////////////////////// void UserCommands::Configure(const Entity &_entity, - const std::shared_ptr &, + const std::shared_ptr &_sdf, EntityComponentManager &_ecm, EventManager &_eventManager) { @@ -680,6 +683,15 @@ void UserCommands::Configure(const Entity &_entity, this->dataPtr->node.Subscribe(lightTopic, &UserCommandsPrivate::OnCmdLight, this->dataPtr.get()); + if (_sdf->HasElement("set_all_light_entities")) + { + this->dataPtr->iface->setAllLightEntities = + _sdf->Get("set_all_light_entities"); + gzdbg << "Set all light entities: " + << this->dataPtr->iface->setAllLightEntities + << std::endl; + } + std::string materialColorTopic{ "/world/" + validWorldName + "/material_color"}; this->dataPtr->node.Subscribe(materialColorTopic, @@ -859,7 +871,6 @@ void UserCommandsPrivate::OnCmdLight(const msgs::Light &_msg) } } - ////////////////////////////////////////////////// bool UserCommandsPrivate::PoseService(const msgs::Pose &_req, msgs::Boolean &_res) @@ -1362,79 +1373,142 @@ LightCommand::LightCommand(msgs::Light *_msg, ////////////////////////////////////////////////// bool LightCommand::Execute() { - auto lightMsg = dynamic_cast(this->msg); + auto lightMsg = dynamic_cast(this->msg); if (nullptr == lightMsg) { gzerr << "Internal error, null light message" << std::endl; return false; } + Entity lightEntity = kNullEntity; + if (this->iface->setAllLightEntities) + { + auto entities = entitiesFromScopedName(lightMsg->name(), + *this->iface->ecm); + if (entities.empty()) + { + gzwarn << "Entity name: " << lightMsg->name() << ", is not found." + << std::endl; + return false; + } + for (const Entity &id : entities) + { + lightEntity = kNullEntity; + lightMsg->set_id(id); + if (lightMsg->id() != kNullEntity) + { + lightEntity = lightMsg->id(); + } + if (!lightEntity) + { + gzmsg << "Failed to find light entity named [" << lightMsg->name() + << "]." << std::endl; + return false; + } - Entity lightEntity{kNullEntity}; + auto lightPose = + this->iface->ecm->Component(lightEntity); + if (nullptr == lightPose) + { + lightEntity = kNullEntity; + } - if (lightMsg->id() != kNullEntity) - { - lightEntity = lightMsg->id(); + if (!lightEntity) + { + gzmsg << "Pose component not available" << std::endl; + return false; + } + + if (lightMsg->has_pose()) + { + lightPose->Data().Pos() = msgs::Convert(lightMsg->pose()).Pos(); + } + + auto lightCmdComp = + this->iface->ecm->Component(lightEntity); + if (!lightCmdComp) + { + this->iface->ecm->CreateComponent( + lightEntity, components::LightCmd(*lightMsg)); + } + else + { + auto state = lightCmdComp->SetData(*lightMsg, this->lightEql) ? + ComponentState::OneTimeChange : + ComponentState::NoChange; + this->iface->ecm->SetChanged(lightEntity, components::LightCmd::typeId, + state); + } + } } - else if (!lightMsg->name().empty()) + else { - if (lightMsg->parent_id() != kNullEntity) + lightEntity = kNullEntity; + if (lightMsg->id() != kNullEntity) { - lightEntity = this->iface->ecm->EntityByComponents( - components::Name(lightMsg->name()), - components::ParentEntity(lightMsg->parent_id())); + lightEntity = lightMsg->id(); } - else + else if (!lightMsg->name().empty()) { - lightEntity = this->iface->ecm->EntityByComponents( - components::Name(lightMsg->name())); + if (lightMsg->parent_id() != kNullEntity) + { + lightEntity = this->iface->ecm->EntityByComponents( + components::Name(lightMsg->name()), + components::ParentEntity(lightMsg->parent_id())); + } + else + { + lightEntity = this->iface->ecm->EntityByComponents( + components::Name(lightMsg->name())); + } + } + if (kNullEntity == lightEntity) + { + gzerr << "Failed to find light with name [" << lightMsg->name() + << "], ID [" << lightMsg->id() << "] and parent ID [" + << lightMsg->parent_id() << "]." << std::endl; + return false; } - } - if (kNullEntity == lightEntity) - { - gzerr << "Failed to find light with name [" << lightMsg->name() - << "], ID [" << lightMsg->id() << "] and parent ID [" - << lightMsg->parent_id() << "]." << std::endl; - return false; - } - if (!lightEntity) - { - gzmsg << "Failed to find light entity named [" << lightMsg->name() - << "]." << std::endl; - return false; - } + if (!lightEntity) + { + gzmsg << "Failed to find light entity named [" << lightMsg->name() + << "]." << std::endl; + return false; + } - auto lightPose = this->iface->ecm->Component(lightEntity); - if (nullptr == lightPose) - lightEntity = kNullEntity; + auto lightPose = this->iface->ecm->Component(lightEntity); + if (nullptr == lightPose) + { + lightEntity = kNullEntity; + } - if (!lightEntity) - { - gzmsg << "Pose component not available" << std::endl; - return false; - } + if (!lightEntity) + { + gzmsg << "Pose component not available" << std::endl; + return false; + } - if (lightMsg->has_pose()) - { - lightPose->Data().Pos() = msgs::Convert(lightMsg->pose()).Pos(); - } + if (lightMsg->has_pose()) + { + lightPose->Data().Pos() = msgs::Convert(lightMsg->pose()).Pos(); + } - auto lightCmdComp = - this->iface->ecm->Component(lightEntity); - if (!lightCmdComp) - { - this->iface->ecm->CreateComponent( - lightEntity, components::LightCmd(*lightMsg)); - } - else - { - auto state = lightCmdComp->SetData(*lightMsg, this->lightEql) ? - ComponentState::OneTimeChange : - ComponentState::NoChange; - this->iface->ecm->SetChanged(lightEntity, components::LightCmd::typeId, - state); + auto lightCmdComp = + this->iface->ecm->Component(lightEntity); + if (!lightCmdComp) + { + this->iface->ecm->CreateComponent( + lightEntity, components::LightCmd(*lightMsg)); + } + else + { + auto state = lightCmdComp->SetData(*lightMsg, this->lightEql) ? + ComponentState::OneTimeChange : + ComponentState::NoChange; + this->iface->ecm->SetChanged(lightEntity, components::LightCmd::typeId, + state); + } } - return true; } diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index 281c6dbf9c..f506ff0971 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -15,6 +15,8 @@ * */ +#include + #include #include @@ -1031,11 +1033,12 @@ TEST_F(UserCommandsTest, GZ_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Light)) const std::string lightTopic = "/world/lights_command/light_config"; msgs::Light lightMsg; - lightMsg.set_name("spot"); gz::msgs::Set(lightMsg.mutable_diffuse(), gz::math::Color(1.0f, 1.0f, 1.0f, 1.0f)); + gz::msgs::Set(lightMsg.mutable_pose()->mutable_position(), + gz::math::Vector3d(1.0f, 0.0f, 0.0f)); - // Publish light config + // Publish light config without name auto pub = node.Advertise(lightTopic); pub.Publish(lightMsg); @@ -1043,10 +1046,337 @@ TEST_F(UserCommandsTest, GZ_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Light)) // Sleep for a small duration to allow Run thread to start GZ_SLEEP_MS(10); + // add name + lightMsg.set_name("spot"); + + // Publish light config + pub.Publish(lightMsg); + + server.Run(true, 100, false); + // Sleep for a small duration to allow Run thread to start + GZ_SLEEP_MS(10); + EXPECT_EQ(math::Color(1.0f, 1.0f, 1.0f, 1.0f), spotLightComp->Data().Diffuse()); } +///////////////////////////////////////////////// +TEST_F(UserCommandsTest, GZ_UTILS_TEST_ENABLED_ONLY_ON_LINUX(LightAll)) +{ + // Start server + ServerConfig serverConfig; + const auto sdfFile = gz::common::joinPaths( + std::string(PROJECT_SOURCE_PATH), "test", "worlds", + "lights_render_all.sdf"); + serverConfig.SetSdfFile(sdfFile); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + + // Create a system just to get the ECM + EntityComponentManager *ecm{nullptr}; + test::Relay testSystem; + testSystem.OnPreUpdate([&](const sim::UpdateInfo &, + sim::EntityComponentManager &_ecm) + { + ecm = &_ecm; + }); + + server.AddSystem(testSystem.systemPtr); + + // Run server and check we have the ECM + EXPECT_EQ(nullptr, ecm); + server.Run(true, 1, false); + EXPECT_NE(nullptr, ecm); + + msgs::Light req; + msgs::Boolean res; + transport::Node node; + bool result; + unsigned int timeout = 1000; + std::string service{"/world/lights_command/light_config"}; + + // Point light + auto pointLightEntity = ecm->EntityByComponents(components::Name("point")); + EXPECT_NE(kNullEntity, pointLightEntity); + + // Check point light entity has not been edited yet - Initial values + auto pointLightComp = ecm->Component(pointLightEntity); + ASSERT_NE(nullptr, pointLightComp); + EXPECT_EQ( + math::Pose3d(0, -1.5, 3, 0, 0, 0), pointLightComp->Data().RawPose()); + EXPECT_EQ(math::Color(1.0f, 0.0f, 0.0f, 1.0f), + pointLightComp->Data().Diffuse()); + EXPECT_EQ(math::Color(0.1f, 0.1f, 0.1f, 1.0f), + pointLightComp->Data().Specular()); + EXPECT_NEAR(4.0, pointLightComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR(0.5, pointLightComp->Data().LinearAttenuationFactor(), 0.1); + 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(); + gz::msgs::Set(req.mutable_diffuse(), + gz::math::Color(0.0f, 1.0f, 1.0f, 0.0f)); + gz::msgs::Set(req.mutable_specular(), + gz::math::Color(0.2f, 0.2f, 0.2f, 0.2f)); + req.set_range(2.6f); + req.set_name("point"); + req.set_type(gz::msgs::Light::POINT); + req.set_attenuation_linear(0.7f); + 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); + + EXPECT_TRUE(node.Request(service, req, timeout, res, result)); + EXPECT_TRUE(result); + EXPECT_TRUE(res.data()); + + server.Run(true, 100, false); + // Sleep for a small duration to allow Run thread to start + GZ_SLEEP_MS(10); + + // Check point light entity has been edited using the service + pointLightComp = ecm->Component(pointLightEntity); + ASSERT_NE(nullptr, pointLightComp); + + EXPECT_EQ(math::Color(0.0f, 1.0f, 1.0f, 0.0f), + pointLightComp->Data().Diffuse()); + EXPECT_EQ(math::Color(0.2f, 0.2f, 0.2f, 0.2f), + pointLightComp->Data().Specular()); + EXPECT_NEAR(2.6, pointLightComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR(0.7, pointLightComp->Data().LinearAttenuationFactor(), 0.1); + 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()); + + // Check directional light entity has not been edited yet - Initial values + auto directionalLightEntity = ecm->EntityByComponents( + components::Name("directional")); + EXPECT_NE(kNullEntity, directionalLightEntity); + + auto directionalLightComp = + ecm->Component(directionalLightEntity); + ASSERT_NE(nullptr, directionalLightComp); + + EXPECT_EQ( + math::Pose3d(0, 0, 10, 0, 0, 0), directionalLightComp->Data().RawPose()); + EXPECT_EQ(math::Color(0.8f, 0.8f, 0.8f, 1.0f), + directionalLightComp->Data().Diffuse()); + EXPECT_EQ(math::Color(0.2f, 0.2f, 0.2f, 1.0f), + directionalLightComp->Data().Specular()); + EXPECT_NEAR(100, directionalLightComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR( + 0.01, directionalLightComp->Data().LinearAttenuationFactor(), 0.01); + EXPECT_NEAR( + 0.9, directionalLightComp->Data().ConstantAttenuationFactor(), 0.1); + EXPECT_NEAR( + 0.001, directionalLightComp->Data().QuadraticAttenuationFactor(), 0.001); + 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()); + + req.Clear(); + gz::msgs::Set(req.mutable_diffuse(), + gz::math::Color(0.0f, 1.0f, 1.0f, 0.0f)); + gz::msgs::Set(req.mutable_specular(), + gz::math::Color(0.3f, 0.3f, 0.3f, 0.3f)); + req.set_range(2.6f); + req.set_name("directional"); + req.set_type(gz::msgs::Light::DIRECTIONAL); + req.set_attenuation_linear(0.7f); + 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); + gz::msgs::Set(req.mutable_direction(), + gz::math::Vector3d(1, 2, 3)); + EXPECT_TRUE(node.Request(service, req, timeout, res, result)); + EXPECT_TRUE(result); + EXPECT_TRUE(res.data()); + + server.Run(true, 100, false); + // Sleep for a small duration to allow Run thread to start + GZ_SLEEP_MS(10); + + // Check directional light entity has been edited using the service + directionalLightComp = + ecm->Component(directionalLightEntity); + ASSERT_NE(nullptr, directionalLightComp); + + EXPECT_EQ(math::Color(0.0f, 1.0f, 1.0f, 0.0f), + directionalLightComp->Data().Diffuse()); + EXPECT_EQ(math::Color(0.3f, 0.3f, 0.3f, 0.3f), + directionalLightComp->Data().Specular()); + EXPECT_NEAR(2.6, directionalLightComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR( + 0.7, directionalLightComp->Data().LinearAttenuationFactor(), 0.1); + EXPECT_NEAR( + 0.6, directionalLightComp->Data().ConstantAttenuationFactor(), 0.1); + EXPECT_NEAR( + 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()); + + // spot light + auto spotLightEntity = ecm->EntityByComponents( + components::Name("spot")); + EXPECT_NE(kNullEntity, spotLightEntity); + + // Check spot light entity has not been edited yet - Initial values + auto spotLightComp = + ecm->Component(spotLightEntity); + ASSERT_NE(nullptr, spotLightComp); + + EXPECT_EQ(math::Pose3d(0, 1.5, 3, 0, 0, 0), spotLightComp->Data().RawPose()); + EXPECT_EQ(math::Color(0.0f, 1.0f, 0.0f, 1.0f), + spotLightComp->Data().Diffuse()); + EXPECT_EQ(math::Color(0.2f, 0.2f, 0.2f, 1.0f), + spotLightComp->Data().Specular()); + EXPECT_NEAR(5, spotLightComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR(0.4, spotLightComp->Data().LinearAttenuationFactor(), 0.01); + EXPECT_NEAR(0.3, spotLightComp->Data().ConstantAttenuationFactor(), 0.1); + EXPECT_NEAR( + 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); + EXPECT_NEAR(0.8, spotLightComp->Data().SpotFalloff(), 0.1); + + req.Clear(); + gz::msgs::Set(req.mutable_diffuse(), + gz::math::Color(1.0f, 0.0f, 1.0f, 0.0f)); + gz::msgs::Set(req.mutable_specular(), + gz::math::Color(0.3f, 0.3f, 0.3f, 0.3f)); + req.set_range(2.6f); + req.set_name("spot"); + req.set_type(gz::msgs::Light::SPOT); + req.set_attenuation_linear(0.7f); + 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); + gz::msgs::Set(req.mutable_direction(), + gz::math::Vector3d(1, 2, 3)); + req.set_spot_inner_angle(1.5f); + req.set_spot_outer_angle(0.3f); + req.set_spot_falloff(0.9f); + + EXPECT_TRUE(node.Request(service, req, timeout, res, result)); + EXPECT_TRUE(result); + EXPECT_TRUE(res.data()); + + server.Run(true, 100, false); + // Sleep for a small duration to allow Run thread to start + GZ_SLEEP_MS(10); + + // Check spot light entity has been edited using the service + spotLightComp = ecm->Component(spotLightEntity); + ASSERT_NE(nullptr, spotLightComp); + + EXPECT_EQ(math::Color(1.0f, 0.0f, 1.0f, 0.0f), + spotLightComp->Data().Diffuse()); + EXPECT_EQ(math::Color(0.3f, 0.3f, 0.3f, 0.3f), + spotLightComp->Data().Specular()); + EXPECT_NEAR(2.6, spotLightComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR(0.7, spotLightComp->Data().LinearAttenuationFactor(), 0.1); + EXPECT_NEAR(0.6, spotLightComp->Data().ConstantAttenuationFactor(), 0.1); + 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); + EXPECT_NEAR(0.3, spotLightComp->Data().SpotOuterAngle().Radian(), 0.1); + EXPECT_NEAR(0.9, spotLightComp->Data().SpotFalloff(), 0.1); + + // sphere + auto sphereLightEntity = + ecm->EntityByComponents(components::Name("sphere_light")); + ASSERT_NE(kNullEntity, sphereLightEntity); + + // check sphere light initial values + auto sphereLightComp = + ecm->Component(sphereLightEntity); + ASSERT_NE(nullptr, sphereLightComp); + EXPECT_EQ(math::Color(1.0f, 1.0f, 1.0f, 1.0f), + sphereLightComp->Data().Diffuse()); + + // Test light_config topic + const std::string lightTopic = "/world/lights_command/light_config"; + + msgs::Light lightMsg; + gz::msgs::Set(lightMsg.mutable_diffuse(), + gz::math::Color(1.0f, 0.0f, 0.0f, 1.0f)); + gz::msgs::Set(lightMsg.mutable_pose()->mutable_position(), + gz::math::Vector3d(1.0f, 0.0f, 0.0f)); + + // Publish light config without name + auto pub = node.Advertise(lightTopic); + pub.Publish(lightMsg); + + server.Run(true, 100, false); + // Sleep for a small duration to allow Run thread to start + GZ_SLEEP_MS(10); + + // add name + lightMsg.set_name("sphere_light"); + + // Publish light config + pub.Publish(lightMsg); + + server.Run(true, 100, false); + // Sleep for a small duration to allow Run thread to start + GZ_SLEEP_MS(10); + + Entity sphereEntity0 = + ecm->EntityByComponents(components::Name("sphere_0")); + Entity sphereEntity1 = + ecm->EntityByComponents(components::Name("sphere_1")); + auto sphereLinkEntity0 = + ecm->ChildrenByComponents(sphereEntity0, + components::Name("sphere_link_0"))[0]; + auto sphereLinkEntity1 = + ecm->ChildrenByComponents(sphereEntity1, + components::Name("sphere_link_1"))[0]; + auto sphereLightEntity0 = + ecm->ChildrenByComponents(sphereLinkEntity0, + components::Name("sphere_light"))[0]; + auto sphereLightEntity1 = + ecm->ChildrenByComponents(sphereLinkEntity1, + components::Name("sphere_light"))[0]; + auto updatedLight0 = + ecm->Component(sphereLightEntity0); + auto updatedLight1 = + ecm->Component(sphereLightEntity1); + + EXPECT_EQ(math::Color(1.0f, 0.0f, 0.0f, 1.0f), + updatedLight0->Data().Diffuse()); + EXPECT_EQ(math::Color(1.0f, 0.0f, 0.0f, 1.0f), + updatedLight1->Data().Diffuse()); +} + ///////////////////////////////////////////////// TEST_F(UserCommandsTest, GZ_UTILS_TEST_ENABLED_ONLY_ON_LINUX(MaterialColor)) { diff --git a/test/worlds/lights_render_all.sdf b/test/worlds/lights_render_all.sdf new file mode 100644 index 0000000000..e2a9bea226 --- /dev/null +++ b/test/worlds/lights_render_all.sdf @@ -0,0 +1,149 @@ + + + + + 0.001 + 0 + + + + + true + + + ogre2 + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 100 + 0.9 + 0.01 + 0.001 + + 0.5 0.2 -0.9 + + + + 0 -1.5 3 0 0 0 + 1 0 0 1 + .1 .1 .1 1 + + 4 + 0.2 + 0.5 + 0.01 + + false + + + + 0 1.5 3 0 0 0 + 0 1 0 1 + .2 .2 .2 1 + + 5 + 0.3 + 0.4 + 0.001 + + 0 0 -1 + + 0.1 + 0.5 + 0.8 + + false + + + + 0 0.0 0.0 0 0 0 + + + + 1 0 1.3 0 0 0 + + 1.047 + + 320 + 240 + + + 0.1 + 100 + + + 1 + 30 + false + camera + + + + + 0.5 + + + + 0.3 0.3 0.3 1 + 0.3 0.3 0.3 1 + 0.3 0.3 0.3 1 + + + + 0 0 1.0 0 0 0 + false + 1 + 1.0 1.0 1.0 1.0 + 1.0 1.0 1.0 1.0 + 0 0 -1 + 1.0 + + 2.1 + 2.1 + + + + + + 0.5 1.0 0.0 0 0 0 + + + + + 0.5 + + + + 0.3 0.3 0.3 1 + 0.3 0.3 0.3 1 + 0.3 0.3 0.3 1 + + + + 0 0 1.0 0 0 0 + false + 1 + 1.0 1.0 1.0 1.0 + 1.0 1.0 1.0 1.0 + 0 0 -1 + 1.0 + + 2.1 + 2.1 + + + + + +