A light entity. More...
#include <Light.hh>
Inherits Entity.
Public Types | |
enum | EntityType { BASE = 0x00000000, ENTITY = 0x00000001, MODEL = 0x00000002, LINK = 0x00000004, COLLISION = 0x00000008, LIGHT = 0x00000010, VISUAL = 0x00000020, JOINT = 0x00000040, BALL_JOINT = 0x00000080, HINGE2_JOINT = 0x00000100, HINGE_JOINT = 0x00000200, SLIDER_JOINT = 0x00000400, SCREW_JOINT = 0x00000800, UNIVERSAL_JOINT = 0x00001000, GEARBOX_JOINT = 0x00002000, FIXED_JOINT = 0x00004000, ACTOR = 0x00008000, SHAPE = 0x00010000, BOX_SHAPE = 0x00020000, CYLINDER_SHAPE = 0x00040000, HEIGHTMAP_SHAPE = 0x00080000, MAP_SHAPE = 0x00100000, MULTIRAY_SHAPE = 0x00200000, RAY_SHAPE = 0x00400000, PLANE_SHAPE = 0x00800000, SPHERE_SHAPE = 0x01000000, MESH_SHAPE = 0x02000000, POLYLINE_SHAPE = 0x04000000, SENSOR_COLLISION = 0x10000000 } |
Unique identifiers for all entity types. More... | |
Public Member Functions | |
Light (BasePtr _parent) | |
Constructor. More... | |
virtual | ~Light () |
Destructor. More... | |
void | AddChild (BasePtr _child) |
Add a child to this entity. More... | |
void | AddType (EntityType _type) |
Add a type specifier. More... | |
virtual ignition::math::AxisAlignedBox | BoundingBox () const |
Return the bounding box for the entity. More... | |
ignition::math::AxisAlignedBox | CollisionBoundingBox () const |
Returns collision bounding box. More... | |
const ignition::math::Pose3d & | DirtyPose () const |
Returns Entity::dirtyPose. More... | |
void | FillMsg (msgs::Light &_msg) |
Fill a light message with this light's parameters. More... | |
virtual void | Fini () |
Finalize the entity. More... | |
BasePtr | GetByName (const std::string &_name) |
Get by name. More... | |
BasePtr | GetChild (unsigned int _i) const |
Get a child by index. More... | |
BasePtr | GetChild (const std::string &_name) |
Get a child by name. More... | |
CollisionPtr | GetChildCollision (const std::string &_name) |
Get a child collision entity, if one exists. More... | |
unsigned int | GetChildCount () const |
Get the number of children. More... | |
LinkPtr | GetChildLink (const std::string &_name) |
Get a child linke entity, if one exists. More... | |
uint32_t | GetId () const |
Return the ID of this entity. More... | |
std::string | GetName () const |
Return the name of the entity. More... | |
void | GetNearestEntityBelow (double &_distBelow, std::string &_entityName) |
Get the distance to the nearest entity below (along the Z-axis) this entity. More... | |
BasePtr | GetParent () const |
Get the parent. More... | |
int | GetParentId () const |
Return the ID of the parent. More... | |
ModelPtr | GetParentModel () |
Get the parent model, if one exists. More... | |
bool | GetSaveable () const |
Get whether the object should be "saved", when the user selects to save the world to xml. More... | |
std::string | GetScopedName (bool _prependWorldName=false) const |
Return the name of this entity with the model scope model1::...::modelN::entityName. More... | |
virtual const sdf::ElementPtr | GetSDF () |
Get the SDF values for the object. More... | |
unsigned int | GetType () const |
Get the full type definition. More... | |
const WorldPtr & | GetWorld () const |
Get the World this object is in. More... | |
bool | HasType (const EntityType &_t) const |
Returns true if this object's type definition has the given type. More... | |
void | Init () override |
Initialize the light. More... | |
ignition::math::Pose3d | InitialRelativePose () const |
Get the initial relative pose. More... | |
bool | IsCanonicalLink () const |
A helper function that checks if this is a canonical body. More... | |
bool | IsSelected () const |
True if the entity is selected by the user. More... | |
bool | IsStatic () const |
Return whether this entity is static. More... | |
void | Load (sdf::ElementPtr _sdf) override |
Load the light. More... | |
void | OnPoseChange () override |
This function is called when the entity's (or one of its parents) pose of the parent has changed. More... | |
bool | operator== (const Base &_ent) const |
Returns true if the entities are the same. More... | |
void | PlaceOnEntity (const std::string &_entityName) |
Move this entity to be ontop of another entity by name. More... | |
void | PlaceOnNearestEntityBelow () |
Move this entity to be ontop of the nearest entity below. More... | |
void | Print (const std::string &_prefix) |
Print this object to screen via gzmsg. More... | |
void | ProcessMsg (const msgs::Light &_msg) |
Update this light's parameters from a message. More... | |
virtual ignition::math::Vector3d | RelativeAngularAccel () const |
Get the angular acceleration of the entity. More... | |
virtual ignition::math::Vector3d | RelativeAngularVel () const |
Get the angular velocity of the entity. More... | |
virtual ignition::math::Vector3d | RelativeLinearAccel () const |
Get the linear acceleration of the entity. More... | |
virtual ignition::math::Vector3d | RelativeLinearVel () const |
Get the linear velocity of the entity. More... | |
ignition::math::Pose3d | RelativePose () const |
Get the pose of the entity relative to its parent. More... | |
virtual void | RemoveChild (unsigned int _id) |
Remove a child from this entity. More... | |
void | RemoveChild (const std::string &_name) |
Remove a child by name. More... | |
void | RemoveChild (physics::BasePtr _child) |
Remove a child by pointer. More... | |
void | RemoveChildren () |
Remove all children. More... | |
virtual void | Reset () |
Reset the entity. More... | |
virtual void | Reset (Base::EntityType _resetType) |
Calls recursive Reset on one of the Base::EntityType's. More... | |
ignition::math::Pose3d | SDFPoseRelativeToParent () const |
Get the SDF pose of the object according to the sdf 1.6 convention. More... | |
std::optional< sdf::SemanticPose > | SDFSemanticPose () const override |
Get the SDF SemanticPose object associated with the pose of this object. More... | |
void | SetAnimation (const common::PoseAnimationPtr &_anim, boost::function< void()> _onComplete) |
Set an animation for this entity. More... | |
void | SetAnimation (common::PoseAnimationPtr _anim) |
Set an animation for this entity. More... | |
void | SetCanonicalLink (bool _value) |
Set to true if this entity is a canonical link for a model. More... | |
void | SetInitialRelativePose (const ignition::math::Pose3d &_pose) |
Set the initial pose. More... | |
virtual void | SetName (const std::string &_name) |
Set the name of the entity. More... | |
void | SetParent (BasePtr _parent) |
Set the parent. More... | |
void | SetRelativePose (const ignition::math::Pose3d &_pose, const bool _notify=true, const bool _publish=true) |
Set the pose of the entity relative to its parent. More... | |
void | SetSaveable (bool _v) |
Set whether the object should be "saved", when the user selects to save the world to xml. More... | |
virtual bool | SetSelected (bool _show) |
Set whether this entity has been selected by the user through the gui. More... | |
void | SetState (const LightState &_state) |
Set the current light state. More... | |
void | SetStatic (const bool &_static) |
Set whether this entity is static: immovable. More... | |
void | SetWorld (const WorldPtr &_newWorld) |
Set the world this object belongs to. More... | |
void | SetWorldPose (const ignition::math::Pose3d &_pose, const bool _notify=true, const bool _publish=true) |
Set the world pose of the entity. More... | |
void | SetWorldPoseDirty () |
Indicate that the world pose should be recalculated. More... | |
void | SetWorldTwist (const ignition::math::Vector3d &_linear, const ignition::math::Vector3d &_angular, const bool _updateChildren=true) |
Set angular and linear rates of an physics::Entity. More... | |
virtual void | StopAnimation () |
Stop the current animation, if any. More... | |
std::string | TypeStr () const |
Get the string name for the entity type. More... | |
virtual void | Update () |
Update the object. More... | |
virtual void | UpdateParameters (sdf::ElementPtr _sdf) |
Update the parameters using new sdf values. More... | |
common::URI | URI () const |
Return the common::URI of this entity. More... | |
virtual ignition::math::Vector3d | WorldAngularAccel () const |
Get the angular acceleration of the entity in the world frame. More... | |
virtual ignition::math::Vector3d | WorldAngularVel () const |
Get the angular velocity of the entity in the world frame. More... | |
virtual ignition::math::Vector3d | WorldLinearAccel () const |
Get the linear acceleration of the entity in the world frame. More... | |
virtual ignition::math::Vector3d | WorldLinearVel () const |
Get the linear velocity of the entity in the world frame. More... | |
virtual const ignition::math::Pose3d & | WorldPose () const override |
Get the absolute pose of the entity. More... | |
Protected Member Functions | |
void | ComputeScopedName () |
Compute the scoped name of this object based on its parents. More... | |
virtual void | RegisterIntrospectionItems () |
Register items in the introspection service. More... | |
virtual void | UnregisterIntrospectionItems () |
Unregister items in the introspection service. More... | |
Protected Attributes | |
common::PoseAnimationPtr | animation |
Current pose animation. More... | |
event::ConnectionPtr | animationConnection |
Connection used to update an animation. More... | |
ignition::math::Pose3d | animationStartPose |
Start pose of an animation. More... | |
Base_V | children |
Children of this entity. More... | |
std::vector< event::ConnectionPtr > | connections |
All our event connections. More... | |
ignition::math::Pose3d | dirtyPose |
The pose set by a physics engine. More... | |
std::vector< common::URI > | introspectionItems |
All the introspection items regsitered for this. More... | |
transport::NodePtr | node |
Communication node. More... | |
ignition::transport::Node | nodeIgn |
Ignition communication node. More... | |
BasePtr | parent |
Parent of this entity. More... | |
EntityPtr | parentEntity |
A helper that prevents numerous dynamic_casts. More... | |
common::Time | prevAnimationTime |
Previous time an animation was updated. More... | |
transport::PublisherPtr | requestPub |
Request publisher. More... | |
ignition::transport::Node::Publisher | requestPubIgn |
Request publisher. More... | |
ignition::math::Vector3d | scale |
Scale of the entity. More... | |
sdf::ElementPtr | sdf |
The SDF values for this object. More... | |
transport::PublisherPtr | visPub |
Visual publisher. More... | |
ignition::transport::Node::Publisher | visPubIgn |
Visual publisher. More... | |
msgs::Visual * | visualMsg |
Visual message container. More... | |
WorldPtr | world |
Pointer to the world. More... | |
ignition::math::Pose3d | worldPose |
World pose of the entity. More... | |
A light entity.
|
inherited |
Unique identifiers for all entity types.
Enumerator | |
---|---|
BASE | Base type. |
ENTITY | Entity type. |
MODEL | Model type. |
LINK | Link type. |
COLLISION | Collision type. |
LIGHT | Light type. |
VISUAL | Visual type. |
JOINT | Joint type. |
BALL_JOINT | BallJoint type. |
HINGE2_JOINT | Hing2Joint type. |
HINGE_JOINT | HingeJoint type. |
SLIDER_JOINT | SliderJoint type. |
SCREW_JOINT | ScrewJoint type. |
UNIVERSAL_JOINT | UniversalJoint type. |
GEARBOX_JOINT | GearboxJoint type. |
FIXED_JOINT | FixedJoint type. |
ACTOR | Actor type. |
SHAPE | Shape type. |
BOX_SHAPE | BoxShape type. |
CYLINDER_SHAPE | CylinderShape type. |
HEIGHTMAP_SHAPE | HeightmapShape type. |
MAP_SHAPE | MapShape type. |
MULTIRAY_SHAPE | MultiRayShape type. |
RAY_SHAPE | RayShape type. |
PLANE_SHAPE | PlaneShape type. |
SPHERE_SHAPE | SphereShape type. |
MESH_SHAPE | MeshShape type. |
POLYLINE_SHAPE | PolylineShape type. |
SENSOR_COLLISION | Indicates a collision shape used for sensing. |
|
virtual |
Destructor.
|
inherited |
|
inherited |
Add a type specifier.
[in] | _type | New type to append to this objects type definition. |
Referenced by Base::Update().
|
virtualinherited |
Return the bounding box for the entity.
Reimplemented in Link, Model, Collision, ODECollision, BulletCollision, DARTCollision, and SimbodyCollision.
|
inherited |
Returns collision bounding box.
|
protectedinherited |
Compute the scoped name of this object based on its parents.
Referenced by Base::Update().
|
inherited |
Returns Entity::dirtyPose.
The dirty pose is the pose set by the physics engine before it's value is propagated to the rest of the simulator.
void FillMsg | ( | msgs::Light & | _msg | ) |
Fill a light message with this light's parameters.
[out] | _msg | Message to fill using this light's data. |
|
virtualinherited |
Finalize the entity.
Reimplemented from Base.
Reimplemented in Actor, Model, Link, DARTModel, DARTCollision, DARTLink, ODECollision, SimbodyLink, BulletLink, ODELink, and Collision.
|
inherited |
Get by name.
[in] | _name | Get a child (or self) object by name |
Referenced by Base::Update().
|
inherited |
Get a child by index.
[in] | _i | Index of the child to retreive. |
Referenced by Base::Update().
|
inherited |
Get a child by name.
[in] | _name | Name of the child. |
|
inherited |
Get a child collision entity, if one exists.
[in] | _name | Name of the child collision object. |
|
inherited |
|
inherited |
|
inherited |
|
inherited |
|
inherited |
Get the distance to the nearest entity below (along the Z-axis) this entity.
[out] | _distBelow | The distance to the nearest entity below. |
[out] | _entityName | The name of the nearest entity below. |
|
inherited |
|
inherited |
|
inherited |
Get the parent model, if one exists.
|
inherited |
Get whether the object should be "saved", when the user selects to save the world to xml.
Referenced by Base::Update().
|
inherited |
Return the name of this entity with the model scope model1::...::modelN::entityName.
[in] | _prependWorldName | True to prended the returned string with the world name. The result will be world::model1::...::modelN::entityName. |
Referenced by Base::Update().
|
virtualinherited |
Get the SDF values for the object.
Reimplemented in Actor, and Model.
Referenced by Base::Update().
|
inherited |
|
inherited |
Get the World this object is in.
Referenced by Base::Update().
|
inherited |
Returns true if this object's type definition has the given type.
[in] | _t | Type to check. |
Referenced by Base::Update().
|
overridevirtual |
Initialize the light.
Reimplemented from Base.
|
inherited |
Get the initial relative pose.
|
inlineinherited |
A helper function that checks if this is a canonical body.
|
inherited |
True if the entity is selected by the user.
Referenced by Base::Update().
|
inherited |
Return whether this entity is static.
|
overridevirtual |
|
overridevirtual |
This function is called when the entity's (or one of its parents) pose of the parent has changed.
Implements Entity.
|
inherited |
Returns true if the entities are the same.
Checks only the name.
[in] | _ent | Base object to compare with. |
Referenced by Base::Update().
|
inherited |
|
inherited |
Move this entity to be ontop of the nearest entity below.
|
inherited |
Print this object to screen via gzmsg.
[in] | _prefix | Usually a set of spaces. |
Referenced by Base::Update().
void ProcessMsg | ( | const msgs::Light & | _msg | ) |
Update this light's parameters from a message.
[in] | _msg | Message to process. |
|
protectedvirtualinherited |
Register items in the introspection service.
Reimplemented in Link, Joint, and Model.
Referenced by Base::Update().
|
virtualinherited |
|
virtualinherited |
|
virtualinherited |
|
virtualinherited |
|
inherited |
Get the pose of the entity relative to its parent.
|
virtualinherited |
Remove a child from this entity.
[in] | _id | ID of the child to remove. |
Referenced by Link::GetKinematic(), and Base::Update().
|
inherited |
Remove a child by name.
[in] | _name | Name of the child. |
|
inherited |
Remove a child by pointer.
[in] | _child | Pointer to the child. |
|
inherited |
Remove all children.
Referenced by Base::Update().
|
virtualinherited |
|
virtualinherited |
Calls recursive Reset on one of the Base::EntityType's.
[in] | _resetType | The type of reset operation |
|
inherited |
Get the SDF pose of the object according to the sdf 1.6 convention.
This convention is that the pose of an element is relative to its parent XML element, except for joints, whose pose is relative to the child link.
Referenced by Base::Update().
|
overridevirtual |
Get the SDF SemanticPose object associated with the pose of this object.
Objects that support frame semantics need to override this function and provide this function.
Reimplemented from Base.
|
inherited |
Set an animation for this entity.
[in] | _anim | Pose animation. |
[in] | _onComplete | Callback for when the animation completes. |
|
inherited |
Set an animation for this entity.
[in] | _anim | Pose animation. |
|
inherited |
Set to true if this entity is a canonical link for a model.
[in] | _value | True if the link is canonical. |
|
inherited |
Set the initial pose.
[in] | _pose | The initial pose. |
|
virtualinherited |
|
inherited |
|
inherited |
Set the pose of the entity relative to its parent.
[in] | _pose | The new pose. |
[in] | _notify | True = tell children of the pose change. |
[in] | _publish | True to publish the pose. |
|
inherited |
Set whether the object should be "saved", when the user selects to save the world to xml.
[in] | _v | Set to True if the object should be saved. |
Referenced by Base::Update().
|
virtualinherited |
Set whether this entity has been selected by the user through the gui.
[in] | _show | True to set this entity as selected. |
Reimplemented in Link.
Referenced by Base::Update().
void SetState | ( | const LightState & | _state | ) |
Set the current light state.
[in] | _state | State to set the light to. |
|
inherited |
Set whether this entity is static: immovable.
[in] | _static | True = static. |
Referenced by Link::UpdateSurface().
|
inherited |
Set the world this object belongs to.
This will also set the world for all children.
[in] | _newWorld | The new World this object is part of. |
Referenced by Base::Update().
|
inherited |
Set the world pose of the entity.
[in] | _pose | The new world pose. |
[in] | _notify | True = tell children of the pose change. |
[in] | _publish | True to publish the pose. |
void SetWorldPoseDirty | ( | ) |
Indicate that the world pose should be recalculated.
The recalculation will be done when Light::WorldPose is called.
|
inherited |
Set angular and linear rates of an physics::Entity.
[in] | _linear | Linear twist. |
[in] | _angular | Angular twist. |
[in] | _updateChildren | True to pass this update to child entities. |
|
virtualinherited |
Stop the current animation, if any.
Reimplemented in Model.
|
inherited |
Get the string name for the entity type.
Referenced by Base::Update().
|
protectedvirtualinherited |
Unregister items in the introspection service.
Referenced by Base::Update().
|
inlinevirtualinherited |
Update the object.
Reimplemented in MultiRayShape, Actor, Joint, RayShape, Model, DARTModel, MapShape, DARTRayShape, ODERayShape, DARTMeshShape, ODEMeshShape, ODEPolylineShape, SimbodyRayShape, BulletRayShape, and MeshShape.
References Base::AddChild(), Base::AddType(), Base::ComputeScopedName(), Base::GetByName(), Base::GetChild(), Base::GetChildCount(), Base::GetId(), Base::GetName(), Base::GetParent(), Base::GetParentId(), Base::GetSaveable(), Base::GetScopedName(), Base::GetSDF(), Base::GetType(), Base::GetWorld(), Base::HasType(), Base::IsSelected(), Base::operator==(), Base::Print(), Base::RegisterIntrospectionItems(), Base::RemoveChild(), Base::RemoveChildren(), Base::SDFPoseRelativeToParent(), Base::SDFSemanticPose(), Base::SetName(), Base::SetParent(), Base::SetSaveable(), Base::SetSelected(), Base::SetWorld(), Base::TypeStr(), Base::UnregisterIntrospectionItems(), Base::UpdateParameters(), and Base::URI().
|
virtualinherited |
|
inherited |
Return the common::URI of this entity.
The URI includes the world where the entity is contained and all the hierarchy of sub-entities that can compose this entity. E.g.: A link entity contains the name of the link and the model where the link is contained.
Referenced by Base::Update().
|
virtualinherited |
|
virtualinherited |
Get the angular velocity of the entity in the world frame.
Reimplemented in Model, Collision, ODELink, DARTLink, SimbodyLink, and BulletLink.
|
virtualinherited |
|
virtualinherited |
|
overridevirtual |
Get the absolute pose of the entity.
Reimplemented from Entity.
|
protectedinherited |
Current pose animation.
|
protectedinherited |
Connection used to update an animation.
|
protectedinherited |
Start pose of an animation.
|
protectedinherited |
Children of this entity.
|
protectedinherited |
All our event connections.
|
protectedinherited |
The pose set by a physics engine.
|
protectedinherited |
All the introspection items regsitered for this.
|
protectedinherited |
Communication node.
|
protectedinherited |
Ignition communication node.
|
protectedinherited |
Parent of this entity.
|
protectedinherited |
A helper that prevents numerous dynamic_casts.
|
protectedinherited |
Previous time an animation was updated.
|
protectedinherited |
Request publisher.
|
protectedinherited |
Request publisher.
|
protectedinherited |
Scale of the entity.
|
protectedinherited |
The SDF values for this object.
|
protectedinherited |
Visual publisher.
|
protectedinherited |
Visual publisher.
|
protectedinherited |
Visual message container.
|
protectedinherited |
Pointer to the world.
|
mutableprotectedinherited |
World pose of the entity.