Thermal camera sensor class. More...
#include <ThermalCameraSensor.hh>
Public Member Functions | |
ThermalCameraSensor () | |
constructor More... | |
virtual | ~ThermalCameraSensor () |
destructor More... | |
common::ConnectionPtr | ConnectImageCallback (std::function< void(const msgs::Image &)> _callback) |
Set a callback to be called when image frame data is generated. More... | |
virtual unsigned int | ImageHeight () const override |
Get image height. More... | |
virtual unsigned int | ImageWidth () const override |
Get image width. More... | |
virtual bool | Init () override |
Initialize values in the sensor. More... | |
virtual bool | Load (const sdf::Sensor &_sdf) override |
Load the sensor based on data from an sdf::Sensor object. More... | |
virtual bool | Load (sdf::ElementPtr _sdf) override |
Load the sensor with SDF parameters. More... | |
void | OnNewThermalFrame (const uint16_t *_scan, unsigned int _width, unsigned int _height, unsigned int _channels, const std::string &_format) |
Thermal data callback used to get the data from the sensor. More... | |
virtual void | SetAmbientTemperature (float _ambient) |
Set the ambient temperature of the environment. More... | |
virtual void | SetAmbientTemperatureRange (float _range) |
Set the range of ambient temperature. More... | |
virtual void | SetLinearResolution (float _resolution) |
Set the temperature linear resolution. The thermal image data returned will be temperature in kelvin / resolution. Typical values are 0.01 (10mK), 0.1 (100mK), or 0.04 to simulate 14 bit format. More... | |
virtual void | SetMaxTemperature (float _max) |
Set the maximum temperature the sensor can detect. More... | |
virtual void | SetMinTemperature (float _min) |
Set the minimum temperature the sensor can detect. More... | |
virtual void | SetScene (gz::rendering::ScenePtr _scene) override |
Set the rendering scene. More... | |
virtual rendering::ThermalCameraPtr | ThermalCamera () |
Force the sensor to generate data. More... | |
virtual bool | Update (const common::Time &_now) override |
Force the sensor to generate data. More... | |
Public Member Functions inherited from CameraSensor | |
CameraSensor () | |
constructor More... | |
virtual | ~CameraSensor () |
destructor More... | |
double | Baseline () const |
Get baseline for stereo cameras. More... | |
gz::common::ConnectionPtr | ConnectImageCallback (std::function< void(const gz::msgs::Image &)> _callback) |
Set a callback to be called when image frame data is generated. More... | |
std::string | InfoTopic () const |
Topic where camera info is published. More... | |
rendering::CameraPtr | RenderingCamera () const |
Get pointer to rendering camera object. More... | |
void | SetBaseline (double _baseline) |
Set baseline for stereo cameras. This is used to populate the projection matrix in the camera info message. More... | |
Public Member Functions inherited from RenderingSensor | |
virtual | ~RenderingSensor () |
destructor More... | |
bool | ManualSceneUpdate () const |
Get whether the scene graph is updated manually. Defaults to false. More... | |
void | Render () |
Render update. This performs the actual render operation. More... | |
rendering::ScenePtr | Scene () const |
Get the rendering scene. More... | |
void | SetManualSceneUpdate (bool _manual) |
Set whether to update the scene graph manually. If set to true, it is expected that rendering::Scene::PreRender is called manually before calling Render() More... | |
virtual void | SetScene (rendering::ScenePtr _scene) |
Set the rendering scene. More... | |
Public Member Functions inherited from Sensor | |
virtual | ~Sensor () |
destructor More... | |
void | AddSequence (gz::msgs::Header *_msg, const std::string &_seqKey="default") |
Add a sequence number to an gz::msgs::Header. This function can be called by a sensor that wants to add a sequence number to a sensor message in order to have improved accountability for generated sensor data. More... | |
bool | EnableMetrics () const |
Get flag state for enabling performance metrics publication. More... | |
std::string | FrameId () const |
FrameId. More... | |
SensorId | Id () const |
Get the sensor's ID. More... | |
std::string | Name () const |
Get name. More... | |
common::Time | NextUpdateTime () const |
Return the next time the sensor will generate data. More... | |
std::string | Parent () const |
Get parent link of the sensor. More... | |
gz::math::Pose3d | Pose () const |
Get the current pose. More... | |
void | PublishMetrics (const std::chrono::duration< double > &_now) |
Publishes information about the performance of the sensor. This method is called by Update(). More... | |
sdf::ElementPtr | SDF () const |
Get the SDF used to load this sensor. More... | |
void | SetEnableMetrics (bool _enableMetrics) |
Set flag to enable publishing performance metrics. More... | |
void | SetFrameId (const std::string &_frameId) |
Set Frame ID of the sensor. More... | |
virtual void | SetParent (const std::string &_parent) |
Set the parent of the sensor. More... | |
void | SetPose (const gz::math::Pose3d &_pose) |
Update the pose of the sensor. More... | |
bool | SetTopic (const std::string &_topic) |
Set topic where sensor data is published. More... | |
void | SetUpdateRate (const double _hz) |
Set the update rate of the sensor. An update rate of zero means that the sensor is updated every cycle. It's zero by default. \detail Negative rates become zero. More... | |
std::string | Topic () const |
Get topic where sensor data is published. More... | |
bool | Update (const common::Time &_now, const bool _force) |
Update the sensor. More... | |
double | UpdateRate () const |
Get the update rate of the sensor. More... | |
Additional Inherited Members | |
Protected Member Functions inherited from CameraSensor | |
bool | AdvertiseInfo () |
Advertise camera info topic. More... | |
bool | AdvertiseInfo (const std::string &_topic) |
Advertise camera info topic. This version takes a string that allows one to override the camera_info topic. More... | |
void | PopulateInfo (const sdf::Camera *_cameraSdf) |
Populate camera info message. More... | |
void | PublishInfo (const gz::common::Time &_now) |
Publish camera info message. More... | |
Protected Member Functions inherited from RenderingSensor | |
RenderingSensor () | |
constructor More... | |
void | AddSensor (rendering::SensorPtr _sensor) |
Add a rendering::Sensor. Its render updates will be handled by this base class. More... | |
Protected Member Functions inherited from Sensor | |
Sensor () | |
constructor More... | |
Detailed Description
Thermal camera sensor class.
This class creates thermal image from an ignition rendering scene. The scene must be created in advance and given to Manager::Init(). It offers both an ignition-transport interface and a direct C++ API to access the image data. The API works by setting a callback to be called with image data.
Constructor & Destructor Documentation
◆ ThermalCameraSensor()
constructor
◆ ~ThermalCameraSensor()
|
virtual |
destructor
Member Function Documentation
◆ ConnectImageCallback()
common::ConnectionPtr ConnectImageCallback | ( | std::function< void(const msgs::Image &)> | _callback | ) |
Set a callback to be called when image frame data is generated.
- Parameters
-
[in] _callback This callback will be called every time the camera produces image data. The Update function will be blocked while the callbacks are executed.
- Remarks
- Do not block inside of the callback.
- Returns
- A connection pointer that must remain in scope. When the connection pointer falls out of scope, the connection is broken.
◆ ImageHeight()
|
overridevirtual |
◆ ImageWidth()
|
overridevirtual |
◆ Init()
|
overridevirtual |
◆ Load() [1/2]
|
overridevirtual |
Load the sensor based on data from an sdf::Sensor object.
- Parameters
-
[in] _sdf SDF Sensor parameters.
- Returns
- true if loading was successful
Reimplemented from CameraSensor.
◆ Load() [2/2]
|
overridevirtual |
Load the sensor with SDF parameters.
- Parameters
-
[in] _sdf SDF Sensor parameters.
- Returns
- true if loading was successful
Reimplemented from CameraSensor.
◆ OnNewThermalFrame()
void OnNewThermalFrame | ( | const uint16_t * | _scan, |
unsigned int | _width, | ||
unsigned int | _height, | ||
unsigned int | _channels, | ||
const std::string & | _format | ||
) |
Thermal data callback used to get the data from the sensor.
- Parameters
-
[in] _scan pointer to the data from the sensor [in] _width width of the thermal image [in] _height height of the thermal image [in] _channel bytes used for the thermal data [in] _format string with the format
◆ SetAmbientTemperature()
|
virtual |
Set the ambient temperature of the environment.
- Parameters
-
[in] _ambient Ambient temperature in kelvin
◆ SetAmbientTemperatureRange()
|
virtual |
Set the range of ambient temperature.
- Parameters
-
[in] _range The ambient temperature ranges from (ambient - range/2) to (ambient + range/2).
◆ SetLinearResolution()
|
virtual |
Set the temperature linear resolution. The thermal image data returned will be temperature in kelvin / resolution. Typical values are 0.01 (10mK), 0.1 (100mK), or 0.04 to simulate 14 bit format.
- Parameters
-
[in] resolution Temperature linear resolution
◆ SetMaxTemperature()
|
virtual |
Set the maximum temperature the sensor can detect.
- Parameters
-
[in] _max Max temperature in kelvin
◆ SetMinTemperature()
|
virtual |
Set the minimum temperature the sensor can detect.
- Parameters
-
[in] _min Min temperature in kelvin
◆ SetScene()
|
overridevirtual |
◆ ThermalCamera()
|
virtual |
Force the sensor to generate data.
- Parameters
-
[in] _now The current time
- Returns
- true if the update was successfull
◆ Update()
|
overridevirtual |
Force the sensor to generate data.
- Parameters
-
[in] _now The current time
- Returns
- true if the update was successfull
Reimplemented from CameraSensor.
The documentation for this class was generated from the following file: