.. _program_listing_file__tmp_ws_src_v4l2_camera_include_v4l2_camera_v4l2_camera.hpp: Program Listing for File v4l2_camera.hpp ======================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/v4l2_camera/include/v4l2_camera/v4l2_camera.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2019 Bold Hearts // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. #ifndef V4L2_CAMERA__V4L2_CAMERA_HPP_ #define V4L2_CAMERA__V4L2_CAMERA_HPP_ #include "v4l2_camera/v4l2_camera_device.hpp" #include #include #include #include #include #include #include #include "v4l2_camera/visibility_control.h" #include "v4l2_camera/parameters.hpp" namespace v4l2_camera { class V4L2Camera : public rclcpp::Node { public: explicit V4L2Camera(rclcpp::NodeOptions const & options); virtual ~V4L2Camera(); private: Parameters parameters_; std::shared_ptr camera_; // Publisher used for intra process comm rclcpp::Publisher::SharedPtr image_pub_; rclcpp::Publisher::SharedPtr info_pub_; // Publisher used for inter process comm image_transport::CameraPublisher camera_transport_pub_; std::shared_ptr cinfo_; std::thread capture_thread_; std::atomic canceled_; std::string camera_frame_id_; std::string output_encoding_; rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_; void applyParameters(); bool handleParameter(rclcpp::Parameter const & param); bool requestPixelFormat(std::string const & fourcc); bool requestImageSize(std::vector const & size); sensor_msgs::msg::Image::UniquePtr convert(sensor_msgs::msg::Image const & img) const; bool checkCameraInfo( sensor_msgs::msg::Image const & img, sensor_msgs::msg::CameraInfo const & ci); }; } // namespace v4l2_camera #endif // V4L2_CAMERA__V4L2_CAMERA_HPP_