camerathread.cpp
Go to the documentation of this file.
1 
19 #include <QMetaType>
20 
21 CameraThread::CameraThread(QObject *parent, std::string topicName) :
22  QThread(parent)
23 {
24  this->topicName = topicName;
25  qRegisterMetaType<sensor_msgs::Image::ConstPtr>("sensor_msgs::Image::ConstPtr");
26 }
27 
29 {
31  a = n.subscribe(topicName, 1000, &CameraThread::onImage, this);
32  ROS_INFO_STREAM("Camera started: " << topicName);
33  while (ros::ok())
34  {
35  ros::spinOnce();
36  }
37 }
38 
39 void CameraThread::onImage(const sensor_msgs::Image::ConstPtr& msg)
40 {
41  this->imageReceived(msg);
42 }
CameraThread(QObject *parent=0, std::string topicName="")
std::string topicName
Definition: camerathread.h:39
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void imageReceived(const sensor_msgs::Image::ConstPtr &msg)
void onImage(const sensor_msgs::Image::ConstPtr &msg)
ROSCPP_DECL bool ok()
#define ROS_INFO_STREAM(args)
ROSCPP_DECL void spinOnce()
ros::Subscriber a
Definition: camerathread.h:40


asr_mild_calibration_tool
Author(s): Aumann Florian, Heller Florian, Meißner Pascal
autogenerated on Mon Dec 2 2019 03:11:43