1.头文件k4a_grabber.h
#pragma once
#include #include #include #include #include #include namespace pcl
{
struct pcl::PointXYZ;
struct pcl::PointXYZI;
struct pcl::PointXYZRGB;
struct pcl::PointXYZRGBA;
template class pcl::PointCloud;
class KinectAzureDKGrabber : public pcl::Grabber
{
public:
KinectAzureDKGrabber(const int& device_id_, const int& depth_mode_, const int& color_format_, const int& color_resolution_);
virtual ~KinectAzureDKGrabber() throw ();
virtual void start();
virtual void stop();
virtual bool isRunning() const;
virtual std::string getName() const;
virtual float getFramesPerSecond() const;
typedef void (signal_KinectAzureDK_PointXYZ)(const std::shared_ptr>&);
typedef void (signal_KinectAzureDK_PointXYZI)(const std::shared_ptr>&);
typedef void (signal_KinectAzureDK_PointXYZRGB)(const std::shared_ptr>&);
typedef void (signal_KinectAzureDK_PointXYZRGBA)(const std::shared_ptr>&);
protected:
void setupDevice(const int& device_id_, const int& depth_mode_, const int& color_format_, const int& color_resolution_);
boost::signals2::signal* signal_PointXYZ;
boost::signals2::signal* signal_PointXYZI;
boost::signals2::signal* signal_PointXYZRGB;
boost::signals2::signal* signal_PointXYZRGBA;
pcl::PointCloud::Ptr convertDepthToPointXYZ();
pcl::PointCloud::Ptr convertInfraredDepthToPointXYZI();
pcl::PointCloud::Ptr convertRGBDepthToPointXYZRGB();
pcl::PointCloud::Ptr convertRGBADepthToPointXYZRGBA();
std::thread thread;
mutable std::mutex mutex;
void threadFunction();
bool quit;
bool running;
k4a_device_configuration_t config;
k4a::device dev;
int device_id;
k4a::calibration calibration;
k4a::transformation transformation;
int colorWidth;
int colorHeight;
k4a::image colorImage;
int depthWidth;
int depthHeight;
k4a::image depthImage;
int infraredWidth;
int infraredHeight;
k4a::image infraredImage;
public:
k4a::calibration getCalibration();
};
}
2.k4a_grabber.cpp
#include #include "k4a_grabber.h"
pcl::KinectAzureDKGrabber::KinectAzureDKGrabber(const int &device_id_, const int &depth_mode_, const int &color_format_, const int &color_resolution_) :
config(K4A_DEVICE_CONFIG_INIT_DISABLE_ALL),
dev(nullptr),
colorImage(nullptr),
depthImage(nullptr),
infraredImage(nullptr),
running(false),
quit(false),
signal_PointXYZ(nullptr),
signal_PointXYZI(nullptr),
signal_PointXYZRGB(nullptr),
signal_PointXYZRGBA(nullptr)
{
setupDevice(device_id_, depth_mode_, color_format_, color_resolution_);
signal_PointXYZ = createSignal();
signal_PointXYZI = createSignal();
signal_PointXYZRGB = createSignal();
signal_PointXYZRGBA = createSignal();
}
pcl::KinectAzureDKGrabber::~KinectAzureDKGrabber() throw()
{
stop();
disconnect_all_slots();
disconnect_all_slots();
disconnect_all_slots();
disconnect_all_slots();
thread.join();
if (dev)
{
transformation.destroy();
dev.close();
}
}
void pcl::KinectAzureDKGrabber::start()
{
dev = k4a::device::open(device_id);
dev.start_cameras(&config);
calibration = dev.get_calibration(config.depth_mode, config.color_resolution);
transformation = k4a::transformation(calibration);
running = true;
thread