Sensor with one or more rays. More...
#include <sensors/sensors.hh>
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... | |
int | Fiducial (const unsigned int _index) const |
Get detected fiducial value for a ray. More... | |
double | GetAngleResolution () const GAZEBO_DEPRECATED(7.0) |
Get the angle in radians between each range. More... | |
int | GetFiducial (unsigned int _index) GAZEBO_DEPRECATED(7.0) |
Get detected fiducial value for a ray. More... | |
physics::MultiRayShapePtr | GetLaserShape () const GAZEBO_DEPRECATED(7.0) |
Returns a pointer to the internal physics::MultiRayShape. 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... | |
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... | |
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... | |
virtual void | Load (const std::string &_worldName) |
Load the sensor with default parameters. 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... | |
double | Retro (const unsigned int _index) const |
Get detected retro (intensity) value for a ray. More... | |
virtual std::string | Topic () const |
Returns the topic name as set in SDF. 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... | |
Public Member Functions inherited from gazebo::sensors::Sensor | |
Sensor (SensorCategory _cat) | |
Constructor. More... | |
virtual | ~Sensor () |
Destructor. 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... | |
void | FillMsg (msgs::Sensor &_msg) |
fills a msgs::Sensor message. More... | |
SensorCategory | GetCategory () const GAZEBO_DEPRECATED(7.0) |
Get the category of the sensor. More... | |
uint32_t | GetId () const GAZEBO_DEPRECATED(7.0) |
Get the sensor's ID. 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... | |
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... | |
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... | |
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, 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... | |
void | ResetLastUpdateTime () |
Reset the lastUpdateTime to zero. 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... | |
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... | |
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... | |
virtual bool | UpdateImpl (const bool _force) |
This gets overwritten by derived sensor types. More... | |
Protected Member Functions inherited from gazebo::sensors::Sensor | |
bool | NeedsUpdate () |
Return true if the sensor needs to be updated. More... | |
Additional Inherited Members | |
Protected Attributes inherited from gazebo::sensors::Sensor | |
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).
gazebo::sensors::RaySensor::RaySensor | ( | ) |
Constructor.
|
virtual |
Destructor.
ignition::math::Angle gazebo::sensors::RaySensor::AngleMax | ( | ) | const |
Get the maximum angle.
ignition::math::Angle gazebo::sensors::RaySensor::AngleMin | ( | ) | const |
Get the minimum angle.
double gazebo::sensors::RaySensor::AngleResolution | ( | ) | const |
Get the angle in radians between each range.
int gazebo::sensors::RaySensor::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 |
|
protectedvirtual |
Finalize the sensor.
Reimplemented from gazebo::sensors::Sensor.
double gazebo::sensors::RaySensor::GetAngleResolution | ( | ) | const |
Get the angle in radians between each range.
int gazebo::sensors::RaySensor::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 |
physics::MultiRayShapePtr gazebo::sensors::RaySensor::GetLaserShape | ( | ) | const |
Returns a pointer to the internal physics::MultiRayShape.
double gazebo::sensors::RaySensor::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 gazebo::sensors::RaySensor::GetRangeCount | ( | ) | const |
double gazebo::sensors::RaySensor::GetRangeMax | ( | ) | const |
double gazebo::sensors::RaySensor::GetRangeMin | ( | ) | const |
double gazebo::sensors::RaySensor::GetRangeResolution | ( | ) | const |
void gazebo::sensors::RaySensor::GetRanges | ( | std::vector< double > & | _ranges | ) |
Get all the ranges.
_ranges | A vector that will contain all the range data |
int gazebo::sensors::RaySensor::GetRayCount | ( | ) | const |
double gazebo::sensors::RaySensor::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 |
double gazebo::sensors::RaySensor::GetVerticalAngleResolution | ( | ) | const |
Get the vertical angle in radians between each range.
int gazebo::sensors::RaySensor::GetVerticalRangeCount | ( | ) | const |
Get the vertical scan line count.
int gazebo::sensors::RaySensor::GetVerticalRayCount | ( | ) | const |
Get the vertical scan line count.
|
virtual |
Initialize the sensor.
Reimplemented from gazebo::sensors::Sensor.
|
virtual |
Returns true if sensor generation is active.
Reimplemented from gazebo::sensors::Sensor.
physics::MultiRayShapePtr gazebo::sensors::RaySensor::LaserShape | ( | ) | const |
Returns a pointer to the internal physics::MultiRayShape.
|
virtual |
Load the sensor with default parameters.
[in] | _worldName | Name of world to load from. |
Reimplemented from gazebo::sensors::Sensor.
double gazebo::sensors::RaySensor::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 gazebo::sensors::RaySensor::RangeCount | ( | ) | const |
Get the range count.
double gazebo::sensors::RaySensor::RangeMax | ( | ) | const |
Get the maximum range.
double gazebo::sensors::RaySensor::RangeMin | ( | ) | const |
Get the minimum range.
double gazebo::sensors::RaySensor::RangeResolution | ( | ) | const |
Get the range resolution.
void gazebo::sensors::RaySensor::Ranges | ( | std::vector< double > & | _ranges | ) | const |
Get all the ranges.
[out] | _ranges | A vector that will contain all the range data |
int gazebo::sensors::RaySensor::RayCount | ( | ) | const |
Get the ray count.
double gazebo::sensors::RaySensor::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 |
|
virtual |
Returns the topic name as set in SDF.
Reimplemented from gazebo::sensors::Sensor.
|
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 gazebo::sensors::Sensor.
ignition::math::Angle gazebo::sensors::RaySensor::VerticalAngleMax | ( | ) | const |
Get the vertical scan line top angle.
ignition::math::Angle gazebo::sensors::RaySensor::VerticalAngleMin | ( | ) | const |
Get the vertical scan bottom angle.
double gazebo::sensors::RaySensor::VerticalAngleResolution | ( | ) | const |
Get the vertical angle in radians between each range.
int gazebo::sensors::RaySensor::VerticalRangeCount | ( | ) | const |
Get the vertical scan line count.
int gazebo::sensors::RaySensor::VerticalRayCount | ( | ) | const |
Get the vertical scan line count.