Go to the documentation of this file.
17 #ifndef GAZEBO_SENSORS_SENSOR_HH_
18 #define GAZEBO_SENSORS_SENSOR_HH_
26 #include <ignition/math/Pose3.hh>
27 #include <ignition/transport/Node.hh>
52 :
public std::enable_shared_from_this<Sensor>
64 public:
virtual void Load(
const std::string &_worldName,
65 sdf::ElementPtr _sdf);
69 public:
virtual void Load(
const std::string &_worldName);
72 public:
virtual void Init();
77 public:
void SetParent(
const std::string &_name,
const uint32_t _id);
82 public: std::string ParentName()
const;
86 public:
virtual void Update(
const bool _force);
90 public:
double UpdateRate()
const;
94 public:
void SetUpdateRate(
const double _hz);
97 public:
virtual void Fini();
101 public: std::string Name()
const;
105 public: std::string ScopedName()
const;
110 public:
virtual ignition::math::Pose3d Pose()
const;
115 public:
virtual void SetPose(
const ignition::math::Pose3d &_pose);
119 public:
virtual void SetActive(
const bool _value);
123 public:
virtual bool IsActive()
const;
127 public: std::string Type()
const;
140 public:
bool Visualize()
const;
144 public:
virtual std::string Topic()
const;
148 public:
void FillMsg(msgs::Sensor &_msg);
152 public: std::string WorldName()
const;
160 std::function<
void()> _subscriber);
168 public:
virtual void ResetLastUpdateTime();
172 public: uint32_t Id()
const;
176 public: uint32_t ParentId()
const;
186 public:
virtual double NextRequiredTimestamp()
const;
194 protected:
virtual bool UpdateImpl(
const bool ) {
return false;}
198 protected:
virtual bool NeedsUpdate();
202 private:
void LoadPlugin(sdf::ElementPtr _sdf);
208 protected: sdf::ElementPtr
sdf;
211 protected: ignition::math::Pose3d
pose;
226 protected: std::vector<SensorPluginPtr>
plugins;
246 protected: std::map<SensorNoiseType, NoisePtr>
noises;
256 private: std::unique_ptr<SensorPrivate> dataPtr;
sdf::ElementPtr sdf
Pointer the the SDF element for the sensor.
Definition: Sensor.hh:208
ignition::math::Pose3d pose
Pose of the sensor.
Definition: Sensor.hh:211
virtual bool NeedsUpdate()
Return true if the sensor needs to be updated.
std::vector< SensorPluginPtr > plugins
All the plugins for the sensor.
Definition: Sensor.hh:226
virtual void Fini()
Finalize the sensor.
Sensor(SensorCategory _cat)
Constructor.
transport::NodePtr node
Node for communication.
Definition: Sensor.hh:217
void SetUpdateRate(const double _hz)
Set the update rate of the sensor.
virtual bool UpdateImpl(const bool)
This gets overwritten by derived sensor types.
Definition: Sensor.hh:194
virtual void Load(const std::string &_worldName, sdf::ElementPtr _sdf)
Load the sensor with SDF parameters.
event::EventT< void()> updated
Event triggered when a sensor is updated.
Definition: Sensor.hh:249
virtual ~Sensor()
Destructor.
Forward declarations for the common classes.
Definition: Animation.hh:26
A Time class, can be used to hold wall- or sim-time. stored as sec and nano-sec.
Definition: Time.hh:47
uint32_t ParentId() const
Get the sensor's parent's ID.
void SetParent(const std::string &_name, const uint32_t _id)
Set the sensor's parent.
std::string parentName
Name of the parent.
Definition: Sensor.hh:220
virtual void Update(const bool _force)
Update the sensor.
void FillMsg(msgs::Sensor &_msg)
fills a msgs::Sensor message.
sensors
Definition: SensorManager.hh:36
common::Time LastMeasurementTime() const
Return last measurement time.
SensorCategory Category() const
Get the category of the sensor.
Forward declarations for transport.
common::Time LastUpdateTime() const
Return last update time.
bool active
True if sensor generation is active.
Definition: Sensor.hh:205
Forward declarations and typedefs for sensors.
Noise models for sensor output signals.
Definition: Noise.hh:55
std::vector< event::ConnectionPtr > connections
All event connections.
Definition: Sensor.hh:214
virtual void ResetLastUpdateTime()
Reset the lastUpdateTime to zero.
ignition::transport::Node nodeIgn
Ignition transport node.
Definition: Sensor.hh:252
virtual std::string Topic() const
Returns the topic name as set in SDF.
virtual double NextRequiredTimestamp() const
Get the next timestamp that will be used by the sensor.
default namespace for gazebo
boost::shared_ptr< Node > NodePtr
Definition: TransportTypes.hh:57
uint32_t parentId
The sensor's parent ID.
Definition: Sensor.hh:223
A class for event processing.
Definition: Event.hh:97
boost::shared_ptr< Scene > ScenePtr
Definition: RenderTypes.hh:82
std::string WorldName() const
Returns the name of the world the sensor is in.
bool Visualize() const
Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF.
common::Time lastUpdateTime
Time of the last update.
Definition: Sensor.hh:239
std::string Name() const
Get name.
double UpdateRate() const
Get the update rate of the sensor.
event::ConnectionPtr ConnectUpdated(std::function< void()> _subscriber)
Connect a signal that is triggered when the sensor is updated.
gazebo::physics::WorldPtr world
Pointer to the world.
Definition: Sensor.hh:229
std::string Type() const
Get sensor type.
std::string ScopedName() const
Get fully scoped name of the sensor.
gazebo::rendering::ScenePtr scene
Pointer to the Scene.
Definition: Sensor.hh:232
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:134
std::string ParentName() const
Returns the name of the sensor parent.
uint32_t Id() const
Get the sensor's ID.
virtual void SetActive(const bool _value)
Set whether the sensor is active or not.
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
virtual bool IsActive() const
Returns true if sensor generation is active.
SensorNoiseType
Definition: SensorTypes.hh:208
virtual void Init()
Initialize the sensor.
std::map< SensorNoiseType, NoisePtr > noises
Noise added to sensor data.
Definition: Sensor.hh:246
common::Time lastMeasurementTime
Stores last time that a sensor measurement was generated; this value must be updated within each sens...
Definition: Sensor.hh:243
Base class for sensors.
Definition: Sensor.hh:51
NoisePtr Noise(const SensorNoiseType _type) const
Get the sensor's noise model for a specified noise type.
virtual ignition::math::Pose3d Pose() const
Get the current pose.
boost::shared_ptr< World > WorldPtr
Definition: PhysicsTypes.hh:90
std::shared_ptr< Noise > NoisePtr
Definition: SensorTypes.hh:124
virtual void SetPose(const ignition::math::Pose3d &_pose)
Set the current pose.
SensorCategory
SensorCategory is used to categorize sensors.
Definition: SensorTypes.hh:308
common::Time updatePeriod
Desired time between updates, set indirectly by Sensor::SetUpdateRate.
Definition: Sensor.hh:236