ros2/CameraROS.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2011-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef CAMERAROS_H_
29 #define CAMERAROS_H_
30 
31 #include <rclcpp/rclcpp.hpp>
32 #include <cv_bridge/cv_bridge.h>
33 
38 
39 #include <image_transport/image_transport.hpp>
40 #include <image_transport/subscriber_filter.hpp>
41 
42 #include <sensor_msgs/msg/camera_info.hpp>
43 #include <sensor_msgs/msg/image.hpp>
44 
45 #include "find_object/Camera.h"
46 #include <QtCore/QStringList>
47 
48 class CameraROS : public find_object::Camera {
49  Q_OBJECT
50 public:
51  CameraROS(bool subscribeDepth, rclcpp::Node * node);
52  virtual ~CameraROS();
53  void setupExecutor(std::shared_ptr<rclcpp::Node> node);
54 
55  virtual bool start();
56  virtual void stop();
57 
58  QStringList subscribedTopics() const;
59 
60 private Q_SLOTS:
61  virtual void takeImage();
62 
63 private:
64  void imgReceivedCallback(const sensor_msgs::msg::Image::ConstSharedPtr msg);
66  const sensor_msgs::msg::Image::ConstSharedPtr rgbMsg,
67  const sensor_msgs::msg::Image::ConstSharedPtr depthMsg,
68  const sensor_msgs::msg::CameraInfo::ConstSharedPtr cameraInfoMsg);
69 
70 private:
71  rclcpp::Node * node_;
72  rclcpp::executors::SingleThreadedExecutor executor_;
73  bool subscribeDepth_;
75 
79 
81  sensor_msgs::msg::Image,
82  sensor_msgs::msg::Image,
83  sensor_msgs::msg::CameraInfo> MyApproxSyncPolicy;
85 
87  sensor_msgs::msg::Image,
88  sensor_msgs::msg::Image,
89  sensor_msgs::msg::CameraInfo> MyExactSyncPolicy;
91 };
92 
93 #endif /* CAMERAROS_H_ */
image_transport::SubscriberFilter
CameraROS::~CameraROS
virtual ~CameraROS()
Definition: ros1/CameraROS.cpp:88
message_filters::Synchronizer
CameraROS::cameraInfoSub_
message_filters::Subscriber< sensor_msgs::msg::CameraInfo > cameraInfoSub_
Definition: ros2/CameraROS.h:78
CameraROS::stop
virtual void stop()
Definition: ros1/CameraROS.cpp:116
CameraROS::executor_
rclcpp::executors::SingleThreadedExecutor executor_
Definition: ros2/CameraROS.h:72
CameraROS::setupExecutor
void setupExecutor(std::shared_ptr< rclcpp::Node > node)
Definition: ros2/CameraROS.cpp:83
CameraROS::node_
rclcpp::Node * node_
Definition: ros2/CameraROS.h:71
CameraROS::exactSync_
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
Definition: ros1/CameraROS.h:88
CameraROS::imageSub_
image_transport::Subscriber imageSub_
Definition: ros1/CameraROS.h:72
CameraROS::subscribedTopics
QStringList subscribedTopics() const
Definition: ros1/CameraROS.cpp:94
CameraROS::rgbSub_
image_transport::SubscriberFilter rgbSub_
Definition: ros1/CameraROS.h:74
message_filters::Subscriber< sensor_msgs::msg::CameraInfo >
image_transport::Subscriber
find_object::Camera
Definition: Camera.h:42
message_filters::sync_policies::ApproximateTime
CameraROS::start
virtual bool start()
Definition: ros1/CameraROS.cpp:110
CameraROS::takeImage
virtual void takeImage()
Definition: ros1/CameraROS.cpp:121
subscriber.h
CameraROS::imgDepthReceivedCallback
void imgDepthReceivedCallback(const sensor_msgs::ImageConstPtr &rgbMsg, const sensor_msgs::ImageConstPtr &depthMsg, const sensor_msgs::CameraInfoConstPtr &cameraInfoMsg)
Definition: ros1/CameraROS.cpp:153
CameraROS
Definition: ros1/CameraROS.h:49
CameraROS::MyApproxSyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::msg::Image, sensor_msgs::msg::Image, sensor_msgs::msg::CameraInfo > MyApproxSyncPolicy
Definition: ros2/CameraROS.h:83
CameraROS::approxSync_
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
Definition: ros1/CameraROS.h:82
CameraROS::MyExactSyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::msg::Image, sensor_msgs::msg::Image, sensor_msgs::msg::CameraInfo > MyExactSyncPolicy
Definition: ros2/CameraROS.h:89
CameraROS::CameraROS
CameraROS(bool subscribeDepth, QObject *parent=0)
Definition: ros1/CameraROS.cpp:36
CameraROS::imgReceivedCallback
void imgReceivedCallback(const sensor_msgs::ImageConstPtr &msg)
Definition: ros1/CameraROS.cpp:126
exact_time.h
CameraROS::depthSub_
image_transport::SubscriberFilter depthSub_
Definition: ros1/CameraROS.h:75
cv_bridge.h
Camera.h
synchronizer.h
approximate_time.h
message_filters::sync_policies::ExactTime
CameraROS::subscribeDepth_
bool subscribeDepth_
Definition: ros1/CameraROS.h:71


find_object_2d
Author(s): Mathieu Labbe
autogenerated on Mon Dec 12 2022 03:43:35