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> 12 #include <sensor_msgs/Image.h> 15 #include "ImiCamera.h" 16 #include <sensor_msgs/PointCloud2.h> 33 const std::string
getUri()
const;
ImiDeviceAttribute * pDeviceAttr
static int readUVCFrame(void *lParam)
void setUVCFrameCallback(FrameCallbackFunction callback)
ImiCameraHandle camHandle
FrameCallbackFunction depthCallback
ImiStreamHandle colorHandle
bool hasDepthSensor() const
void convertToCloudPoint(ImiImageFrame *pFrame)
const std::string getUri() const
int startDepthStream(ImiFrameMode depthFrameMode)
int startColorStream(ImiFrameMode colorFrameMode)
boost::function< void(sensor_msgs::ImagePtr image)> FrameCallbackFunction
void setCloudPointCallback(CloudCallbackFunction callback)
FrameCallbackFunction colorCallback
CloudCallbackFunction cloudCallback
ImiDeviceHandle pImiDevice
FrameCallbackFunction uvcCallback
boost::mutex device_mutex_
int startUVCStream(ImiCameraFrameMode uvcframeMode)
uint16_t getUsbVendorId() const
bool hasColorSensor() const
void setColorFrameCallback(FrameCallbackFunction callback)
sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height)
void setDepthFrameCallback(FrameCallbackFunction callback)
static int readFrame(void *lParam)
boost::function< void(boost::shared_ptr< sensor_msgs::PointCloud2 > cloudPtr)> CloudCallbackFunction
uint16_t getUsbProductId() const
bool hasUVCSensor() const
ImiStreamHandle depthHandle