15 #ifndef SPINNAKER_CAMERA_DRIVER__CAMERA_LIST_WRAPPER_HPP_
16 #define SPINNAKER_CAMERA_DRIVER__CAMERA_LIST_WRAPPER_HPP_
19 #include <spinnaker/Spinnaker.h>
22 #include <sensor_msgs/msg/image.hpp>
54 Spinnaker::CameraList camera_list,
59 Spinnaker::CameraList camera_list,
60 const std::vector<CameraSettings> & camera_settings);
76 void start_capturing();
79 void stop_capturing();
82 std::unique_ptr<sensor_msgs::msg::Image> retreive_image_from_camera(
83 const std::uint32_t camera_index)
const;
93 Spinnaker::CameraList m_camera_list{};
95 std::vector<CameraWrapper> m_cameras{};
103 #endif // SPINNAKER_CAMERA_DRIVER__CAMERA_LIST_WRAPPER_HPP_