Multiple camera sensor. More...
#include <sensors/sensors.hh>

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