Class StCameraInterface
Defined in File stcamera_interface.hpp
Inheritance Relationships
Derived Type
public stcamera::StCameraInterfaceImpl
(Class StCameraInterfaceImpl)
Class Documentation
-
class StCameraInterface
Base class to control a connected camera.
This is a base class to control a connected camera, including callback for services.
Subclassed by stcamera::StCameraInterfaceImpl
Public Functions
-
StCameraInterface(rclcpp::Node *nh_parent, const std::string &camera_namespace, StParameter *param, rclcpp::Clock &clock)
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 ~StCameraInterface()
Destructor.
All event node callbacks are deregistered and the callbacks are released here.
-
virtual bool deviceIsLost() = 0
Check if the device is disconnected.
- Returns:
True if device is already disconnected. False otherwise.
Protected Functions
-
inline const std::string &getTextForMsg() const
-
inline rclcpp::Logger get_logger() const
Protected Attributes
-
std::shared_ptr<rclcpp::Node> nh_
-
rclcpp::Node *parent_nh_
Node handle.
-
const std::string camera_namespace_
Namespace of the camera. The namespace is generated by using StParameter::getNamespace() function.
-
StParameter *param_
Pointer to the instance of StParameter.
-
rclcpp::Clock &clock_
-
StCameraInterface(rclcpp::Node *nh_parent, const std::string &camera_namespace, StParameter *param, rclcpp::Clock &clock)