#include <CameraROS.h>
Signals | |
void | rosDataReceived (const std::string &frameId, const ros::Time &stamp, const cv::Mat &depth, float depthConstant) |
Public Member Functions | |
CameraROS (bool subscribeDepth, QObject *parent=0) | |
virtual bool | start () |
virtual void | stop () |
QStringList | subscribedTopics () const |
virtual | ~CameraROS () |
Private Types | |
typedef message_filters::sync_policies::ApproximateTime < sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > | MySyncPolicy |
Private Slots | |
virtual void | takeImage () |
Private Member Functions | |
void | imgDepthReceivedCallback (const sensor_msgs::ImageConstPtr &rgbMsg, const sensor_msgs::ImageConstPtr &depthMsg, const sensor_msgs::CameraInfoConstPtr &cameraInfoMsg) |
void | imgReceivedCallback (const sensor_msgs::ImageConstPtr &msg) |
Private Attributes | |
message_filters::Subscriber < sensor_msgs::CameraInfo > | cameraInfoSub_ |
image_transport::SubscriberFilter | depthSub_ |
image_transport::Subscriber | imageSub_ |
image_transport::SubscriberFilter | rgbSub_ |
bool | subscribeDepth_ |
message_filters::Synchronizer < MySyncPolicy > * | sync_ |
Definition at line 48 of file CameraROS.h.
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo> CameraROS::MySyncPolicy [private] |
Definition at line 86 of file CameraROS.h.
CameraROS::CameraROS | ( | bool | subscribeDepth, |
QObject * | parent = 0 |
||
) |
Definition at line 36 of file CameraROS.cpp.
virtual CameraROS::~CameraROS | ( | ) | [inline, virtual] |
Definition at line 52 of file CameraROS.h.
void CameraROS::imgDepthReceivedCallback | ( | const sensor_msgs::ImageConstPtr & | rgbMsg, |
const sensor_msgs::ImageConstPtr & | depthMsg, | ||
const sensor_msgs::CameraInfoConstPtr & | cameraInfoMsg | ||
) | [private] |
Definition at line 132 of file CameraROS.cpp.
void CameraROS::imgReceivedCallback | ( | const sensor_msgs::ImageConstPtr & | msg | ) | [private] |
Definition at line 107 of file CameraROS.cpp.
void CameraROS::rosDataReceived | ( | const std::string & | frameId, |
const ros::Time & | stamp, | ||
const cv::Mat & | depth, | ||
float | depthConstant | ||
) | [signal] |
bool CameraROS::start | ( | ) | [virtual] |
Reimplemented from find_object::Camera.
Definition at line 91 of file CameraROS.cpp.
void CameraROS::stop | ( | ) | [virtual] |
Reimplemented from find_object::Camera.
Definition at line 97 of file CameraROS.cpp.
QStringList CameraROS::subscribedTopics | ( | ) | const |
Definition at line 75 of file CameraROS.cpp.
void CameraROS::takeImage | ( | ) | [private, virtual, slot] |
Reimplemented from find_object::Camera.
Definition at line 102 of file CameraROS.cpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> CameraROS::cameraInfoSub_ [private] |
Definition at line 81 of file CameraROS.h.
Definition at line 80 of file CameraROS.h.
Definition at line 77 of file CameraROS.h.
Definition at line 79 of file CameraROS.h.
bool CameraROS::subscribeDepth_ [private] |
Definition at line 76 of file CameraROS.h.
Definition at line 87 of file CameraROS.h.