Class CameraDriverGv

Inheritance Relationships

Base Type

Class Documentation

class CameraDriverGv : public camera_aravis2::CameraDriver

Public Functions

explicit CameraDriverGv(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

Initialization constructor.

Parameters:

options[in] Node options.

virtual ~CameraDriverGv()

Default destructor.

Protected Functions

virtual bool setTechSpecificTlControlSettings() override

Method to set GigEVision specific transport layer control settings of the camera.

For example: PtpEnable, GevSCPSPacketSize…

Returns:

True if successful. False, otherwise.

virtual int discoverNumberOfStreams() override

Discover number of available camera streams.

virtual void tuneArvStream(ArvStream *p_stream) const override

Tune specific parameters for GigEVision streams.

Parameters:

p_stream[in] Pointer to Aravis Gv stream.

virtual void postFrameProcessingCallback(const uint stream_id) override

Callback method to inject short processing routines after the publication of each frame, e.g. check state of PTP.

This is called within the processing loop of processStreamBuffer.

Note

This should not hold heavy processing as it will the delay the processing of the next frame within the stream buffer.

Parameters:

stream_id[in] ID of stream for which the buffer is to be processed.

void checkPtpState()

Check the status of the Precision Time Protocol and reset its clock if applicable. * The clock will only be reset if the status of PTP is “Faulty”, “Disabled”, or “Initializing”.

Protected Attributes

std::shared_ptr<GvTransportLayerControl> p_gv_tl_control_

Pointer to Gev-Specific transport layer control settings.