Class StCameraInterfaceImpl

Inheritance Relationships

Base Type

Class Documentation

class StCameraInterfaceImpl : public stcamera::StCameraInterface

Class to control a connected camera.

This class is specific for camera. If there is a more specific camera to control, derive this class.

Public Functions

StCameraInterfaceImpl(StApi::IStDeviceReleasable *dev, rclcpp::Node *nh_parent, const std::string &camera_namespace, StParameter *param, rclcpp::Clock &clock, uint32_t queue_size = STCAMERA_QUEUE_SIZE)

Constructor.

Parameters:
  • dev[in] Pointer to the IStDeviceReleasable of the device.

  • nh_parent[in] The main ROS node handle.

  • camera_namespace[in] The namespace for the device.

  • param[in] Pointer to the StParameter class instance.

  • queue_size[in] Used for initializing publisher (Maximum number of outgoing messages to be queued for delivery to subscribers). Default is set to STCAMERA_QUEUE_SIZE

virtual ~StCameraInterfaceImpl()

Destructor.

All event node callbacks are deregistered and the callbacks are released here.

virtual bool deviceIsLost() override

Check if the device is disconnected.

Returns:

True if device is already disconnected. False otherwise.

Protected Functions

void initDeviceAndDataStream()
void registerDeviceLostEvent()
void activateChunks()
void eventSystemCB(StApi::IStCallbackParamBase *p, void *pvContext)

GenTL System event callback function.

This function is called automatically when any GenTL System event occured.

Parameters:
  • p[in] Pointer to the callback handle.

  • pvContext[in] user’s pointer (not used).

void eventInterfaceCB(StApi::IStCallbackParamBase *p, void *pvContext)

GenTL Interface event callback function.

This function is called automatically when any GenTL Interface event occured. The event data is published through the default event topic.

Parameters:
  • p[in] Pointer to the callback handle.

  • pvContext[in] user’s pointer (not used).

void eventDeviceCB(StApi::IStCallbackParamBase *p, void *pvContext)

GenTL Device event callback function.

This function is called automatically when any GenTL Device event occured. The event data is published through the default event topic.

Parameters:
  • p[in] Pointer to the callback handle.

  • pvContext[in] user’s pointer (not used).

void eventGenApiNodeCB(GenApi::INode *p, void *pvContext)

GenICam node event callback function.

This function is called automatically if a GenICam node event is registered. The event data is published through either the custom event topic provided when enabling the event or the default event topic.

Parameters:
  • p[in] Pointer to the GenICam node callback.

  • pvContext[in] user’s pointer (pointer to the MapCallback of which the event belongs to)

void eventDataStreamCB(StApi::IStCallbackParamBase *p, void *pvContext)

GenTL DataStream event callback function.

This function is called automatically when any GenTL DataStream event occured. Except for GenTL EVENT_NEW_BUFFER of which data is published throught image_transport mechanism or chunk topic, other event data is published through the default event topic.

Parameters:
  • p[in] Pointer to the callback handle.

  • pvContext[in] user’s pointer (not used).

bool readNodeCallback(const std::shared_ptr<stcamera_msgs::srv::ReadNode_Request> req, std::shared_ptr<stcamera_msgs::srv::ReadNode_Response> res)

ROS service callback for obtaining GenICam node value regardless the node value’s interface type.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool readNodeBoolCallback(const std::shared_ptr<stcamera_msgs::srv::ReadNodeBool_Request> req, std::shared_ptr<stcamera_msgs::srv::ReadNodeBool_Response> res)

ROS service callback for obtaining GenICam node value with boolean interface type.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool readNodeEnumCallback(const std::shared_ptr<stcamera_msgs::srv::ReadNodeEnum_Request> req, std::shared_ptr<stcamera_msgs::srv::ReadNodeEnum_Response> res)

ROS service callback for obtaining GenICam node value with enumeration interface type.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool readNodeIntCallback(const std::shared_ptr<stcamera_msgs::srv::ReadNodeInt_Request> req, std::shared_ptr<stcamera_msgs::srv::ReadNodeInt_Response> res)

ROS service callback for obtaining GenICam node value with integer interface type.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool readNodeFloatCallback(const std::shared_ptr<stcamera_msgs::srv::ReadNodeFloat_Request> req, std::shared_ptr<stcamera_msgs::srv::ReadNodeFloat_Response> res)

ROS service callback for obtaining GenICam node value with float interface type.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool readNodePortCallback(const std::shared_ptr<stcamera_msgs::srv::ReadNodePort_Request> req, std::shared_ptr<stcamera_msgs::srv::ReadNodePort_Response> res)

ROS service callback for obtaining GenICam node value with port interface type.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool readNodeRegisterCallback(const std::shared_ptr<stcamera_msgs::srv::ReadNodeRegister_Request> req, std::shared_ptr<stcamera_msgs::srv::ReadNodeRegister_Response> res)

ROS service callback for obtaining GenICam node value with register interface type.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool readNodeRegisterInfoCallback(const std::shared_ptr<stcamera_msgs::srv::ReadNodeRegisterInfo_Request> req, std::shared_ptr<stcamera_msgs::srv::ReadNodeRegisterInfo_Response> res)

ROS service callback for obtaining GenICam node info with register interface type.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool readNodeStringCallback(const std::shared_ptr<stcamera_msgs::srv::ReadNodeString_Request> req, std::shared_ptr<stcamera_msgs::srv::ReadNodeString_Response> res)

ROS service callback for obtaining GenICam node value with string interface type.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool writeNodeCallback(const std::shared_ptr<stcamera_msgs::srv::WriteNode_Request> req, std::shared_ptr<stcamera_msgs::srv::WriteNode_Response> res)

ROS service callback for writing GenICam node value regardless the node value’s interface type.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool writeNodeBoolCallback(const std::shared_ptr<stcamera_msgs::srv::WriteNodeBool_Request> req, std::shared_ptr<stcamera_msgs::srv::WriteNodeBool_Response> res)

ROS service callback for writing GenICam node value with boolean interface type.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool writeNodeEnumIntCallback(const std::shared_ptr<stcamera_msgs::srv::WriteNodeEnumInt_Request> req, std::shared_ptr<stcamera_msgs::srv::WriteNodeEnumInt_Response> res)

ROS service callback for writing GenICam node value with enumeration interface type, where the input is the integer value of the enumeration entry.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool writeNodeEnumStrCallback(const std::shared_ptr<stcamera_msgs::srv::WriteNodeEnumStr_Request> req, std::shared_ptr<stcamera_msgs::srv::WriteNodeEnumStr_Response> res)

ROS service callback for writing GenICam node value with enumeration interface type, where the input is the symbolic name of the enumeration entry.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool writeNodeIntCallback(const std::shared_ptr<stcamera_msgs::srv::WriteNodeInt_Request> req, std::shared_ptr<stcamera_msgs::srv::WriteNodeInt_Response> res)

ROS service callback for writing GenICam node value with integer interface type.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool writeNodeFloatCallback(const std::shared_ptr<stcamera_msgs::srv::WriteNodeFloat_Request> req, std::shared_ptr<stcamera_msgs::srv::WriteNodeFloat_Response> res)

ROS service callback for writing GenICam node value with float interface type.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool writeNodePortCallback(const std::shared_ptr<stcamera_msgs::srv::WriteNodePort_Request> req, std::shared_ptr<stcamera_msgs::srv::WriteNodePort_Response> res)

ROS service callback for writing GenICam node value with port interface type.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool writeNodeRegisterCallback(const std::shared_ptr<stcamera_msgs::srv::WriteNodeRegister_Request> req, std::shared_ptr<stcamera_msgs::srv::WriteNodeRegister_Response> res)

ROS service callback for writing GenICam node value with register interface type.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool writeNodeStringCallback(const std::shared_ptr<stcamera_msgs::srv::WriteNodeString_Request> req, std::shared_ptr<stcamera_msgs::srv::WriteNodeString_Response> res)

ROS service callback for writing GenICam node value with string interface type.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool executeNodeCallback(const std::shared_ptr<stcamera_msgs::srv::ExecuteNode_Request> req, std::shared_ptr<stcamera_msgs::srv::ExecuteNode_Response> res)

ROS service callback for executing GenICam node that has command interface type.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool enableChunkCallback(const std::shared_ptr<stcamera_msgs::srv::EnableChunk_Request> req, std::shared_ptr<stcamera_msgs::srv::EnableChunk_Response> res)

ROS service callback for enabling or disabling chunk.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool enableTriggerCallback(const std::shared_ptr<stcamera_msgs::srv::EnableTrigger_Request> req, std::shared_ptr<stcamera_msgs::srv::EnableTrigger_Response> res)

ROS service callback for enabling or disabling trigger.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool enableEventNodeCallback(const std::shared_ptr<stcamera_msgs::srv::EnableEventNode_Request> req, std::shared_ptr<stcamera_msgs::srv::EnableEventNode_Response> res)

ROS service callback for enabling or disabling GenICam event.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool enableImageAcquisitionCallback(const std::shared_ptr<stcamera_msgs::srv::EnableImageAcquisition_Request> req, std::shared_ptr<stcamera_msgs::srv::EnableImageAcquisition_Response> res)

ROS service callback for enabling or disabling image acquisition.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool enableEventAcquisitionCallback(const std::shared_ptr<stcamera_msgs::srv::EnableEventAcquisition_Request> req, std::shared_ptr<stcamera_msgs::srv::EnableEventAcquisition_Response> res)

ROS service callback for enabling or disabling event acquisition.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool getImageAcquisitionStatusCallback(const std::shared_ptr<stcamera_msgs::srv::GetImageAcquisitionStatus_Request> req, std::shared_ptr<stcamera_msgs::srv::GetImageAcquisitionStatus_Response> res)

ROS service callback for obtaining image acquisition status.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool getEventAcquisitionStatusListCallback(const std::shared_ptr<stcamera_msgs::srv::GetEventAcquisitionStatusList_Request> req, std::shared_ptr<stcamera_msgs::srv::GetEventAcquisitionStatusList_Response> res)

ROS service callback for obtaining event acquisition status.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool getEventNodeStatusListCallback(const std::shared_ptr<stcamera_msgs::srv::GetEventNodeStatusList_Request> req, std::shared_ptr<stcamera_msgs::srv::GetEventNodeStatusList_Response> res)

ROS service callback for obtaining GenICam node events status.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool getChunkListCallback(const std::shared_ptr<stcamera_msgs::srv::GetChunkList_Request> req, std::shared_ptr<stcamera_msgs::srv::GetChunkList_Response> res)

ROS service callback for obtaining chunks provided by the camera.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool getTriggerListCallback(const std::shared_ptr<stcamera_msgs::srv::GetTriggerList_Request> req, std::shared_ptr<stcamera_msgs::srv::GetTriggerList_Response> res)

ROS service callback for obtaining triggers provided by the camera.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool getEnumListCallback(const std::shared_ptr<stcamera_msgs::srv::GetEnumList_Request> req, std::shared_ptr<stcamera_msgs::srv::GetEnumList_Response> res)

ROS service callback for obtaining enumeration entry of a given GenICam node with interface type of enumeration.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool getGenICamNodeInfoCallback(const std::shared_ptr<stcamera_msgs::srv::GetGenICamNodeInfo_Request> req, std::shared_ptr<stcamera_msgs::srv::GetGenICamNodeInfo_Response> res)

ROS service callback for obtaining information of a given GenICam node.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

bool sendSoftTriggerCallback(const std::shared_ptr<stcamera_msgs::srv::SendSoftTrigger_Request> req, std::shared_ptr<stcamera_msgs::srv::SendSoftTrigger_Response> res)

ROS service callback for sending software trigger execution command to the camera.

Parameters:
  • req[in] ROS service request

  • res[out] ROS service response

Returns:

true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

void initializeCameraInfo()

Initialize information of the camera. This information is delivered to image subscribers upon publishing acquired images.

GenApi::INodeMap *getNodeMap(const std::string &genicam_module)

A helper function to obtain the GenICam node for a given module name.

Parameters:

genicam_module[in] Name of the module: System, Interface, LocalDevice, RemoteDevice, DataStream.

Returns:

nullptr if module name is invalid. Otherwise GenICam node of the module.

MapCallback *getCallbackMap(const std::string &genicam_module)

A helper function to obtain one of event callback mapping for a given module name.

Parameters:

genicam_module[in] Name of the module: System, Interface, LocalDevice, RemoteDevice, DataStream.

Returns:

nullptr if module name is invalid. Otherwise the callback map that corresponds to the module.

void publishEventDefault(stcamera_msgs::msg::Event &msg)

A helper function to publish an event through the default event publisher.

Parameters:

msg[in] The message to deliver.

void initPublishers()
void initServices()

Protected Attributes

StApi::CIStDevicePtr tl_dev_

Smart pointer to the CIStDevice that holds the device instance.

camera_info_manager::CameraInfoManager camera_info_manager_

Used for managing the camera info.

const uint32_t queue_size_

Queue size for publisher (used when dynamically advertise custom topic name).

bool bool_event_system_

Flag to indicate if GenTL System event is being enabled or not.

bool bool_event_interface_

Flag to indicate if GenTL Interface event is being enabled or not.

bool bool_event_device_

Flag to indicate if GenTL Device event is being enabled or not.

bool bool_event_datastream_

Flag to indicate if GenTL DataStream event is being enabled or not.

bool destroyed_

destroyed

StApi::CIStRegisteredCallbackPtr ist_registered_callback_system_
StApi::CIStRegisteredCallbackPtr ist_registered_callback_interface_
StApi::CIStRegisteredCallbackPtr ist_registered_callback_device_
StApi::CIStRegisteredCallbackPtr ist_registered_callback_datastream_
image_transport::CameraPublisher it_campub_

Publisher for image data.

StApi::CIStDataStreamPtr tl_ds_

Smart pointer to the CIStDataStream that holds the device’s datastream.

rclcpp::Publisher<stcamera_msgs::msg::Event>::SharedPtr def_event_
rclcpp::Publisher<stcamera_msgs::msg::Chunk>::SharedPtr msg_chunk_

Publisher for chunk data.

std::mutex mtx_acquisition_

Guard to prevent race when enabling or disabling image acquisition.

bool bool_acquisition_is_started_

Flag to indicate if image acquisition is being enabled or not.

std::mutex mtx_event_

Guard to prevent race when enabling or disabling event acquisition.

MapPublisher map_msg_event_

Map of event publisher in pair of (topic name, publisher).

MapCallback map_event_system_

Map the GenICam event node callback name (System module) with the StCallback_t (pair of topic/event name and the pointer to the callback instance.

MapCallback map_event_interface_

Map the GenICam event node callback name (Interface module) with the StCallback_t (pair of topic/event name and the pointer to the callback instance.

MapCallback map_event_localdevice_

Map the GenICam event node callback name (LocalDevice module) with the StCallback_t (pair of topic name/event and the pointer to the callback instance.

MapCallback map_event_remotedevice_

Map the GenICam event node callback name (RemoteDevice module) with the StCallback_t (pair of topic/event name and the pointer to the callback instance.

MapCallback map_event_datastream_

Map the GenICam event node callback name (DataStream module) with the StCallback_t (pair of topic/event name and the pointer to the callback instance.

std::mutex mtx_chunk_

Guard to prevent race when enabling or disabling chunk.

MapChunk map_chunk_

Map the chunk name with the chunk’s GenICam node

CImageAllocator image_allocator_
StApi::CIStImageBufferPtr p_stimage_buffer_
StApi::CIStPixelFormatConverterPtr p_stpixel_format_converter_
sensor_msgs::msg::CameraInfo camera_info_
rclcpp::Service<stcamera_msgs::srv::ReadNode>::SharedPtr srv_read_node_

Server for read_node

rclcpp::Service<stcamera_msgs::srv::ReadNodeBool>::SharedPtr srv_read_node_bool_

Server for read_node_bool

rclcpp::Service<stcamera_msgs::srv::ReadNodeEnum>::SharedPtr srv_read_node_enum_

Server for read_node_enum

rclcpp::Service<stcamera_msgs::srv::ReadNodeInt>::SharedPtr srv_read_node_int_

Server for read_node_int

rclcpp::Service<stcamera_msgs::srv::ReadNodeFloat>::SharedPtr srv_read_node_float_

Server for read_node_float

rclcpp::Service<stcamera_msgs::srv::ReadNodePort>::SharedPtr srv_read_node_port_

Server for read_node_port

rclcpp::Service<stcamera_msgs::srv::ReadNodeRegister>::SharedPtr srv_read_node_register_

Server for read_node_register

rclcpp::Service<stcamera_msgs::srv::ReadNodeRegisterInfo>::SharedPtr srv_read_node_register_info_

Server for read_node_register_info

rclcpp::Service<stcamera_msgs::srv::ReadNodeString>::SharedPtr srv_read_node_string_

Server for read_node_string

rclcpp::Service<stcamera_msgs::srv::WriteNode>::SharedPtr srv_write_node_

Server for write_node

rclcpp::Service<stcamera_msgs::srv::WriteNodeBool>::SharedPtr srv_write_node_bool_

Server for write_node_bool

rclcpp::Service<stcamera_msgs::srv::WriteNodeEnumInt>::SharedPtr srv_write_node_enum_int_

Server for write_node_enum_int

rclcpp::Service<stcamera_msgs::srv::WriteNodeEnumStr>::SharedPtr srv_write_node_enum_str_

Server for write_node_enum_str

rclcpp::Service<stcamera_msgs::srv::WriteNodeInt>::SharedPtr srv_write_node_int_

Server for write_node_int

rclcpp::Service<stcamera_msgs::srv::WriteNodeFloat>::SharedPtr srv_write_node_float_

Server for write_node_float

rclcpp::Service<stcamera_msgs::srv::WriteNodePort>::SharedPtr srv_write_node_port_

Server for write_node_port

rclcpp::Service<stcamera_msgs::srv::WriteNodeRegister>::SharedPtr srv_write_node_register_

Server for write_node_register

rclcpp::Service<stcamera_msgs::srv::WriteNodeString>::SharedPtr srv_write_node_string_

Server for write_node_string

rclcpp::Service<stcamera_msgs::srv::ExecuteNode>::SharedPtr srv_execute_node_

Server for execute_node

rclcpp::Service<stcamera_msgs::srv::EnableChunk>::SharedPtr srv_enable_chunk_

Server for enable_chunk

rclcpp::Service<stcamera_msgs::srv::EnableTrigger>::SharedPtr srv_enable_trigger_

Server for enable_trigger

rclcpp::Service<stcamera_msgs::srv::EnableEventNode>::SharedPtr srv_enable_event_node_

Server for enable_event_node

rclcpp::Service<stcamera_msgs::srv::EnableImageAcquisition>::SharedPtr srv_enable_image_acquisition_

Server for enable_image_acquisition

rclcpp::Service<stcamera_msgs::srv::EnableEventAcquisition>::SharedPtr srv_enable_event_acquisition_

Server for enable_event_acquisition

rclcpp::Service<stcamera_msgs::srv::GetImageAcquisitionStatus>::SharedPtr srv_get_image_acquisition_status_

Server for get_image_acquisition_status

rclcpp::Service<stcamera_msgs::srv::GetEventAcquisitionStatusList>::SharedPtr srv_get_event_acquisition_status_list_

Server for get_event_acquisition_status_list

rclcpp::Service<stcamera_msgs::srv::GetEventNodeStatusList>::SharedPtr srv_get_event_node_status_list_

Server for get_event_node_status_list

rclcpp::Service<stcamera_msgs::srv::GetChunkList>::SharedPtr srv_get_chunk_list_

Server for get_chunk_list

rclcpp::Service<stcamera_msgs::srv::GetTriggerList>::SharedPtr srv_get_trigger_list_

Server for get_trigger_list

rclcpp::Service<stcamera_msgs::srv::GetEnumList>::SharedPtr srv_get_enum_list_

Server for get_enum_list

rclcpp::Service<stcamera_msgs::srv::GetGenICamNodeInfo>::SharedPtr srv_get_genicam_node_info_

Server for get_genicam_node_info

rclcpp::Service<stcamera_msgs::srv::SendSoftTrigger>::SharedPtr srv_send_soft_trigger_

Server for send_soft_trigger