00001 // Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC. 00002 // Author 00003 // All rights reserved. 00004 // 00005 // This file is part of iri-ros-pkg 00006 // iri-ros-pkg is free software: you can redistribute it and/or modify 00007 // it under the terms of the GNU Lesser General Public License as published by 00008 // the Free Software Foundation, either version 3 of the License, or 00009 // at your option) any later version. 00010 // 00011 // This program is distributed in the hope that it will be useful, 00012 // but WITHOUT ANY WARRANTY; without even the implied warranty of 00013 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00014 // GNU Lesser General Public License for more details. 00015 // 00016 // You should have received a copy of the GNU Lesser General Public License 00017 // along with this program. If not, see <http://www.gnu.org/licenses/>. 00018 // 00019 // IMPORTANT NOTE: This code has been generated through a script from the 00020 // iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness 00021 // of the scripts. ROS topics can be easly add by using those scripts. Please 00022 // refer to the IRI wiki page for more information: 00023 // http://wikiri.upc.es/index.php/Robotics_Lab 00024 00025 #ifndef _trajectory_scans_2_pointcloud_alg_node_h_ 00026 #define _trajectory_scans_2_pointcloud_alg_node_h_ 00027 00028 #include <iri_base_algorithm/iri_base_algorithm.h> 00029 #include "trajectory_scans_2_pointcloud_alg.h" 00030 #include <Eigen/Dense> 00031 // [publisher subscriber headers] 00032 #include <sensor_msgs/LaserScan.h> 00033 #include <sensor_msgs/PointCloud2.h> 00034 00035 #include <iri_poseslam/Trajectory.h> 00036 00037 #include <pcl/point_types.h> 00038 #include <pcl/point_cloud.h> 00039 #include <pcl_ros/point_cloud.h> 00040 #include <pcl/ros/conversions.h> 00041 #include <pcl_ros/transforms.h> 00042 00043 #include <laser_geometry/laser_geometry.h> 00044 #include <math.h> 00045 00046 // [service client headers] 00047 00048 // [action server client headers] 00049 00050 using namespace Eigen; 00051 00056 class TrajectoryScans2PointcloudAlgNode : public algorithm_base::IriBaseAlgorithm<TrajectoryScans2PointcloudAlgorithm> 00057 { 00058 private: 00059 00060 Matrix4f T_laser_frame; 00061 00062 laser_geometry::LaserProjection laser_projector_; 00063 00064 // [publisher attributes] 00065 ros::Publisher laser_pointcloud_publisher_; 00066 sensor_msgs::PointCloud2 PointCloud_msg_; 00067 bool publish_redundant_; 00068 bool emptyPointCloud_; 00069 00070 // [subscriber attributes] 00071 ros::Subscriber scan_subscriber_; 00072 void scan_callback(const sensor_msgs::LaserScan::ConstPtr& msg); 00073 ros::Subscriber trajectory_subscriber_; 00074 void trajectory_callback(const iri_poseslam::Trajectory::ConstPtr& msg); 00075 00076 // [service attributes] 00077 00078 // [client attributes] 00079 00080 // [action server attributes] 00081 00082 // [action client attributes] 00083 00084 //Buffers 00085 std::vector<sensor_msgs::LaserScan> laser_scan_buffer_; 00086 std::vector<sensor_msgs::LaserScan> trajectory_laser_scan_buffer_; 00087 00088 public: 00095 TrajectoryScans2PointcloudAlgNode(void); 00096 00103 ~TrajectoryScans2PointcloudAlgNode(void); 00104 00105 protected: 00118 void mainNodeThread(void); 00119 00132 void node_config_update(Config &config, uint32_t level); 00133 00140 void addNodeDiagnostics(void); 00141 00142 // [diagnostic functions] 00143 00144 // [test functions] 00152 bool recompute_PointCloud_msg(const iri_poseslam::Trajectory& trajectory); 00153 00161 sensor_msgs::PointCloud2 laser_scan_to_point_cloud(const sensor_msgs::LaserScan& LScan, const geometry_msgs::Pose& pose); 00162 00169 void add_to_PointCloud_msg(const sensor_msgs::PointCloud2& newPointCloud); 00170 00176 void clear_PointCloud_msg(); 00177 00186 Matrix4f transformation_matrix(const float x, const float y, const float z, const float alpha) const; 00187 }; 00188 00189 #endif