A custom gazebo plugin that provides an interface to programatically collect data from cameras at specific times. More...
#include <CameraUtils.hh>
Public Member Functions | |
CameraUtils () | |
Constructs the object. More... | |
virtual | ~CameraUtils () |
Destroys the object. More... | |
virtual void | Load (sensors::SensorPtr _sensor, sdf::ElementPtr _sdf) |
Loads the object. More... | |
void | OnNewFrame (const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) |
Callback function for handling frame updates. More... | |
Protected Attributes | |
sensors::CameraSensorPtr | parentSensor |
Pointer to camera sensor. More... | |
rendering::CameraPtr | camera |
Pointer to camera object. More... | |
unsigned int | width |
Image width. More... | |
unsigned int | height |
Image height. More... | |
unsigned int | depth |
Image depth. More... | |
std::string | format |
Image format. More... | |
std::string | extension |
Exported image extension. More... | |
Private Member Functions | |
void | onRequest (CameraUtilsRequestPtr &_msg) |
Callback function for handling incoming requests. More... | |
Private Attributes | |
std::unique_ptr< CameraUtilsPrivate > | dataPtr |
Class with private attributes. More... | |
std::string | output_dir |
Directory for saving output. More... | |
int | saved_counter {0} |
Saved frames counter. More... | |
std::string | next_file_name |
File name for next capture. More... | |
bool | save_on_update {false} |
Internal flag for saving on next update. More... | |
event::ConnectionPtr | newFrameConnection |
Connects to new frame rendered event. More... | |
A custom gazebo plugin that provides an interface to programatically collect data from cameras at specific times.
See the example usage below:
See worlds/camera.world for a complete example.
CameraUtils | ( | ) |
Constructs the object.
|
virtual |
Destroys the object.
|
virtual |
Loads the object.
_sensor | The camera sensor to which the plugin is attached |
_sdf | The SDF element with plugin parameters |
void OnNewFrame | ( | const unsigned char * | _image, |
unsigned int | _width, | ||
unsigned int | _height, | ||
unsigned int | _depth, | ||
const std::string & | _format | ||
) |
Callback function for handling frame updates.
_image | Image data |
_width | Image width |
_height | Image height |
_depth | Image depth |
_format | Image format |
|
private |
Callback function for handling incoming requests.
_msg | The message |
|
protected |
Pointer to camera object.
|
private |
Class with private attributes.
|
protected |
Image depth.
|
protected |
Exported image extension.
|
protected |
Image format.
|
protected |
Image height.
|
private |
Connects to new frame rendered event.
|
private |
File name for next capture.
|
private |
Directory for saving output.
|
protected |
Pointer to camera sensor.
|
private |
Internal flag for saving on next update.
|
private |
Saved frames counter.
|
protected |
Image width.