
Public Member Functions | |
| void | Load (gazebo::sensors::SensorPtr parent, sdf::ElementPtr sdf) override |
| void | OnNewFrame (const unsigned char *image, unsigned int width, unsigned int height, unsigned int depth, const std::string &format) override |
| ThrottlingCamera ()=default | |
| ~ThrottlingCamera () override=default | |
Additional Inherited Members | |
Private Member Functions inherited from gazebo::GazeboRosCameraUtils | |
| GazeboRosCameraUtils () | |
| void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix="") |
| void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix, double _hack_baseline) |
| event::ConnectionPtr | OnLoad (const boost::function< void()> &) |
| ~GazeboRosCameraUtils () | |
| void | CameraQueueThread () |
| virtual bool | CanTriggerCamera () |
| void | ImageConnect () |
| void | ImageDisconnect () |
| void | PublishCameraInfo () |
| void | PublishCameraInfo (ros::Publisher camera_info_publisher) |
| void | PublishCameraInfo (common::Time &last_update_time) |
| void | PutCameraData (const unsigned char *_src) |
| void | PutCameraData (const unsigned char *_src, common::Time &last_update_time) |
| virtual void | TriggerCamera () |
Gazebo camera plugin for a world-throttling (rate-preserving) camera.
This plugin will slow the simulation down to maintain average publishing rate. Note that this plugin will only perform slowdown, it will not speed the simulation back up!
Definition at line 112 of file throttling_camera.cpp.
|
default |
|
overridedefault |
|
inlineoverride |
Plugin load function. Called by Gazebo each time the plugin is instantiated.
| parent | Gazebo sensor that this plugin connects to. |
| sdf | SDF element containing this plugin. |
Definition at line 137 of file throttling_camera.cpp.
|
inlineoverride |
Frame callback. Called every time a new frame is rendered by the camera.
Checks whether we should slow simulation down and publishes a new image message.
| image | Image data. |
| width | Image width, in pixels. |
| height | Image height, in pixels. |
| depth | Image depth, in bytes. |
| format | Image format description string. |
Definition at line 210 of file throttling_camera.cpp.
|
private |
A pointer to the Gazebo camera sensor.
Definition at line 116 of file throttling_camera.cpp.
|
private |
Maximum update interval that is considered "okay". Should be higher than the "average" update interval to avoid extreme slowdowns
Definition at line 123 of file throttling_camera.cpp.
|
private |
A pointer to the physics preset manager. Used to actually slow the simulation down.
Definition at line 120 of file throttling_camera.cpp.
|
private |
Statistics for publishing time intervals.
Definition at line 126 of file throttling_camera.cpp.
|
private |
A pointer to the current simulated world (required to change world parameters)
Definition at line 118 of file throttling_camera.cpp.