|
| RgbdCameraSensor () |
| constructor
|
|
virtual | ~RgbdCameraSensor () |
| destructor
|
|
virtual bool | HasColorConnections () const |
| Check if there are color subscribers.
|
|
virtual bool | HasConnections () const override |
| Check if there are any subscribers.
|
|
virtual bool | HasDepthConnections () const |
| Check if there are depth subscribers.
|
|
virtual bool | HasPointConnections () const |
| Check if there are point cloud subscribers.
|
|
virtual unsigned int | ImageHeight () const override |
| Get image height.
|
|
virtual unsigned int | ImageWidth () const override |
| Get image width.
|
|
virtual bool | Init () override |
| Initialize values in the sensor.
|
|
virtual bool | Load (const sdf::Sensor &_sdf) override |
| Load the sensor based on data from an sdf::Sensor object.
|
|
virtual bool | Load (sdf::ElementPtr _sdf) override |
| Load the sensor with SDF parameters.
|
|
virtual void | SetScene (gz::rendering::ScenePtr _scene) override |
| Set the rendering scene.
|
|
virtual bool | Update (const std::chrono::steady_clock::duration &_now) override |
| Force the sensor to generate data.
|
|
| CameraSensor () |
| constructor
|
|
virtual | ~CameraSensor () |
| destructor
|
|
double | Baseline () const |
| Get baseline for stereo cameras.
|
|
gz::common::ConnectionPtr | ConnectImageCallback (std::function< void(const gz::msgs::Image &)> _callback) |
| Set a callback to be called when image frame data is generated.
|
|
virtual bool | HasImageConnections () const |
| Check if there are any image subscribers.
|
|
virtual bool | HasInfoConnections () const |
| Check if there are any info subscribers.
|
|
std::string | InfoTopic () const |
| Topic where camera info is published.
|
|
const std::string & | OpticalFrameId () const |
| Get the camera optical frame.
|
|
virtual rendering::CameraPtr | RenderingCamera () const |
| Get pointer to rendering camera object.
|
|
void | SetBaseline (double _baseline) |
| Set baseline for stereo cameras. This is used to populate the projection matrix in the camera info message.
|
|
bool | Update (const std::chrono::steady_clock::duration &_now, const bool _force) |
| Update the sensor.
|
|
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.
|
|
virtual | ~RenderingSensor () |
| destructor
|
|
bool | ManualSceneUpdate () const |
| Get whether the scene graph is updated manually. Defaults to false.
|
|
void | Render () |
| Render update. This performs the actual render operation.
|
|
rendering::ScenePtr | Scene () const |
| Get the rendering scene.
|
|
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()
|
|
virtual void | SetScene (rendering::ScenePtr _scene) |
| Set the rendering scene.
|
|
virtual | ~Sensor () |
| destructor
|
|
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.
|
|
bool | EnableMetrics () const |
| Get flag state for enabling performance metrics publication.
|
|
std::string | FrameId () const |
| FrameId.
|
|
bool | HasPendingTrigger () const |
| Whether the sensor has a pending trigger.
|
|
SensorId | Id () const |
| Get the sensor's ID.
|
|
bool | IsActive () const |
| Get whether the sensor is enabled or not.
|
|
bool | IsTriggered () const |
| Whether the sensor trigger mode is enabled.
|
|
std::string | Name () const |
| Get name.
|
|
std::chrono::steady_clock::duration | NextDataUpdateTime () const |
| Return the next time the sensor will generate data.
|
|
std::string | Parent () const |
| Get parent link of the sensor.
|
|
gz::math::Pose3d | Pose () const |
| Get the current pose.
|
|
void | PublishMetrics (const std::chrono::duration< double > &_now) |
| Publishes information about the performance of the sensor. This method is called by Update().
|
|
sdf::ElementPtr | SDF () const |
| Get the SDF used to load this sensor.
|
|
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.
|
|
void | SetEnableMetrics (bool _enableMetrics) |
| Set flag to enable publishing performance metrics.
|
|
void | SetFrameId (const std::string &_frameId) |
| Set Frame ID of the sensor.
|
|
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.
|
|
virtual void | SetParent (const std::string &_parent) |
| Set the parent of the sensor.
|
|
void | SetPose (const gz::math::Pose3d &_pose) |
| Update the pose of the sensor.
|
|
bool | SetTopic (const std::string &_topic) |
| Set topic where sensor data is published.
|
|
bool | SetTriggered (bool _triggered, const std::string &_triggerTopic="") |
| Enable or disable triggered mode. In this mode,.
|
|
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.
|
|
std::string | Topic () const |
| Get topic where sensor data is published.
|
|
bool | Update (const std::chrono::steady_clock::duration &_now, const bool _force) |
| Update the sensor.
|
|
double | UpdateRate () const |
| Get the update rate of the sensor.
|
|
RGBD camera sensor class.
This class creates a few types of sensor data from a Gazebo Rendering scene:
- RGB image (same as CameraSensor)
- Depth image (same as DepthCamera)
- (future / todo) Color point cloud The scene must be created in advance and given to Manager::Init(). It offers both a 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.