Public Member Functions | Private Types | Private Slots | Private Member Functions | Private Attributes | List of all members
CameraROS Class Reference

#include <CameraROS.h>

Inheritance diagram for CameraROS:
Inheritance graph
[legend]

Public Member Functions

 CameraROS (bool subscribeDepth, rclcpp::Node *node)
 
 CameraROS (bool subscribeDepth, QObject *parent=0)
 
void setupExecutor (std::shared_ptr< rclcpp::Node > node)
 
virtual bool start ()
 
virtual bool start ()
 
virtual void stop ()
 
virtual void stop ()
 
QStringList subscribedTopics () const
 
QStringList subscribedTopics () const
 
virtual ~CameraROS ()
 
virtual ~CameraROS ()
 
- Public Member Functions inherited from find_object::Camera
 Camera (QObject *parent=0)
 
int getCurrentFrameIndex ()
 
int getPort ()
 
int getTotalFrames ()
 
virtual bool isRunning ()
 
void moveToFrame (int frame)
 
void pause ()
 
virtual ~Camera ()
 

Private Types

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyApproxSyncPolicy
 
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::msg::Image, sensor_msgs::msg::Image, sensor_msgs::msg::CameraInfo > MyApproxSyncPolicy
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncPolicy
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::msg::Image, sensor_msgs::msg::Image, sensor_msgs::msg::CameraInfo > MyExactSyncPolicy
 

Private Slots

virtual void takeImage ()
 
virtual void takeImage ()
 

Private Member Functions

void imgDepthReceivedCallback (const sensor_msgs::ImageConstPtr &rgbMsg, const sensor_msgs::ImageConstPtr &depthMsg, const sensor_msgs::CameraInfoConstPtr &cameraInfoMsg)
 
void imgDepthReceivedCallback (const sensor_msgs::msg::Image::ConstSharedPtr rgbMsg, const sensor_msgs::msg::Image::ConstSharedPtr depthMsg, const sensor_msgs::msg::CameraInfo::ConstSharedPtr cameraInfoMsg)
 
void imgReceivedCallback (const sensor_msgs::msg::Image::ConstSharedPtr msg)
 
void imgReceivedCallback (const sensor_msgs::ImageConstPtr &msg)
 

Private Attributes

message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
 
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
 
message_filters::Subscriber< sensor_msgs::msg::CameraInfo > cameraInfoSub_
 
image_transport::SubscriberFilter depthSub_
 
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
 
rclcpp::executors::SingleThreadedExecutor executor_
 
image_transport::Subscriber imageSub_
 
rclcpp::Node * node_
 
image_transport::SubscriberFilter rgbSub_
 
bool subscribeDepth_
 

Additional Inherited Members

- Public Slots inherited from find_object::Camera
virtual void takeImage ()
 
virtual void updateImageRate ()
 
- Signals inherited from find_object::Camera
void finished ()
 
void imageReceived (const cv::Mat &image)
 
void imageReceived (const cv::Mat &image, const find_object::Header &header, const cv::Mat &depth, float depthConstant)
 
- Protected Member Functions inherited from find_object::Camera
void startTimer ()
 
void stopTimer ()
 

Detailed Description

Definition at line 49 of file ros1/CameraROS.h.

Member Typedef Documentation

◆ MyApproxSyncPolicy [1/2]

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo> CameraROS::MyApproxSyncPolicy
private

Definition at line 81 of file ros1/CameraROS.h.

◆ MyApproxSyncPolicy [2/2]

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::msg::Image, sensor_msgs::msg::Image, sensor_msgs::msg::CameraInfo> CameraROS::MyApproxSyncPolicy
private

Definition at line 83 of file ros2/CameraROS.h.

◆ MyExactSyncPolicy [1/2]

typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo> CameraROS::MyExactSyncPolicy
private

Definition at line 87 of file ros1/CameraROS.h.

◆ MyExactSyncPolicy [2/2]

typedef message_filters::sync_policies::ExactTime< sensor_msgs::msg::Image, sensor_msgs::msg::Image, sensor_msgs::msg::CameraInfo> CameraROS::MyExactSyncPolicy
private

Definition at line 89 of file ros2/CameraROS.h.

Constructor & Destructor Documentation

◆ CameraROS() [1/2]

CameraROS::CameraROS ( bool  subscribeDepth,
QObject *  parent = 0 
)

Definition at line 36 of file ros1/CameraROS.cpp.

◆ ~CameraROS() [1/2]

CameraROS::~CameraROS ( )
virtual

Definition at line 88 of file ros1/CameraROS.cpp.

◆ CameraROS() [2/2]

CameraROS::CameraROS ( bool  subscribeDepth,
rclcpp::Node *  node 
)

Definition at line 36 of file ros2/CameraROS.cpp.

◆ ~CameraROS() [2/2]

virtual CameraROS::~CameraROS ( )
virtual

Member Function Documentation

◆ imgDepthReceivedCallback() [1/2]

void CameraROS::imgDepthReceivedCallback ( const sensor_msgs::ImageConstPtr &  rgbMsg,
const sensor_msgs::ImageConstPtr &  depthMsg,
const sensor_msgs::CameraInfoConstPtr &  cameraInfoMsg 
)
private

Definition at line 153 of file ros1/CameraROS.cpp.

◆ imgDepthReceivedCallback() [2/2]

void CameraROS::imgDepthReceivedCallback ( const sensor_msgs::msg::Image::ConstSharedPtr  rgbMsg,
const sensor_msgs::msg::Image::ConstSharedPtr  depthMsg,
const sensor_msgs::msg::CameraInfo::ConstSharedPtr  cameraInfoMsg 
)
private

Definition at line 147 of file ros2/CameraROS.cpp.

◆ imgReceivedCallback() [1/2]

void CameraROS::imgReceivedCallback ( const sensor_msgs::msg::Image::ConstSharedPtr  msg)
private

Definition at line 120 of file ros2/CameraROS.cpp.

◆ imgReceivedCallback() [2/2]

void CameraROS::imgReceivedCallback ( const sensor_msgs::ImageConstPtr &  msg)
private

Definition at line 126 of file ros1/CameraROS.cpp.

◆ setupExecutor()

void CameraROS::setupExecutor ( std::shared_ptr< rclcpp::Node >  node)

Definition at line 83 of file ros2/CameraROS.cpp.

◆ start() [1/2]

bool CameraROS::start ( )
virtual

Reimplemented from find_object::Camera.

Definition at line 110 of file ros1/CameraROS.cpp.

◆ start() [2/2]

virtual bool CameraROS::start ( )
virtual

Reimplemented from find_object::Camera.

◆ stop() [1/2]

virtual void CameraROS::stop ( )
virtual

Reimplemented from find_object::Camera.

◆ stop() [2/2]

void CameraROS::stop ( )
virtual

Reimplemented from find_object::Camera.

Definition at line 116 of file ros1/CameraROS.cpp.

◆ subscribedTopics() [1/2]

QStringList CameraROS::subscribedTopics ( ) const

Definition at line 94 of file ros1/CameraROS.cpp.

◆ subscribedTopics() [2/2]

QStringList CameraROS::subscribedTopics ( ) const

◆ takeImage [1/2]

void CameraROS::takeImage ( )
privatevirtualslot

Definition at line 121 of file ros1/CameraROS.cpp.

◆ takeImage [2/2]

virtual void CameraROS::takeImage ( )
privatevirtualslot

Member Data Documentation

◆ approxSync_

message_filters::Synchronizer< MyApproxSyncPolicy > * CameraROS::approxSync_
private

Definition at line 82 of file ros1/CameraROS.h.

◆ cameraInfoSub_ [1/2]

message_filters::Subscriber<sensor_msgs::CameraInfo> CameraROS::cameraInfoSub_
private

Definition at line 76 of file ros1/CameraROS.h.

◆ cameraInfoSub_ [2/2]

message_filters::Subscriber<sensor_msgs::msg::CameraInfo> CameraROS::cameraInfoSub_
private

Definition at line 78 of file ros2/CameraROS.h.

◆ depthSub_

image_transport::SubscriberFilter CameraROS::depthSub_
private

Definition at line 75 of file ros1/CameraROS.h.

◆ exactSync_

message_filters::Synchronizer< MyExactSyncPolicy > * CameraROS::exactSync_
private

Definition at line 88 of file ros1/CameraROS.h.

◆ executor_

rclcpp::executors::SingleThreadedExecutor CameraROS::executor_
private

Definition at line 72 of file ros2/CameraROS.h.

◆ imageSub_

image_transport::Subscriber CameraROS::imageSub_
private

Definition at line 72 of file ros1/CameraROS.h.

◆ node_

rclcpp::Node* CameraROS::node_
private

Definition at line 71 of file ros2/CameraROS.h.

◆ rgbSub_

image_transport::SubscriberFilter CameraROS::rgbSub_
private

Definition at line 74 of file ros1/CameraROS.h.

◆ subscribeDepth_

bool CameraROS::subscribeDepth_
private

Definition at line 71 of file ros1/CameraROS.h.


The documentation for this class was generated from the following files:


find_object_2d
Author(s): Mathieu Labbe
autogenerated on Mon Dec 12 2022 03:20:10