00001
00010 #include <pcl/io/pcd_io.h>
00011 #include <pcl/point_types.h>
00012 #include <pcl/surface/mls.h>
00013 #include "OpenNIGrabber.h"
00014 #include "hrpsys/idl/pointcloud.hh"
00015
00016
00017
00018 static const char* spec[] =
00019 {
00020 "implementation_id", "OpenNIGrabber",
00021 "type_name", "OpenNIGrabber",
00022 "description", "OpenNI grabber",
00023 "version", HRPSYS_PACKAGE_VERSION,
00024 "vendor", "AIST",
00025 "category", "example",
00026 "activity_type", "DataFlowComponent",
00027 "max_instance", "10",
00028 "language", "C++",
00029 "lang_type", "compile",
00030
00031 "conf.default.outputColorImage", "0",
00032 "conf.default.outputDepthImage", "0",
00033 "conf.default.outputPointCloud", "0",
00034 "conf.default.outputPointCloudRGBA", "0",
00035 "conf.default.debugLevel", "0",
00036
00037 ""
00038 };
00039
00040
00041 OpenNIGrabber::OpenNIGrabber(RTC::Manager* manager)
00042 : RTC::DataFlowComponentBase(manager),
00043
00044 m_cloudOut("cloud", m_cloud),
00045 m_imageOut("image", m_image),
00046 m_depthOut("depth", m_depth),
00047
00048 m_interface(NULL),
00049 m_requestToWriteImage(false),
00050 m_requestToWritePointCloud(false),
00051 dummy(0)
00052 {
00053 }
00054
00055 OpenNIGrabber::~OpenNIGrabber()
00056 {
00057 }
00058
00059
00060
00061 RTC::ReturnCode_t OpenNIGrabber::onInitialize()
00062 {
00063 std::cout << m_profile.instance_name << ": onInitialize()" << std::endl;
00064
00065
00066 bindParameter("outputColorImage", m_outputColorImage, "0");
00067 bindParameter("outputDepthImage", m_outputDepthImage, "0");
00068 bindParameter("outputPointCloud", m_outputPointCloud, "0");
00069 bindParameter("outputPointCloudRGBA", m_outputPointCloudRGBA, "0");
00070 bindParameter("debugLevel", m_debugLevel, "0");
00071
00072
00073
00074
00075
00076
00077
00078
00079 addOutPort("cloudOut", m_cloudOut);
00080 addOutPort("imageOut", m_imageOut);
00081 addOutPort("depthOut", m_depthOut);
00082
00083
00084
00085
00086
00087
00088
00089
00090
00091 RTC::Properties& prop = getProperties();
00092
00093 return RTC::RTC_OK;
00094 }
00095
00096
00097 void OpenNIGrabber::grabberCallbackColorImage(const boost::shared_ptr<pcl::io::Image>& image)
00098 {
00099 if (!m_requestToWriteImage) return;
00100
00101 outputColorImage(image);
00102
00103 m_requestToWriteImage = false;
00104 }
00105
00106 void OpenNIGrabber::outputColorImage(const boost::shared_ptr<pcl::io::Image>& image)
00107 {
00108 setTimestamp(m_image);
00109
00110 Img::ImageData &id = m_image.data.image;
00111 id.width = image->getWidth();
00112 id.height = image->getHeight();
00113 id.format = Img::CF_RGB;
00114 id.raw_data.length(id.width*id.height*3);
00115
00116 unsigned char *dst = (unsigned char*)id.raw_data.get_buffer();
00117 unsigned char *src = (unsigned char*)image->getData();
00118 memcpy(dst, src, id.raw_data.length());
00119
00120 m_imageOut.write();
00121 }
00122
00123 void OpenNIGrabber::grabberCallbackDepthImage(const boost::shared_ptr<pcl::io::DepthImage>& image)
00124 {
00125 if (!m_requestToWriteImage) return;
00126
00127 outputDepthImage(image);
00128
00129 m_requestToWriteImage = false;
00130 }
00131
00132 void OpenNIGrabber::outputDepthImage(const boost::shared_ptr<pcl::io::DepthImage>& image)
00133 {
00134 setTimestamp(m_depth);
00135
00136 Img::ImageData &id = m_depth.data.image;
00137 id.width = image->getWidth();
00138 id.height = image->getHeight();
00139 id.format = Img::CF_DEPTH;
00140 id.raw_data.length(id.width*id.height*2);
00141
00142 unsigned char *dst = (unsigned char*)id.raw_data.get_buffer();
00143 unsigned char *src = (unsigned char*)image->getData();
00144 memcpy(dst, src, id.raw_data.length());
00145
00146 m_depthOut.write();
00147 }
00148
00149 void OpenNIGrabber::grabberCallbackColorAndDepthImage(const boost::shared_ptr<pcl::io::Image>& image, const boost::shared_ptr<pcl::io::DepthImage>& depth, float reciprocalFocalLength)
00150 {
00151 if (!m_requestToWriteImage) return;
00152
00153 outputColorImage(image);
00154 outputDepthImage(depth);
00155
00156 m_requestToWriteImage = false;
00157 }
00158
00159 void OpenNIGrabber::grabberCallbackPointCloudRGBA(const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud)
00160 {
00161 if (!m_requestToWritePointCloud) return;
00162
00163 setTimestamp(m_cloud);
00164
00165 m_cloud.width = cloud->width;
00166 m_cloud.height = cloud->height;
00167 m_cloud.row_step = m_cloud.point_step*m_cloud.width;
00168 m_cloud.data.length(m_cloud.height*m_cloud.row_step);
00169
00170 float *dst_cloud = (float *)m_cloud.data.get_buffer();
00171 for (unsigned int i=0; i<cloud->points.size(); i++){
00172 dst_cloud[0] = cloud->points[i].x;
00173 dst_cloud[1] = -cloud->points[i].y;
00174 dst_cloud[2] = -cloud->points[i].z;
00175 dst_cloud[3] = cloud->points[i].rgb;
00176 dst_cloud += 4;
00177 }
00178 m_cloudOut.write();
00179 m_requestToWritePointCloud = false;
00180 }
00181
00182 void OpenNIGrabber::grabberCallbackPointCloud(const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &cloud)
00183 {
00184 if (!m_requestToWritePointCloud) return;
00185
00186 setTimestamp(m_cloud);
00187 m_cloud.width = cloud->width;
00188 m_cloud.height = cloud->height;
00189 m_cloud.row_step = m_cloud.point_step*m_cloud.width;
00190 m_cloud.data.length(m_cloud.height*m_cloud.row_step);
00191
00192 float *dst_cloud = (float *)m_cloud.data.get_buffer();
00193 for (unsigned int i=0; i<cloud->points.size(); i++){
00194 dst_cloud[0] = cloud->points[i].x;
00195 dst_cloud[1] = -cloud->points[i].y;
00196 dst_cloud[2] = -cloud->points[i].z;
00197 dst_cloud += 4;
00198 }
00199 m_cloudOut.write();
00200 m_requestToWritePointCloud = false;
00201 }
00202
00203
00204
00205
00206
00207
00208
00209
00210
00211
00212
00213
00214
00215
00216
00217
00218
00219
00220
00221
00222
00223
00224 RTC::ReturnCode_t OpenNIGrabber::onActivated(RTC::UniqueId ec_id)
00225 {
00226 std::cout << m_profile.instance_name<< ": onActivated(" << ec_id << ")" << std::endl;
00227
00228 try {
00229 m_interface = new pcl::io::OpenNI2Grabber();
00230
00231 if (m_outputColorImage && !m_outputDepthImage){
00232 boost::function<void (const boost::shared_ptr<pcl::io::Image>&)> f = boost::bind(&OpenNIGrabber::grabberCallbackColorImage, this, _1);
00233 m_interface->registerCallback(f);
00234 }else if (!m_outputColorImage && m_outputDepthImage){
00235 boost::function<void (const boost::shared_ptr<pcl::io::DepthImage>&)> f = boost::bind(&OpenNIGrabber::grabberCallbackDepthImage, this, _1);
00236 m_interface->registerCallback(f);
00237 }else if (m_outputColorImage && m_outputDepthImage){
00238 boost::function<void (const boost::shared_ptr<pcl::io::Image>&, const boost::shared_ptr<pcl::io::DepthImage>&, float)> f = boost::bind(&OpenNIGrabber::grabberCallbackColorAndDepthImage, this, _1, _2, _3);
00239 m_interface->registerCallback(f);
00240 }
00241 if (m_outputPointCloud){
00242 m_cloud.type = "xyz";
00243 m_cloud.fields.length(3);
00244 m_cloud.fields[0].name = "x";
00245 m_cloud.fields[0].offset = 0;
00246 m_cloud.fields[0].data_type = PointCloudTypes::FLOAT32;
00247 m_cloud.fields[0].count = 4;
00248 m_cloud.fields[1].name = "y";
00249 m_cloud.fields[1].offset = 4;
00250 m_cloud.fields[1].data_type = PointCloudTypes::FLOAT32;
00251 m_cloud.fields[1].count = 4;
00252 m_cloud.fields[2].name = "z";
00253 m_cloud.fields[2].offset = 8;
00254 m_cloud.fields[2].data_type = PointCloudTypes::FLOAT32;
00255 m_cloud.fields[2].count = 4;
00256 m_cloud.is_bigendian = false;
00257 m_cloud.point_step = 16;
00258 m_cloud.is_dense = true;
00259 boost::function<void (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr&)> f = boost::bind(&OpenNIGrabber::grabberCallbackPointCloud, this, _1);
00260 m_interface->registerCallback(f);
00261 }else if(m_outputPointCloudRGBA){
00262 m_cloud.type = "xyzrgb";
00263 m_cloud.fields.length(6);
00264 m_cloud.fields[0].name = "x";
00265 m_cloud.fields[0].offset = 0;
00266 m_cloud.fields[0].data_type = PointCloudTypes::FLOAT32;
00267 m_cloud.fields[0].count = 4;
00268 m_cloud.fields[1].name = "y";
00269 m_cloud.fields[1].offset = 4;
00270 m_cloud.fields[1].data_type = PointCloudTypes::FLOAT32;
00271 m_cloud.fields[1].count = 4;
00272 m_cloud.fields[2].name = "z";
00273 m_cloud.fields[2].offset = 8;
00274 m_cloud.fields[2].data_type = PointCloudTypes::FLOAT32;
00275 m_cloud.fields[2].count = 4;
00276 m_cloud.fields[3].name = "r";
00277 m_cloud.fields[3].offset = 12;
00278 m_cloud.fields[3].data_type = PointCloudTypes::UINT8;
00279 m_cloud.fields[3].count = 1;
00280 m_cloud.fields[4].name = "g";
00281 m_cloud.fields[4].offset = 13;
00282 m_cloud.fields[4].data_type = PointCloudTypes::UINT8;
00283 m_cloud.fields[4].count = 1;
00284 m_cloud.fields[5].name = "b";
00285 m_cloud.fields[5].offset = 14;
00286 m_cloud.fields[5].data_type = PointCloudTypes::UINT8;
00287 m_cloud.fields[5].count = 1;
00288 m_cloud.is_bigendian = false;
00289 m_cloud.point_step = 16;
00290 m_cloud.is_dense = true;
00291 boost::function<void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&)> f = boost::bind(&OpenNIGrabber::grabberCallbackPointCloudRGBA, this, _1);
00292 m_interface->registerCallback(f);
00293 }
00294
00295 m_interface->start();
00296 }catch(pcl::IOException& ex){
00297 std::cerr << "[" << m_profile.instance_name << "] Error: " << ex.what() << std::endl;
00298 return RTC::RTC_ERROR;
00299 }catch(...){
00300 std::cerr << "[" << m_profile.instance_name
00301 << "] Error: An exception occurred while starting grabber" << std::endl;
00302 return RTC::RTC_ERROR;
00303 }
00304
00305 return RTC::RTC_OK;
00306 }
00307
00308 RTC::ReturnCode_t OpenNIGrabber::onDeactivated(RTC::UniqueId ec_id)
00309 {
00310 std::cout << m_profile.instance_name<< ": onDeactivated(" << ec_id << ")" << std::endl;
00311
00312 if (m_interface){
00313 m_interface->stop();
00314
00315 delete m_interface;
00316 }
00317
00318 return RTC::RTC_OK;
00319 }
00320
00321 RTC::ReturnCode_t OpenNIGrabber::onExecute(RTC::UniqueId ec_id)
00322 {
00323
00324 if (m_debugLevel>0){
00325 if (m_interface->isRunning()){
00326 std::cerr << "[" << m_profile.instance_name
00327 << "] grabber is running. frame rate=" << m_interface->getFramesPerSecond() << std::endl;
00328 }else{
00329 std::cerr << "[" << m_profile.instance_name
00330 << "] grabber is not running" << std::endl;
00331 }
00332 }
00333 m_requestToWriteImage = true;
00334 m_requestToWritePointCloud = true;
00335
00336 return RTC::RTC_OK;
00337 }
00338
00339
00340
00341
00342
00343
00344
00345
00346
00347
00348
00349
00350
00351
00352
00353
00354
00355
00356
00357
00358
00359
00360
00361
00362
00363
00364
00365
00366
00367
00368
00369
00370
00371
00372
00373
00374
00375
00376 extern "C"
00377 {
00378
00379 void OpenNIGrabberInit(RTC::Manager* manager)
00380 {
00381 RTC::Properties profile(spec);
00382 manager->registerFactory(profile,
00383 RTC::Create<OpenNIGrabber>,
00384 RTC::Delete<OpenNIGrabber>);
00385 }
00386
00387 };
00388
00389