Class Camera

Nested Relationships

Nested Types

Class Documentation

class Camera

Public Types

using ImageConstPtr = spinnaker_camera_driver::ImageConstPtr
using CompositeDiagnosticsTask = diagnostic_updater::CompositeDiagnosticTask
using FunctionDiagnosticsTask = diagnostic_updater::FunctionDiagnosticTask
using DiagnosticStatusWrapper = diagnostic_updater::DiagnosticStatusWrapper

Public Functions

explicit Camera(const std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>&, const std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>&, const std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>&, const std::shared_ptr<rclcpp::node_interfaces::NodeTimersInterface>&, const std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>&, const std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>&, const std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>&, image_transport::ImageTransport *it, camera_info_manager::CameraInfoManager *im, const std::string &logName, const std::string &prefix, bool useStatus = true)
~Camera()
inline void setSynchronizer(const std::shared_ptr<Synchronizer> &s)
inline void setExposureController(const std::shared_ptr<ExposureController> &e)
inline const std::string &getName() const
inline const std::string &getPrefix() const
bool configure()
bool activate()
bool deactivate()
bool deconfigure()