Multiple camera sensor. More...
#include <sensors/sensors.hh>
Public Member Functions | |
MultiCameraSensor () | |
Constructor. | |
virtual | ~MultiCameraSensor () |
Destructor. | |
rendering::CameraPtr | GetCamera (unsigned int _index) const |
Returns a pointer to a rendering::Camera. | |
unsigned int | GetCameraCount () const |
Get the number of cameras. | |
const unsigned char * | GetImageData (unsigned int _index) |
Gets the raw image data from the sensor. | |
unsigned int | GetImageHeight (unsigned int _index) const |
Gets the height of the image in pixels. | |
unsigned int | GetImageWidth (unsigned int _index) const |
Gets the width of the image in pixels. | |
virtual std::string | GetTopic () const |
Returns the topic name as set in SDF. | |
virtual void | Init () |
Initialize the sensor. | |
virtual bool | IsActive () |
Returns true if sensor generation is active. | |
virtual void | Load (const std::string &_worldName) |
Load the sensor with default parameters. | |
bool | SaveFrame (const std::vector< std::string > &_filenames) |
Saves the camera image(s) to the disk. | |
Public Member Functions inherited from gazebo::sensors::Sensor | |
Sensor (SensorCategory _cat) | |
Constructor. | |
virtual | ~Sensor () |
Destructor. | |
template<typename T > | |
event::ConnectionPtr | ConnectUpdated (T _subscriber) |
Connect a signal that is triggered when the sensor is updated. | |
void | DisconnectUpdated (event::ConnectionPtr &_c) |
Disconnect from a the updated signal. | |
void | FillMsg (msgs::Sensor &_msg) |
fills a msgs::Sensor message. | |
SensorCategory | GetCategory () const |
Get the category of the sensor. | |
common::Time | GetLastMeasurementTime () |
Return last measurement time. | |
common::Time | GetLastUpdateTime () |
Return last update time. | |
std::string | GetName () const |
Get name. | |
std::string | GetParentName () const |
Returns the name of the sensor parent. | |
virtual math::Pose | GetPose () const |
Get the current pose. | |
std::string | GetScopedName () const |
Get fully scoped name of the sensor. | |
std::string | GetType () const |
Get sensor type. | |
double | GetUpdateRate () |
Get the update rate of the sensor. | |
bool | GetVisualize () const |
Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF. | |
std::string | GetWorldName () const |
Returns the name of the world the sensor is in. | |
virtual void | Load (const std::string &_worldName, sdf::ElementPtr _sdf) |
Load the sensor with SDF parameters. | |
void | ResetLastUpdateTime () |
Reset the lastUpdateTime to zero. | |
virtual void | SetActive (bool _value) |
Set whether the sensor is active or not. | |
virtual void | SetParent (const std::string &_name) |
Set the parent of the sensor. | |
void | SetUpdateRate (double _hz) |
Set the update rate of the sensor. | |
void | Update (bool _force) |
Update the sensor. | |
Protected Member Functions | |
virtual void | Fini () |
Finalize the sensor. | |
virtual void | UpdateImpl (bool _force) |
This gets overwritten by derived sensor types. | |
Additional Inherited Members | |
Protected Attributes inherited from gazebo::sensors::Sensor | |
bool | active |
True if sensor generation is active. | |
std::vector< event::ConnectionPtr > | connections |
All event connections. | |
common::Time | lastMeasurementTime |
Stores last time that a sensor measurement was generated; this value must be updated within each sensor's UpdateImpl. | |
common::Time | lastUpdateTime |
Time of the last update. | |
transport::NodePtr | node |
Node for communication. | |
std::string | parentName |
Name of the parent. | |
std::vector< SensorPluginPtr > | plugins |
All the plugins for the sensor. | |
math::Pose | pose |
Pose of the sensor. | |
transport::SubscriberPtr | poseSub |
Subscribe to pose updates. | |
sdf::ElementPtr | sdf |
Pointer the the SDF element for the sensor. | |
common::Time | updatePeriod |
Desired time between updates, set indirectly by Sensor::SetUpdateRate. | |
gazebo::physics::WorldPtr | world |
Pointer to the world. | |
Multiple camera sensor.
This sensor type can create one or more synchronized cameras.
gazebo::sensors::MultiCameraSensor::MultiCameraSensor | ( | ) |
Constructor.
|
virtual |
Destructor.
|
protectedvirtual |
Finalize the sensor.
Reimplemented from gazebo::sensors::Sensor.
rendering::CameraPtr gazebo::sensors::MultiCameraSensor::GetCamera | ( | unsigned int | _index | ) | const |
Returns a pointer to a rendering::Camera.
[in] | _index | Index of the camera to get |
unsigned int gazebo::sensors::MultiCameraSensor::GetCameraCount | ( | ) | const |
Get the number of cameras.
const unsigned char* gazebo::sensors::MultiCameraSensor::GetImageData | ( | unsigned int | _index | ) |
Gets the raw image data from the sensor.
[in] | _index | Index of the camera |
unsigned int gazebo::sensors::MultiCameraSensor::GetImageHeight | ( | unsigned int | _index | ) | const |
Gets the height of the image in pixels.
[in] | _index | Index of the camera |
unsigned int gazebo::sensors::MultiCameraSensor::GetImageWidth | ( | unsigned int | _index | ) | const |
Gets the width of the image in pixels.
[in] | _index | Index of the camera |
|
virtual |
Returns the topic name as set in SDF.
Reimplemented from gazebo::sensors::Sensor.
|
virtual |
Initialize the sensor.
Reimplemented from gazebo::sensors::Sensor.
|
virtual |
Returns true if sensor generation is active.
Reimplemented from gazebo::sensors::Sensor.
|
virtual |
Load the sensor with default parameters.
[in] | _worldName | Name of world to load from. |
Reimplemented from gazebo::sensors::Sensor.
bool gazebo::sensors::MultiCameraSensor::SaveFrame | ( | const std::vector< std::string > & | _filenames | ) |
Saves the camera image(s) to the disk.
[in] | _filenames | The name of the files for each camera. |
|
protectedvirtual |
This gets overwritten by derived sensor types.
This function is called during Sensor::Update. And in turn, Sensor::Update is called by SensorManager::Update
[in] | _force | True if update is forced, false if not |
Reimplemented from gazebo::sensors::Sensor.