Sensor with one or more rays. More...
#include <sensors/sensors.hh>
Inherits Sensor.
Public Member Functions | |
RaySensor () | |
Constructor. More... | |
virtual | ~RaySensor () |
Destructor. More... | |
ignition::math::Angle | AngleMax () const |
Get the maximum angle. More... | |
ignition::math::Angle | AngleMin () const |
Get the minimum angle. More... | |
double | AngleResolution () const |
Get the angle in radians between each range. More... | |
SensorCategory | Category () const |
Get the category of the sensor. More... | |
event::ConnectionPtr | ConnectUpdated (std::function< void()> _subscriber) |
Connect a signal that is triggered when the sensor is updated. More... | |
void | DisconnectUpdated (event::ConnectionPtr &_c) |
Disconnect from a the updated signal. More... | |
int | Fiducial (const unsigned int _index) const |
Get detected fiducial value for a ray. More... | |
void | FillMsg (msgs::Sensor &_msg) |
fills a msgs::Sensor message. More... | |
double | GetAngleResolution () const GAZEBO_DEPRECATED(7.0) |
Get the angle in radians between each range. More... | |
SensorCategory | GetCategory () const GAZEBO_DEPRECATED(7.0) |
Get the category of the sensor. More... | |
int | GetFiducial (unsigned int _index) GAZEBO_DEPRECATED(7.0) |
Get detected fiducial value for a ray. More... | |
uint32_t | GetId () const GAZEBO_DEPRECATED(7.0) |
Get the sensor's ID. More... | |
physics::MultiRayShapePtr | GetLaserShape () const GAZEBO_DEPRECATED(7.0) |
Returns a pointer to the internal physics::MultiRayShape. More... | |
common::Time | GetLastMeasurementTime () GAZEBO_DEPRECATED(7.0) |
Return last measurement time. More... | |
common::Time | GetLastUpdateTime () GAZEBO_DEPRECATED(7.0) |
Return last update time. More... | |
std::string | GetName () const GAZEBO_DEPRECATED(7.0) |
Get name. More... | |
NoisePtr | GetNoise (const SensorNoiseType _type) const GAZEBO_DEPRECATED(7.0) |
Get the sensor's noise model for a specified noise type. More... | |
uint32_t | GetParentId () const GAZEBO_DEPRECATED(7.0) |
Get the sensor's parent's ID. More... | |
std::string | GetParentName () const GAZEBO_DEPRECATED(7.0) |
Returns the name of the sensor parent. More... | |
double | GetRange (unsigned int _index) GAZEBO_DEPRECATED(7.0) |
Get detected range for a ray. More... | |
int | GetRangeCount () const GAZEBO_DEPRECATED(7.0) |
Get the range count. More... | |
double | GetRangeMax () const GAZEBO_DEPRECATED(7.0) |
Get the maximum range. More... | |
double | GetRangeMin () const GAZEBO_DEPRECATED(7.0) |
Get the minimum range. More... | |
double | GetRangeResolution () const GAZEBO_DEPRECATED(7.0) |
Get the range resolution. More... | |
void | GetRanges (std::vector< double > &_ranges) GAZEBO_DEPRECATED(7.0) |
Get all the ranges. More... | |
int | GetRayCount () const GAZEBO_DEPRECATED(7.0) |
Get the ray count. More... | |
double | GetRetro (unsigned int _index) GAZEBO_DEPRECATED(7.0) |
Get detected retro (intensity) value for a ray. More... | |
std::string | GetScopedName () const GAZEBO_DEPRECATED(7.0) |
Get fully scoped name of the sensor. More... | |
virtual std::string | GetTopic () const GAZEBO_DEPRECATED(7.0) |
Returns the topic name as set in SDF. More... | |
std::string | GetType () const GAZEBO_DEPRECATED(7.0) |
Get sensor type. More... | |
double | GetUpdateRate () GAZEBO_DEPRECATED(7.0) |
Get the update rate of the sensor. More... | |
double | GetVerticalAngleResolution () const GAZEBO_DEPRECATED(7.0) |
Get the vertical angle in radians between each range. More... | |
int | GetVerticalRangeCount () const GAZEBO_DEPRECATED(7.0) |
Get the vertical scan line count. More... | |
int | GetVerticalRayCount () const GAZEBO_DEPRECATED(7.0) |
Get the vertical scan line count. More... | |
bool | GetVisualize () const GAZEBO_DEPRECATED(7.0) |
Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF. More... | |
std::string | GetWorldName () const GAZEBO_DEPRECATED(7.0) |
Returns the name of the world the sensor is in. More... | |
uint32_t | Id () const |
Get the sensor's ID. More... | |
virtual void | Init () |
Initialize the sensor. More... | |
virtual bool | IsActive () const |
Returns true if sensor generation is active. More... | |
physics::MultiRayShapePtr | LaserShape () const |
Returns a pointer to the internal physics::MultiRayShape. More... | |
common::Time | LastMeasurementTime () const |
Return last measurement time. More... | |
common::Time | LastUpdateTime () const |
Return last update time. More... | |
virtual void | Load (const std::string &_worldName) |
Load the sensor with default parameters. More... | |
virtual void | Load (const std::string &_worldName, sdf::ElementPtr _sdf) |
Load the sensor with SDF parameters. More... | |
std::string | Name () const |
Get name. More... | |
NoisePtr | Noise (const SensorNoiseType _type) const |
Get the sensor's noise model for a specified noise type. More... | |
uint32_t | ParentId () const |
Get the sensor's parent's ID. More... | |
std::string | ParentName () const |
Returns the name of the sensor parent. More... | |
virtual ignition::math::Pose3d | Pose () const |
Get the current pose. More... | |
double | Range (const unsigned int _index) const |
Get detected range for a ray. More... | |
int | RangeCount () const |
Get the range count. More... | |
double | RangeMax () const |
Get the maximum range. More... | |
double | RangeMin () const |
Get the minimum range. More... | |
double | RangeResolution () const |
Get the range resolution. More... | |
void | Ranges (std::vector< double > &_ranges) const |
Get all the ranges. More... | |
int | RayCount () const |
Get the ray count. More... | |
void | ResetLastUpdateTime () |
Reset the lastUpdateTime to zero. More... | |
double | Retro (const unsigned int _index) const |
Get detected retro (intensity) value for a ray. More... | |
std::string | ScopedName () const |
Get fully scoped name of the sensor. More... | |
virtual void | SetActive (const bool _value) |
Set whether the sensor is active or not. More... | |
void | SetParent (const std::string &_name, const uint32_t _id) |
Set the sensor's parent. More... | |
virtual void | SetPose (const ignition::math::Pose3d &_pose) |
Set the current pose. More... | |
void | SetUpdateRate (const double _hz) |
Set the update rate of the sensor. More... | |
virtual std::string | Topic () const |
Returns the topic name as set in SDF. More... | |
std::string | Type () const |
Get sensor type. More... | |
void | Update (const bool _force) |
Update the sensor. More... | |
double | UpdateRate () const |
Get the update rate of the sensor. More... | |
ignition::math::Angle | VerticalAngleMax () const |
Get the vertical scan line top angle. More... | |
ignition::math::Angle | VerticalAngleMin () const |
Get the vertical scan bottom angle. More... | |
double | VerticalAngleResolution () const |
Get the vertical angle in radians between each range. More... | |
int | VerticalRangeCount () const |
Get the vertical scan line count. More... | |
int | VerticalRayCount () const |
Get the vertical scan line count. More... | |
bool | Visualize () const |
Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF. More... | |
std::string | WorldName () const |
Returns the name of the world the sensor is in. More... | |
Protected Member Functions | |
virtual void | Fini () |
Finalize the sensor. More... | |
bool | NeedsUpdate () |
Return true if the sensor needs to be updated. More... | |
virtual bool | UpdateImpl (const bool _force) |
This gets overwritten by derived sensor types. More... | |
Protected Attributes | |
bool | active |
True if sensor generation is active. More... | |
std::vector< event::ConnectionPtr > | connections |
All event connections. More... | |
common::Time | lastMeasurementTime |
Stores last time that a sensor measurement was generated; this value must be updated within each sensor's UpdateImpl. More... | |
common::Time | lastUpdateTime |
Time of the last update. More... | |
transport::NodePtr | node |
Node for communication. More... | |
std::map< SensorNoiseType, NoisePtr > | noises |
Noise added to sensor data. More... | |
uint32_t | parentId |
The sensor's parent ID. More... | |
std::string | parentName |
Name of the parent. More... | |
std::vector< SensorPluginPtr > | plugins |
All the plugins for the sensor. More... | |
ignition::math::Pose3d | pose |
Pose of the sensor. More... | |
gazebo::rendering::ScenePtr | scene |
Pointer to the Scene. More... | |
sdf::ElementPtr | sdf |
Pointer the the SDF element for the sensor. More... | |
common::Time | updatePeriod |
Desired time between updates, set indirectly by Sensor::SetUpdateRate. More... | |
gazebo::physics::WorldPtr | world |
Pointer to the world. More... | |
Sensor with one or more rays.
This sensor cast rays into the world, tests for intersections, and reports the range to the nearest object. It is used by ranging sensor models (e.g., sonars and scanning laser range finders).
RaySensor | ( | ) |
Constructor.
|
virtual |
Destructor.
ignition::math::Angle AngleMax | ( | ) | const |
Get the maximum angle.
ignition::math::Angle AngleMin | ( | ) | const |
Get the minimum angle.
double AngleResolution | ( | ) | const |
Get the angle in radians between each range.
|
inherited |
|
inherited |
Connect a signal that is triggered when the sensor is updated.
[in] | _subscriber | Callback that receives the signal. |
|
inherited |
Disconnect from a the updated signal.
[in] | _c | The connection to disconnect |
int Fiducial | ( | const unsigned int | _index | ) | const |
Get detected fiducial value for a ray.
Warning: If you are accessing all the ray data in a loop it's possible that the Ray will update in the middle of your access loop. This means some data will come from one scan, and some from another scan. You can solve this problem by using SetActive(false) <your accessor="" loop>=""> SetActive(true).
[in] | _index | Index value of specific ray |
|
inherited |
fills a msgs::Sensor message.
[out] | _msg | Message to fill. |
|
protectedvirtual |
Finalize the sensor.
Reimplemented from Sensor.
double GetAngleResolution | ( | ) | const |
Get the angle in radians between each range.
|
inherited |
Get the category of the sensor.
int GetFiducial | ( | unsigned int | _index | ) |
Get detected fiducial value for a ray.
Warning: If you are accessing all the ray data in a loop it's possible that the Ray will update in the middle of your access loop. This means some data will come from one scan, and some from another scan. You can solve this problem by using SetActive(false) <your accessor="" loop>=""> SetActive(true).
[in] | _index | Index value of specific ray |
|
inherited |
physics::MultiRayShapePtr GetLaserShape | ( | ) | const |
Returns a pointer to the internal physics::MultiRayShape.
|
inherited |
Return last measurement time.
|
inherited |
|
inherited |
|
inherited |
Get the sensor's noise model for a specified noise type.
[in] | _type | Index of the noise type. Refer to SensorNoiseType enumeration for possible indices |
|
inherited |
|
inherited |
Returns the name of the sensor parent.
The parent name is set by Sensor::SetParent.
double GetRange | ( | unsigned int | _index | ) |
Get detected range for a ray.
Warning: If you are accessing all the ray data in a loop it's possible that the Ray will update in the middle of your access loop. This means some data will come from one scan, and some from another scan. You can solve this problem by using SetActive(false) <your accessor="" loop>=""> SetActive(true).
[in] | _index | Index of specific ray |
int GetRangeCount | ( | ) | const |
double GetRangeMax | ( | ) | const |
double GetRangeMin | ( | ) | const |
double GetRangeResolution | ( | ) | const |
void GetRanges | ( | std::vector< double > & | _ranges | ) |
Get all the ranges.
_ranges | A vector that will contain all the range data |
int GetRayCount | ( | ) | const |
double GetRetro | ( | unsigned int | _index | ) |
Get detected retro (intensity) value for a ray.
Warning: If you are accessing all the ray data in a loop it's possible that the Ray will update in the middle of your access loop. This means some data will come from one scan, and some from another scan. You can solve this problem by using SetActive(false) <your accessor="" loop>=""> SetActive(true).
[in] | _index | Index of specific ray |
|
inherited |
Get fully scoped name of the sensor.
|
virtualinherited |
Returns the topic name as set in SDF.
Reimplemented in AltimeterSensor, LogicalCameraSensor, and MagnetometerSensor.
|
inherited |
|
inherited |
Get the update rate of the sensor.
double GetVerticalAngleResolution | ( | ) | const |
Get the vertical angle in radians between each range.
int GetVerticalRangeCount | ( | ) | const |
Get the vertical scan line count.
int GetVerticalRayCount | ( | ) | const |
Get the vertical scan line count.
|
inherited |
Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF.
|
inherited |
Returns the name of the world the sensor is in.
|
inherited |
Get the sensor's ID.
|
virtual |
Initialize the sensor.
Reimplemented from Sensor.
|
virtual |
Returns true if sensor generation is active.
Reimplemented from Sensor.
physics::MultiRayShapePtr LaserShape | ( | ) | const |
Returns a pointer to the internal physics::MultiRayShape.
|
inherited |
Return last measurement time.
|
inherited |
Return last update time.
|
virtual |
Load the sensor with default parameters.
[in] | _worldName | Name of world to load from. |
Reimplemented from Sensor.
|
virtualinherited |
Load the sensor with SDF parameters.
[in] | _sdf | SDF Sensor parameters. |
[in] | _worldName | Name of world to load from. |
Reimplemented in GpuRaySensor, ContactSensor, DepthCameraSensor, CameraSensor, ForceTorqueSensor, AltimeterSensor, GpsSensor, LogicalCameraSensor, RFIDSensor, MagnetometerSensor, ImuSensor, and RFIDTag.
|
inherited |
Get name.
|
protectedinherited |
Return true if the sensor needs to be updated.
|
inherited |
Get the sensor's noise model for a specified noise type.
[in] | _type | Index of the noise type. Refer to SensorNoiseType enumeration for possible indices |
|
inherited |
Get the sensor's parent's ID.
|
inherited |
Returns the name of the sensor parent.
The parent name is set by Sensor::SetParent.
|
virtualinherited |
double Range | ( | const unsigned int | _index | ) | const |
Get detected range for a ray.
Warning: If you are accessing all the ray data in a loop it's possible that the Ray will update in the middle of your access loop. This means some data will come from one scan, and some from another scan. You can solve this problem by using SetActive(false) <your accessor="" loop>=""> SetActive(true).
[in] | _index | Index of specific ray |
int RangeCount | ( | ) | const |
Get the range count.
double RangeMax | ( | ) | const |
Get the maximum range.
double RangeMin | ( | ) | const |
Get the minimum range.
double RangeResolution | ( | ) | const |
Get the range resolution.
void Ranges | ( | std::vector< double > & | _ranges | ) | const |
Get all the ranges.
[out] | _ranges | A vector that will contain all the range data |
int RayCount | ( | ) | const |
Get the ray count.
|
inherited |
Reset the lastUpdateTime to zero.
double Retro | ( | const unsigned int | _index | ) | const |
Get detected retro (intensity) value for a ray.
Warning: If you are accessing all the ray data in a loop it's possible that the Ray will update in the middle of your access loop. This means some data will come from one scan, and some from another scan. You can solve this problem by using SetActive(false) <your accessor="" loop>=""> SetActive(true).
[in] | _index | Index of specific ray |
|
inherited |
Get fully scoped name of the sensor.
|
virtualinherited |
Set whether the sensor is active or not.
[in] | _value | True if active, false if not. |
Reimplemented in DepthCameraSensor.
|
inherited |
Set the sensor's parent.
[in] | _name | The sensor's parent's name. |
[in] | _id | The sensor's parent's ID. |
|
virtualinherited |
|
inherited |
Set the update rate of the sensor.
[in] | _hz | update rate of sensor. |
|
virtual |
|
inherited |
Get sensor type.
|
inherited |
Update the sensor.
[in] | _force | True to force update, false otherwise. |
|
protectedvirtual |
This gets overwritten by derived sensor types.
This function is called during Sensor::Update. And in turn, Sensor::Update is called by SensorManager::Update
[in] | _force | True if update is forced, false if not |
Reimplemented from Sensor.
|
inherited |
Get the update rate of the sensor.
ignition::math::Angle VerticalAngleMax | ( | ) | const |
Get the vertical scan line top angle.
ignition::math::Angle VerticalAngleMin | ( | ) | const |
Get the vertical scan bottom angle.
double VerticalAngleResolution | ( | ) | const |
Get the vertical angle in radians between each range.
int VerticalRangeCount | ( | ) | const |
Get the vertical scan line count.
int VerticalRayCount | ( | ) | const |
Get the vertical scan line count.
|
inherited |
Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF.
|
inherited |
Returns the name of the world the sensor is in.
|
protectedinherited |
True if sensor generation is active.
|
protectedinherited |
All event connections.
|
protectedinherited |
Stores last time that a sensor measurement was generated; this value must be updated within each sensor's UpdateImpl.
|
protectedinherited |
Time of the last update.
|
protectedinherited |
Node for communication.
|
protectedinherited |
Noise added to sensor data.
|
protectedinherited |
The sensor's parent ID.
|
protectedinherited |
Name of the parent.
|
protectedinherited |
All the plugins for the sensor.
|
protectedinherited |
Pose of the sensor.
|
protectedinherited |
Pointer to the Scene.
|
protectedinherited |
Pointer the the SDF element for the sensor.
|
protectedinherited |
Desired time between updates, set indirectly by Sensor::SetUpdateRate.
|
protectedinherited |
Pointer to the world.