Go to the documentation of this file.00001 #include "wrinkled_map_alg_node.h"
00002
00003 WrinkledMapAlgNode::WrinkledMapAlgNode(void) :
00004 algorithm_base::IriBaseAlgorithm<WrinkledMapAlgorithm>()
00005 {
00006
00007
00008
00009
00010 this->heatmap_pointcloud_publisher_ = this->public_node_handle_.advertise<sensor_msgs::PointCloud2>("wrinkled_point_cloud", 1);
00011
00012
00013 this->normal_desc_subscriber_ = this->public_node_handle_.subscribe("descs", 1, &WrinkledMapAlgNode::wrinkleCallback, this);
00014
00015
00016 this->wrinkle_server_ = this->public_node_handle_.advertiseService("wrinkle", &WrinkledMapAlgNode::wrinkleSrvCallback, this);
00017
00018
00019 ndesc_pc_service_client_ = this->public_node_handle_.serviceClient<normal_descriptor_node::ndesc_pc_service>("ndesc_pc_service");
00020
00021
00022
00023
00024 }
00025
00026 WrinkledMapAlgNode::~WrinkledMapAlgNode(void)
00027 {
00028
00029 }
00030
00031 void WrinkledMapAlgNode::mainNodeThread(void)
00032 {
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050 }
00051
00052
00053 void WrinkledMapAlgNode::wrinkleCallback(const normal_descriptor_node::ndesc_pc &descs)
00054 {
00055 pcl::PointCloud<pcl::PointXYZRGB> hmap;
00056 this->alg_.compute_entropy_wrinkled_map(descs, hmap);
00057 pcl::toROSMsg(hmap, this->cloud_out_);
00058
00059 this->cloud_out_.header = descs.header;
00060 this->heatmap_pointcloud_publisher_.publish(this->cloud_out_);
00061 ROS_INFO("wrinkle map published");
00062
00063 }
00064
00065
00066
00067 bool WrinkledMapAlgNode::wrinkleSrvCallback(iri_wrinkled_map::wrinkle::Request &req, iri_wrinkled_map::wrinkle::Response &res)
00068 {
00069 ROS_INFO("WrinkledMapAlgNode::wrinkleCallback: New Request Received!");
00070 pcl::PointCloud<pcl::PointXYZRGB> hmap;
00071 this->ndesc_pc_service_srv_.request.cloth_cloud=req.cloth_cloud;
00072 if(ndesc_pc_service_client_.call(ndesc_pc_service_srv_))
00073 {
00074 this->alg_.compute_entropy_wrinkled_map(ndesc_pc_service_srv_.response.ndesc_pc_msg, hmap);
00075 pcl::toROSMsg(hmap, res.score_map);
00076 res.score_map.header = req.cloth_cloud.header;
00077 }
00078 else
00079 {
00080 return false;
00081 }
00082 return true;
00083 }
00084
00085
00086
00087
00088
00089 void WrinkledMapAlgNode::node_config_update(Config &config, uint32_t level)
00090 {
00091 this->alg_.lock();
00092
00093 this->alg_.unlock();
00094 }
00095
00096 void WrinkledMapAlgNode::addNodeDiagnostics(void)
00097 {
00098 }
00099
00100
00101 int main(int argc,char *argv[])
00102 {
00103 return algorithm_base::main<WrinkledMapAlgNode>(argc, argv, "wrinkled_map_alg_node");
00104 }