23 #include "pcl_frombuf_thread.h"
25 #include <fvutils/base/types.h>
26 #include <fvutils/color/colorspaces.h>
27 #include <fvutils/ipc/shm_image.h>
28 #include <pcl_utils/utils.h>
33 using namespace firevision;
46 :
Thread(
"OpenNiPclOnlyThread",
Thread::OPMODE_WAITFORWAKEUP),
61 width_ = pcl_buf_->
width();
62 height_ = pcl_buf_->
height();
65 pcl_->is_dense =
false;
67 pcl_->height = height_;
68 pcl_->points.resize((
size_t)width_ * (
size_t)height_);
89 if (last_capture_time_ != capture_time) {
90 last_capture_time_ = capture_time;
96 pcl_utils::set_time(pcl_, capture_time);
99 for (
unsigned int h = 0; h < height_; ++h) {
100 for (
unsigned int w = 0; w < width_; ++w, ++idx, ++pclbuf) {
102 pcl.points[idx].x = pclbuf->
x;
103 pcl.points[idx].y = pclbuf->
y;
104 pcl.points[idx].z = pclbuf->
z;
virtual void finalize()
Finalize the thread.
virtual ~OpenNiPclOnlyThread()
Destructor.
virtual void loop()
Code to execute in the thread.
virtual void init()
Initialize the thread.
OpenNiPclOnlyThread()
Constructor.
Thread aspect to use blocked timing.
Configuration * config
This is the Configuration member used to access the configuration.
virtual std::string get_string(const char *path)=0
Get value from configuration which is of type string.
PointCloudManager * pcl_manager
Manager to distribute and access point clouds.
void remove_pointcloud(const char *id)
Remove the point cloud.
void add_pointcloud(const char *id, RefPtr< pcl::PointCloud< PointT >> cloud)
Add point cloud.
int use_count() const
Get current reference count.
unsigned int num_attached() const
Get number of attached processes.
void unlock()
Unlock memory.
void lock_for_read()
Lock shared memory segment for reading.
Thread class encapsulation of pthreads.
A class for handling time.
Shared memory image buffer.
unsigned int height() const
Get image height.
fawkes::Time capture_time() const
Get the time when the image was captured.
unsigned int width() const
Get image width.
unsigned char * buffer() const
Get image buffer.
Fawkes library namespace.
Structure defining a point in a CARTESIAN_3D_FLOAT buffer.