Light parameter for supporting RenderEngine implementations.
Look at the various RenderEngine___Params types to see if they support declaring lights.
#include <drake/geometry/render/light_parameter.h>
Public Member Functions | |
template<typename Archive > | |
void | Serialize (Archive *a) |
Passes this object to an Archive. More... | |
Public Attributes | |
std::string | type {"directional"} |
The light type is either "point" , "spot" , or "directional" . More... | |
Rgba | color = Rgba(1, 1, 1) |
The illuminating color of the light (with channels in the range [0, 1]). More... | |
Eigen::Vector3d | attenuation_values = {1, 0, 0} |
The quadratic attenuation constants (k₀, k₁, and k₂). More... | |
Eigen::Vector3d | position {0, 0, 0} |
The position of the light in the frame indicated by frame F: p_FL. More... | |
std::string | frame {"camera"} |
Specifies the frame to which the camera is fixed, "world" or "camera" . More... | |
double | intensity {1} |
A multiplier for the brightness of the light. More... | |
Eigen::Vector3d | direction {0, 0, 1} |
The direction the light points in the frame indicated by frame . More... | |
double | cone_angle {0} |
For a spotlight, it is the measure of the angle (in degrees) between the light's central direction vector and the border of the light's conical extent. More... | |
void Serialize | ( | Archive * | a | ) |
Passes this object to an Archive.
Refer to YAML Serialization for background.
Eigen::Vector3d attenuation_values = {1, 0, 0} |
The quadratic attenuation constants (k₀, k₁, and k₂).
The intensity of light can decrease with distance according to the following equation:
I = 1/(k₀ + k₁·d + k₂·d²)
In the physical world, light from a point source decreases with the squared distance (with some linear attenuation due to atmospheric effects). However, this often leads to undesirable illumination effects in low-dynamic range rendering. Suitable values typically will temper the quadratic effects with non-zero constant and linear terms.
If the values sum to 1, then, a surface one meter away from the light will get full illumination (surfaces closer will get magnified illumination. When tuning attenuation to achieve a particular falloff pattern, it is common to increase the light intensity
to offset what would otherwise appear to be a rapid decay. By default, the light is unattenuated, with constant illumination across all distances.
When using directional lights, attenuation is best kept with the default, non attenuated values (<1, 0, 0>). Other attenuation values may be applied, but the effect may be surprising and difficult to control.
The illuminating color of the light (with channels in the range [0, 1]).
The alpha value is currently ignored.
double cone_angle {0} |
For a spotlight, it is the measure of the angle (in degrees) between the light's central direction vector and the border of the light's conical extent.
It is half of the spotlight's full angular span. So, a light with a 45° cone_angle
would cast light over a 90° span.
Eigen::Vector3d direction {0, 0, 1} |
The direction the light points in the frame indicated by frame
.
For example, in the world frame, a spotlight with direction [0, 0, -1]ᵀ points straight down. In the camera frame, the direction [0, 0, 1]ᵀ points forward in the camera's view direction. This field only applies to spotlight and directional lights.
std::string frame {"camera"} |
Specifies the frame to which the camera is fixed, "world"
or "camera"
.
Remember, as documented by CameraInfo, the camera frame has +Cz pointing into the image, +Cx pointing to the right, and +Cy pointing to the bottom of the image.
double intensity {1} |
A multiplier for the brightness of the light.
A zero intensity will effectively disable the light. A value of one will have an intensity equal to the light's color. Higher values will magnify the light's illumination (and may be necessary to offset the attenuation effects).
Eigen::Vector3d position {0, 0, 0} |
The position of the light in the frame indicated by frame
F: p_FL.
std::string type {"directional"} |
The light type is either "point"
, "spot"
, or "directional"
.