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

Allow to turn on/off lights #1343

Merged
merged 9 commits into from
Mar 15, 2022
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
27 changes: 27 additions & 0 deletions src/Conversions.cc
Original file line number Diff line number Diff line change
Expand Up @@ -568,6 +568,14 @@ 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(anyone) Use the field isLightOn in light.proto from
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
// 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());

if (_in.Type() == sdf::LightType::POINT)
out.set_type(msgs::Light_LightType_POINT);
else if (_in.Type() == sdf::LightType::SPOT)
Expand Down Expand Up @@ -597,6 +605,25 @@ 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(anyone) Use the field isLightOn 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
29 changes: 27 additions & 2 deletions src/gui/plugins/component_inspector/ComponentInspector.cc
Original file line number Diff line number Diff line change
Expand Up @@ -153,6 +153,21 @@ 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 @@ -176,7 +191,8 @@ void ignition::gazebo::setData(QStandardItem *_item, const msgs::Light &_data)
QVariant(_data.spot_outer_angle()),
QVariant(_data.spot_falloff()),
QVariant(_data.intensity()),
QVariant(lightType)
QVariant(lightType),
QVariant(isLightOn)
}), ComponentsModel::RoleNames().key("data"));
}

Expand Down Expand Up @@ -989,7 +1005,8 @@ void ComponentInspector::OnLight(
double _attRange, double _attLinear, double _attConstant,
double _attQuadratic, bool _castShadows, double _directionX,
double _directionY, double _directionZ, double _innerAngle,
double _outerAngle, double _falloff, double _intensity, int _type)
double _outerAngle, double _falloff, double _intensity, int _type,
bool _isLightOn)
{
std::function<void(const ignition::msgs::Boolean &, const bool)> cb =
[](const ignition::msgs::Boolean &/*_rep*/, const bool _result)
Expand All @@ -999,6 +1016,14 @@ void ComponentInspector::OnLight(
};

ignition::msgs::Light req;

// todo(anyone) Use the field isLightOn in light.proto from
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
// 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 Down
2 changes: 1 addition & 1 deletion src/gui/plugins/component_inspector/ComponentInspector.hh
Original file line number Diff line number Diff line change
Expand Up @@ -259,7 +259,7 @@ namespace gazebo
double _attLinear, double _attConstant, double _attQuadratic,
bool _castShadows, double _directionX, double _directionY,
double _directionZ, double _innerAngle, double _outerAngle,
double _falloff, double _intensity, int _type);
double _falloff, double _intensity, int _type, bool _isLightOn);
chapulina marked this conversation as resolved.
Show resolved Hide resolved

/// \brief Callback in Qt thread when physics' properties change.
/// \param[in] _stepSize step size
Expand Down
6 changes: 4 additions & 2 deletions src/gui/plugins/component_inspector/ComponentInspector.qml
Original file line number Diff line number Diff line change
Expand Up @@ -101,12 +101,14 @@ Rectangle {
_rDiffuse, _gDiffuse, _bDiffuse, _aDiffuse,
_attRange, _attLinear, _attConstant, _attQuadratic,
_castShadows, _directionX, _directionY, _directionZ,
_innerAngle, _outerAngle, _falloff, _intensity, _type) {
_innerAngle, _outerAngle, _falloff, _intensity, _type,
_isLightOn) {
ComponentInspector.OnLight(_rSpecular, _gSpecular, _bSpecular, _aSpecular,
_rDiffuse, _gDiffuse, _bDiffuse, _aDiffuse,
_attRange, _attLinear, _attConstant, _attQuadratic,
_castShadows, _directionX, _directionY, _directionZ,
_innerAngle, _outerAngle, _falloff, _intensity, _type)
_innerAngle, _outerAngle, _falloff, _intensity, _type,
_isLightOn)
}

/*
Expand Down
45 changes: 44 additions & 1 deletion src/gui/plugins/component_inspector/Light.qml
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,9 @@ Rectangle {
// Loaded item for intensity
property var intensityItem: {}

// Loaded item for isLightOn
property var isLightOnItem: {}

// Send new light data to C++
function sendLight() {
// TODO(anyone) There's a loss of precision when these values get to C++
Expand All @@ -123,7 +126,8 @@ Rectangle {
outerAngleItem.value,
falloffItem.value,
intensityItem.value,
model.data[20]
model.data[20],
isLightOnItem.checked
);
}

Expand Down Expand Up @@ -285,6 +289,45 @@ Rectangle {
id: grid
width: parent.width

RowLayout {
Rectangle {
color: "transparent"
height: 40
Layout.preferredWidth: isOnText.width + indentation*3
Loader {
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
id: isLightOn
width: iconWidth
height: iconHeight
y:10
sourceComponent: plotIcon
}
Component.onCompleted: isLightOn.item.componentInfo = "is light on ?"

Text {
id : isOnText
text: ' Turn on/off'
leftPadding: 5
color: Material.theme == Material.Light ? "#444444" : "#bbbbbb"
font.pointSize: 12
anchors.centerIn: parent
}
}
Item {
Layout.fillWidth: true
height: 40

Loader {
id: inOnLoader
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
anchors.fill: parent
property double numberValue: model.data[21]
sourceComponent: ignSwitch
onLoaded: {
isLightOnItem = inOnLoader.item
}
}
}
}

RowLayout {
Rectangle {
color: "transparent"
Expand Down
34 changes: 30 additions & 4 deletions src/rendering/RenderUtil.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2131,11 +2131,37 @@ void RenderUtilPrivate::UpdateLights(
auto l = std::dynamic_pointer_cast<rendering::Light>(node);
if (l)
{
if (!ignition::math::equal(
l->Intensity(),
static_cast<double>(light.second.intensity())))
// todo(anyone) Use the field isLightOn in light.proto from
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
// 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));
}
}
}

// const auto lightOnOff = _entityLightsOn.at(light.first);
ahcorde marked this conversation as resolved.
Show resolved Hide resolved

if (isLightOn)
{
if (!ignition::math::equal(
l->Intensity(),
static_cast<double>(light.second.intensity())))
{
l->SetIntensity(light.second.intensity());
}
}
else
{
l->SetIntensity(light.second.intensity());
l->SetIntensity(0);
}
if (light.second.has_diffuse())
{
Expand Down
21 changes: 21 additions & 0 deletions src/systems/user_commands/UserCommands.cc
Original file line number Diff line number Diff line change
Expand Up @@ -159,7 +159,28 @@ class LightCommand : public UserCommandBase
public: std::function<bool(const msgs::Light &, const msgs::Light &)>
lightEql { [](const msgs::Light &_a, const msgs::Light &_b)
{
// todo(anyone) Use the field isLightOn 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.type() == _b.type() &&
_a.name() == _b.name() &&
math::equal(
Expand Down