Class CameraDriver

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Derived Types

Class Documentation

class CameraDriver : public camera_aravis2::CameraAravisNodeBase

Subclassed by camera_aravis2::CameraDriverGv, camera_aravis2::CameraDriverUv

Public Functions

explicit CameraDriver(const std::string &name, const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

Initialization constructor.

Parameters:
  • name[in] Node name.

  • options[in] Node options.

virtual ~CameraDriver()

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.

virtual bool setTechSpecificTlControlSettings() = 0

Virtual method definition to set technology specific transport layer control settings of the camera.

For example PtpEnable or GevSCPSPacketSize, in case of GigEVision Cameras.

This is called within setTransportLayerControlSettings and needs implementation in subclasses.

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.

bool initializeServices()

Method to initialize service servers.

Returns:

True if successful. False, otherwise.

virtual int discoverNumberOfStreams() = 0

Discover number of available camera streams.

virtual void tuneArvStream(ArvStream *p_stream) const = 0

Tune specific parameters for Aravis streams.

Parameters:

p_stream[in] Pointer to Aravis stream.

void setupDynamicParameters()

Load and set up dynamic parameters.

This will read the yaml file (if specified) which holds the parameters that are to be made dynamically changeable and declare them.

rcl_interfaces::msg::SetParametersResult handleDynamicParameterChange(const std::vector<rclcpp::Parameter> &iParameters)

Handle dynamic change of parameters. For example, through rqt_reconfigure.

This loops through the list of parameters in iParameters and sets their value accordingly.

Parameters:

iParameters[in] Parameters that have changed.

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 spawnCameraStreams()

Spawn camera streams.

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(CameraDriver::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.

virtual void postFrameProcessingCallback(const uint stream_id) = 0

Pure virtual callback method to inject short processing routines after the publication of each frame.

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 printCameraConfiguration() const

Print currently applied camera configuration.

void printStreamStatistics() const

Print stream statistics, such as completed and failed buffers.

void onCalculateWhiteBalanceOnceTriggered(const std::shared_ptr<camera_aravis2_msgs::srv::CalculateWhiteBalance::Request> req, std::shared_ptr<camera_aravis2_msgs::srv::CalculateWhiteBalance::Response> res) const

Service callback method to calculate white balance once.

Parameters:
  • req[in] Service request

  • res[out] Service response

Protected Attributes

std::shared_ptr<GenTransportLayerControl> p_tl_control_

Pointer to transport layer control settings.

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

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

std::vector<CameraDriver::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.

rclcpp::Service<camera_aravis2_msgs::srv::CalculateWhiteBalance>::SharedPtr p_white_balance_srv_

Service to calculate white balance.

OnSetParametersCallbackHandle::SharedPtr p_parameter_callback_handle_

Callback handle to adjust parameters.

std::vector<std::string> dynamic_parameters_names_

List of the specified dynamic parameter names.

std::atomic<bool> is_diagnostics_published_

Atomic flag, indicating if diagnostics are published.

std::thread diagnostic_thread_

Thread 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::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.

struct Stream

Struct implementing camera stream.

Public Functions

inline Stream()

Default constructor.

Public Members

ArvStream *p_arv_stream

Pointer to aravis stream.

ImageBufferPool::SharedPtr p_buffer_pool

Shared pointer to buffer pool.

std::string name

Name of stream.

Sensor sensor

Sensor associated with the stream.

ImageRoi image_roi

Image region associated with the stream.

AcquisitionControl acquisition_control

Control settings for image acquisition.

AnalogControl analog_control

Control settings for analog control.

std::string camera_info_url

URL to camera info yaml file.

ConversionFunction cvt_pixel_format

Conversion function to convert pixel format from sensor into image message.

image_transport::CameraPublisher camera_pub

Camera publisher.

std::unique_ptr<camera_info_manager::CameraInfoManager> p_camera_info_manager

Unique pointer to camera info manager.

sensor_msgs::msg::CameraInfo::SharedPtr p_cam_info_msg

Pointer to camera_info message.

bool is_buffer_processed

Flag controlling processing of buffer data.

std::thread buffer_processing_thread

Thread to process ready stream buffer.

ConcurrentQueue<std::pair<ArvBuffer*, sensor_msgs::msg::Image::SharedPtr>> buffer_queue

Concurrent queue holding the buffer data to be processed in a separate thread.