BoundingBox camera sensor class. More...
#include <BoundingBoxCameraSensor.hh>
Public Member Functions | |
BoundingBoxCameraSensor () | |
constructor More... | |
virtual | ~BoundingBoxCameraSensor () |
destructor More... | |
virtual rendering::BoundingBoxCameraPtr | BoundingBoxCamera () const |
Get the rendering BoundingBox camera. More... | |
virtual bool | HasConnections () const override |
Check if there are any subscribers. 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 | OnNewBoundingBoxes (const std::vector< rendering::BoundingBox > &_boxes) |
Callback on new bounding boxes from bounding boxes camera. More... | |
virtual void | SetScene (rendering::ScenePtr _scene) override |
Set the rendering scene. More... | |
virtual bool | Update (const std::chrono::steady_clock::duration &_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... | |
virtual bool | HasImageConnections () const |
Check if there are any image subscribers. More... | |
virtual bool | HasInfoConnections () const |
Check if there are any info subscribers. More... | |
std::string | InfoTopic () const |
Topic where camera info is published. More... | |
const std::string & | OpticalFrameId () const |
Get the camera optical frame. More... | |
virtual 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... | |
virtual void | SetScene (gz::rendering::ScenePtr _scene) override |
Set the rendering scene. More... | |
virtual bool | Update (const std::chrono::steady_clock::duration &_now)=0 |
Force the sensor to generate data. More... | |
bool | Update (const std::chrono::steady_clock::duration &_now, const bool _force) |
Update the sensor. More... | |
void | UpdateLensIntrinsicsAndProjection (rendering::CameraPtr _camera, sdf::Camera &_cameraSdf) |
Set camera lens intrinsics and projection based on values from SDF. If the camera SDF does not contain intrinsic or projection parameters, the camera will not be updated. Instead, the camera SDF will be updated with intrinsic and projection values computed manually from current camera intrinsic properties. 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... | |
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 a 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... | |
bool | HasPendingTrigger () const |
Whether the sensor has a pending trigger. More... | |
SensorId | Id () const |
Get the sensor's ID. More... | |
bool | IsActive () const |
Get whether the sensor is enabled or not. More... | |
bool | IsTriggered () const |
Whether the sensor trigger mode is enabled. More... | |
std::string | Name () const |
Get name. More... | |
std::chrono::steady_clock::duration | NextDataUpdateTime () 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 | SetActive (bool _active) |
Enable or disable the sensor. Disabled sensors will not generate or publish data unless Update is called with the '_force' argument set to true. 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... | |
void | SetNextDataUpdateTime (const std::chrono::steady_clock::duration &_time) |
Manually set the next time the sensor will generate data Useful for accomodating jumps backwards in time as well as specifying updates for non-uniformly updating sensors. 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... | |
bool | SetTriggered (bool _triggered, const std::string &_triggerTopic="") |
Enable or disable triggered mode. In this mode,. 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. More... | |
std::string | Topic () const |
Get topic where sensor data is published. More... | |
bool | Update (const std::chrono::steady_clock::duration &_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 std::chrono::steady_clock::duration &_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
BoundingBox camera sensor class.
This class creates a BoundingBox image from an gz rendering scene. The scene must be created in advance and given to Manager::Init(). It offers both an gz-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
◆ BoundingBoxCameraSensor()
constructor
◆ ~BoundingBoxCameraSensor()
|
virtual |
destructor
Member Function Documentation
◆ BoundingBoxCamera()
|
virtual |
Get the rendering BoundingBox camera.
- Returns
- BoundingBox camera pointer
◆ HasConnections()
|
overridevirtual |
Check if there are any subscribers.
- Returns
- True if there are subscribers, false otherwise
Reimplemented from CameraSensor.
◆ 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.
◆ OnNewBoundingBoxes()
void OnNewBoundingBoxes | ( | const std::vector< rendering::BoundingBox > & | _boxes | ) |
Callback on new bounding boxes from bounding boxes camera.
- Parameters
-
[in] _boxes Detected bounding boxes from the camera
◆ SetScene()
|
overridevirtual |
Set the rendering scene.
- Parameters
-
[in] _scene Pointer to the scene
Reimplemented from RenderingSensor.
◆ Update()
|
overridevirtual |
Force the sensor to generate data.
- Parameters
-
[in] _now The current time
- Returns
- true if the update was successful
Reimplemented from CameraSensor.
The documentation for this class was generated from the following file: