imi_Device.h
Go to the documentation of this file.
1 #pragma once
2 
3 #ifndef IMI_DEVICE_H
4 #define IMI_DEVICE_H
5 
6 #include <boost/shared_ptr.hpp>
7 #include <boost/cstdint.hpp>
8 #include <boost/bind.hpp>
9 #include <boost/function.hpp>
10 #include <boost/thread/mutex.hpp>
11 
12 #include <sensor_msgs/Image.h>
14 #include "ImiNect.h"
15 #include "ImiCamera.h"
16 #include <sensor_msgs/PointCloud2.h>
17 #include <string>
18 #include <vector>
19 
20 
21 
22 namespace imi_wrapper
23 {
24  typedef boost::function<void(sensor_msgs::ImagePtr image)> FrameCallbackFunction;
25  typedef boost::function<void(boost::shared_ptr<sensor_msgs::PointCloud2> cloudPtr)> CloudCallbackFunction;
26 
27  class ImiDevice
28  {
29  public:
30  ImiDevice();
31  virtual ~ImiDevice();
32 
33  const std::string getUri() const;
34  uint16_t getUsbVendorId() const;
35  uint16_t getUsbProductId() const;
36 
37  bool isValid() const;
38 
39  bool hasColorSensor() const;
40  bool hasUVCSensor() const;
41  bool hasDepthSensor() const;
42 
43  int startColorStream(ImiFrameMode colorFrameMode);
44  int startUVCStream(ImiCameraFrameMode uvcframeMode);
45  int startDepthStream(ImiFrameMode depthFrameMode);
46 
47  void stopAllStreams();
48 
49  void stopColorStream();
50  void stopUVCStream();
51  void stopDepthStream();
52 
53  int openDevice();
54  int closeDevice();
55 
56  void setColorFrameCallback(FrameCallbackFunction callback);
57  void setUVCFrameCallback(FrameCallbackFunction callback);
58  void setDepthFrameCallback(FrameCallbackFunction callback);
60 
61  void convertToCloudPoint(ImiImageFrame* pFrame);
62 
63  sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height);
64 
65  static int readFrame(void* lParam);
66  static int readUVCFrame(void* lParam);
67 
68  private:
69  boost::mutex device_mutex_;
70  boost::mutex uvc_mutex_;
71  ImiDeviceAttribute* pDeviceAttr;
72  ImiDeviceHandle pImiDevice;
73 
74  ImiStreamHandle depthHandle;
75  ImiStreamHandle colorHandle;
76  ImiCameraHandle camHandle;
77 
82 
83  FrameCallbackFunction depthCallback;
84  FrameCallbackFunction colorCallback;
86  FrameCallbackFunction uvcCallback;
87 
88  double m_cx;
89  double m_cy;
90  double m_fx;
91  double m_fy;
92  };
93 }
94 
95 #endif /* OPENNI_DEVICE_H */
ImiDeviceAttribute * pDeviceAttr
Definition: imi_Device.h:71
static int readUVCFrame(void *lParam)
Definition: imi_Device.cpp:258
void setUVCFrameCallback(FrameCallbackFunction callback)
Definition: imi_Device.cpp:436
boost::mutex uvc_mutex_
Definition: imi_Device.h:70
ImiCameraHandle camHandle
Definition: imi_Device.h:76
FrameCallbackFunction depthCallback
Definition: imi_Device.h:83
ImiStreamHandle colorHandle
Definition: imi_Device.h:75
bool hasDepthSensor() const
Definition: imi_Device.cpp:425
void convertToCloudPoint(ImiImageFrame *pFrame)
Definition: imi_Device.cpp:105
const std::string getUri() const
Definition: imi_Device.cpp:380
bool isValid() const
Definition: imi_Device.cpp:410
int startDepthStream(ImiFrameMode depthFrameMode)
Definition: imi_Device.cpp:500
int startColorStream(ImiFrameMode colorFrameMode)
Definition: imi_Device.cpp:454
boost::function< void(sensor_msgs::ImagePtr image)> FrameCallbackFunction
Definition: imi_Device.h:24
void setCloudPointCallback(CloudCallbackFunction callback)
Definition: imi_Device.cpp:448
FrameCallbackFunction colorCallback
Definition: imi_Device.h:84
CloudCallbackFunction cloudCallback
Definition: imi_Device.h:85
ImiDeviceHandle pImiDevice
Definition: imi_Device.h:72
FrameCallbackFunction uvcCallback
Definition: imi_Device.h:86
boost::mutex device_mutex_
Definition: imi_Device.h:69
int startUVCStream(ImiCameraFrameMode uvcframeMode)
Definition: imi_Device.cpp:478
uint16_t getUsbVendorId() const
Definition: imi_Device.cpp:390
bool hasColorSensor() const
Definition: imi_Device.cpp:415
void setColorFrameCallback(FrameCallbackFunction callback)
Definition: imi_Device.cpp:430
sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height)
Definition: imi_Device.cpp:346
void setDepthFrameCallback(FrameCallbackFunction callback)
Definition: imi_Device.cpp:442
static int readFrame(void *lParam)
Definition: imi_Device.cpp:155
boost::function< void(boost::shared_ptr< sensor_msgs::PointCloud2 > cloudPtr)> CloudCallbackFunction
Definition: imi_Device.h:25
uint16_t getUsbProductId() const
Definition: imi_Device.cpp:400
bool hasUVCSensor() const
Definition: imi_Device.cpp:420
ImiStreamHandle depthHandle
Definition: imi_Device.h:74


imi_camera
Author(s): hjimi , HUAJIEIMI
autogenerated on Mon Jun 10 2019 13:32:59