Class CameraDriverGv

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class CameraDriverGv : public camera_aravis2::CameraAravisNodeBase

Public Functions

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

Initialization constructor.

Parameters:

options[in] Node options.

virtual ~CameraDriverGv()

Default destructor.

bool isSpawningOrInitialized() const

Returns true, if node is spawning or is initialized. False, otherwise.

Protected Functions

virtual void setUpParameters() override

Set up the launch parameters.

bool setUpCameraStreamStructs()

Set up camera stream structs. Here, the number of streams available are discovered, and user settings are read from launch parameters and are used to set up structs. This also involves the logic of how to handle faults of inconsistent number of stream_names, pixel_formats, and camera_info settings.

Returns:

True if successful. False, otherwise.

bool getDeviceControlParameterList(const std::string &param_name, std::vector<std::pair<std::string, rclcpp::ParameterValue>> &param_values) const

Get list of parameters underneath ‘param_name’ within the list of device control parameters.

Parameters:
  • param_name[in] Name of the nested parameter within device control. The method will prepend ‘DeviceControl.’ to the parameter prior to the search.

  • param_values[out] List of parameter values associated with feature names.

Returns:

True if parameter is found in ‘parameter_overrides_’ and, thus, given by the user. False otherwise.

bool setDeviceControlSettings()

Set device control settings of the camera.

For example: DeviceLinkThroughputLimit …

Returns:

True if successful. False, otherwise.

bool getTransportLayerControlParameter(const std::string &param_name, rclcpp::ParameterValue &param_value) const

Get parameter with ‘param_name’ within the list of transport layer control parameters.

Parameters:
  • param_name[in] Name of the nested parameter within transport layer control. The method will prepend ‘TransportLayerControl.’ to the parameter prior to the search.

  • param_value[out] Parameter value.

Returns:

True if parameter is found in ‘parameter_overrides_’ and, thus, given by the user. False otherwise.

bool getTransportLayerControlParameterList(const std::string &param_name, std::vector<std::pair<std::string, rclcpp::ParameterValue>> &param_values) const

Get list of parameters underneath ‘param_name’ within the list of transport layer control parameters.

Parameters:
  • param_name[in] Name of the nested parameter within transport layer control. The method will prepend ‘TransportLayerControl.’ to the parameter prior to the search.

  • param_values[out] List of parameter values associated with feature names.

Returns:

True if parameter is found in ‘parameter_overrides_’ and, thus, given by the user. False otherwise.

bool setTransportLayerControlSettings()

Set transport layer control settings of the camera.

For example: PtpEnable, GevSCPSPacketSize …

Returns:

True if successful. False, otherwise.

bool getImageFormatControlParameter(const std::string &param_name, rclcpp::ParameterValue &param_value) const

Get parameter with ‘param_name’ within the list of image format control parameters.

Parameters:
  • param_name[in] Name of the nested parameter within image format control. The method will prepend ‘ImageFormatControl.’ to the parameter prior to the search.

  • param_value[out] Parameter value.

Returns:

True if parameter is found in ‘parameter_overrides_’ and, thus, given by the user. False otherwise.

bool getImageFormatControlParameterList(const std::string &param_name, std::vector<std::pair<std::string, rclcpp::ParameterValue>> &param_values) const

Get list of parameters underneath ‘param_name’ within the list of image format control parameters.

Parameters:
  • param_name[in] Name of the nested parameter within image format control. The method will prepend ‘ImageFormatControl.’ to the parameter prior to the search.

  • param_values[out] List of parameter values associated with feature names.

Returns:

True if parameter is found in ‘parameter_overrides_’ and, thus, given by the user. False otherwise.

bool setImageFormatControlSettings()

Set image format control settings of the camera.

For example: Pixel Format, Image Size, Image Offset …

Returns:

True if successful. False, otherwise.

bool getAcquisitionControlParameter(const std::string &param_name, rclcpp::ParameterValue &param_value) const

Get parameter with ‘parameter_name’ within the list of acquisition control parameters.

Parameters:
  • param_name[in] Name of the nested parameter within acquisition control. The method will prepend ‘AcquisitionControl.’ to the parameter prior to the search.

  • param_value[out] Parameter value.

Returns:

True if parameter is found in ‘parameter_overrides_’ and, thus, given by the user. False otherwise.

bool getAcquisitionControlParameterList(const std::string &param_name, std::vector<std::pair<std::string, rclcpp::ParameterValue>> &param_values) const

Get list of parameters underneath ‘param_name’ within the list of acquisition control parameters.

Parameters:
  • param_name[in] Name of the nested parameter within acquisition control. The method will prepend ‘AcquisitionControl.’ to the parameter prior to the search.

  • param_values[out] List of parameter values associated with feature names.

Returns:

True if parameter is found in ‘parameter_overrides_’ and, thus, given by the user. False otherwise.

bool setAcquisitionControlSettings()

Set acquisition control settings of the camera.

Returns:

True if successful. False, otherwise.

bool getAnalogControlParameter(const std::string &param_name, rclcpp::ParameterValue &param_value) const

Get parameter with ‘parameter_name’ within the list of analog control parameters.

Parameters:
  • param_name[in] Name of the nested parameter within analog control. The method will prepend ‘AnalogControl.’ to the parameter prior to the search.

  • param_value[out] Parameter value.

Returns:

True if parameter is found in ‘parameter_overrides_’ and, thus, given by the user. False otherwise.

bool getAnalogControlParameterList(const std::string &param_name, std::vector<std::pair<std::string, rclcpp::ParameterValue>> &param_values) const

Get list of parameters underneath ‘param_name’ within the list of analog control parameters.

Parameters:
  • param_name[in] Name of the nested parameter within analog control. The method will prepend ‘AnalogControl.’ to the parameter prior to the search.

  • param_values[out] List of parameter values associated with feature names.

Returns:

True if parameter is found in ‘parameter_overrides_’ and, thus, given by the user. False otherwise.

bool setAnalogControlSettings()

Set analog control settings of the camera.

Returns:

True if successful. False, otherwise.

int discoverNumberOfStreams()

Discover number of available camera streams.

void spawnCameraStreams()

Spawn camera streams.

void tuneGvStream(ArvGvStream *p_stream) const

Tune specific parameters for GigEVision streams.

Parameters:

p_stream[in] Pointer to Aravis Gv stream.

void setUpCameraDiagnosticPublisher()

Set up publisher for camera diagnostics.

In this, the YAML file configuring the diagnostics which are to be published is read and parsed.

void publishCameraDiagnosticsLoop(double rate) const

Read and publish camera diagnostics.

This runs in a separate thread and loops at the given rate to read the stats from the camera and published them on hte appropriate topic.

void checkPtp()

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”.

void processStreamBuffer(const uint stream_id)

Process available stream buffer.

Parameters:

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

bool adjustImageRoi(ImageRoi &img_roi, ArvBuffer *p_buffer) const

Adjust image roi to actual image size stored in the buffer.

Parameters:
  • img_roi[inout] Image ROI.

  • p_buffer[in] Pointer to image buffer.

Returns:

True, if roi needed adjustment. False, otherwise.

void fillImageMsgMetadata(sensor_msgs::msg::Image::SharedPtr &p_img_msg, ArvBuffer *p_buffer, const Sensor &sensor, const ImageRoi &img_roi) const

Set metadata to image message.

Parameters:
  • p_img_msg[inout] Pointer to image message.

  • p_buffer[in] Pointer to aravis buffer holding the pixel data.

  • sensor[in] Sensor object corresponding to image. Used to set frame_id, image_encoding, and more.

  • img_roi[in] Image ROI.

void fillCameraInfoMsg(Stream &stream, const sensor_msgs::msg::Image::SharedPtr &p_img_msg) const

Fill camera_info message.

Parameters:
  • stream[inout] Stream object which holds camera_info message and other data.

  • p_img_msg[in] Pointer to corresponding image message.

void printCameraConfiguration() const

Print currently applied camera configuration.

void printStreamStatistics() const

Print stream statistics, such as completed and failed buffers.

Protected Attributes

TransportLayerControl tl_control_

Transport layer control settings.

std::vector<Stream> streams_

List of camera streams.

std::atomic<bool> is_spawning_

Atomic flag, indicating if streams are being spawned.

std::thread spawn_stream_thread_

Thread in which the streams are spawned.

std::atomic<bool> is_diagnostics_published_

Atomic flag, indicating if diagnostics are published.

std::thread diagnostic_thread_

Thead in which the publishing of the camera diagnostics runs.

rclcpp::Publisher<camera_aravis2_msgs::msg::CameraDiagnostics>::SharedPtr p_diagnostic_pub_

Pointer to publisher for camera diagnostics.

int current_num_subscribers_

Number of subscribers currently connected to the message topic.

YAML::Node diagnostic_features_

YAML node holding diagnostic features.

std::vector<std::shared_ptr<std::pair<CameraDriverGv*, uint>>> new_buffer_cb_data_ptrs

List of pointers to data pair for the new-buffer callback.

std::vector<std::string> config_warn_msgs_

Message strings to warn the user of inconsistencies at summary output.

Protected Static Functions

static void handleNewBufferSignal(ArvStream *p_stream, gpointer p_user_data)

Handle ‘new-buffer’ signal emitted by aravis, notifying that a new buffer is ready.

Parameters:
  • p_device[in] Pointer to aravis device.

  • p_user_data[in] Pointer to associated user data.