Go to the documentation of this file.00001
00002 #include <hrl_head_registration/head_registration.h>
00003
00004 void expandPC(const PCRGB::Ptr& pc_label, const PCRGB::Ptr& pc_base,
00005 PCRGB::Ptr& pc_expand, double radius)
00006 {
00007 KDTree::Ptr kd_tree(new pcl::KdTreeFLANN<PRGB> ());
00008 kd_tree->setInputCloud(pc_base);
00009 vector<int> inds;
00010 vector<float> dists;
00011 for(uint32_t i=0;i<pc_label->size();i++) {
00012 inds.clear(); dists.clear();
00013 kd_tree->radiusSearch(*pc_label, i, radius, inds, dists);
00014 for(uint32_t j=0;j<inds.size();j++)
00015 COPY_PT_INTO_CLOUD(pc_label, pc_expand, inds[j]);
00016 }
00017 }
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058 int main(int argc, char **argv)
00059 {
00060 ros::init(argc, argv, "head_training");
00061 ros::NodeHandle nh;
00062 PCRGB::Ptr input_pc;
00063 readPCBag(argv[1], input_pc);
00064 PCRGB::Ptr skin_pc(new PCRGB());
00065 PCRGB::Ptr expanded_pc(new PCRGB());
00066 PCRGB::Ptr trimmed_pc(new PCRGB());
00067
00068 uint32_t closest_ind = findClosestPoint(input_pc, atoi(argv[3]), atoi(argv[4]));
00069 sphereTrim(input_pc, trimmed_pc, closest_ind, atof(argv[5]));
00070 extractSkinPC(trimmed_pc, skin_pc, atof(argv[2]));
00071
00072 skin_pc->header.frame_id = "/base_link";
00073 savePCBag("skin_pc.bag", skin_pc);
00074 pubLoop(skin_pc, "test", 5);
00075 return 0;
00076 }