Class GvmMulticameraSensor
Defined in File gvm_multicamera_sensor.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public Sensor
Class Documentation
-
class GvmMulticameraSensor : public Sensor
Creates multiple cameras and publishes an event with synchronized images from all of these cameras.
Note
Provides a ROS interface for dynamically updating the configuration of a camera. If a model is not specified in the request, the model/link configuration defaults to the model/link to which the sensor is attached.
Note
Expects the usual sensor configuration, but with an arbitrary number of cameras.
Public Types
-
using NewImagesFn = void(const std::vector<ImageDataPtr>&)
Public Functions
-
GvmMulticameraSensor()
-
virtual ~GvmMulticameraSensor() override
-
virtual void Load(const std::string &world_name) override
-
virtual void Init() override
-
virtual bool IsActive() const override
-
std::vector<std::string> getCameraNames() const
-
event::ConnectionPtr connectNewImages(const std::function<NewImagesFn> &callback)
-
rendering::CameraPtr getCamera(const std::string &name)
-
bool attachToLink(const std::string &camera_name, const RefModelConfig &model_config, bool on_init = false)
-
void setRecording(bool recording)
-
bool isRecording() const
Public Static Functions
-
static sensors::GvmMulticameraSensor *newSensor()
-
struct ImageData
-
using NewImagesFn = void(const std::vector<ImageDataPtr>&)