point_cloud_conversions.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010--2012,
00003 François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland
00004 You can contact the authors at <f dot pomerleau at gmail dot com> and
00005 <stephane at magnenat dot net>
00006 All rights reserved.
00007 Redistribution and use in source and binary forms, with or without
00008 modification, are permitted provided that the following conditions are met:
00009  * Redistributions of source code must retain the above copyright
00010       notice, this list of conditions and the following disclaimer.
00011  * Redistributions in binary form must reproduce the above copyright
00012       notice, this list of conditions and the following disclaimer in the
00013       documentation and/or other materials provided with the distribution.
00014  * Neither the name of the <organization> nor the
00015       names of its contributors may be used to endorse or promote products
00016       derived from this software without specific prior written permission.
00017 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00018 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00019 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00020 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
00021 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 
00028  * point_cloud_conversions.h -> Modification
00029  *
00030  *      Author: roberto
00031  *
00032  * This is a modified implementation of the method for online estimation of kinematic structures described in our paper
00033  * "Online Interactive Perception of Articulated Objects with Multi-Level Recursive Estimation Based on Task-Specific Priors"
00034  * (Martín-Martín and Brock, 2014) and the extension to segment, reconstruct and track shapes introduced in our paper
00035  * "An Integrated Approach to Visual Perception of Articulated Objects" (Martín-Martín, Höfer and Brock, 2016)
00036  * This implementation can be used to reproduce the results of the paper and to be applied to new research.
00037  * The implementation allows also to be extended to perceive different information/models or to use additional sources of information.
00038  * A detail explanation of the method and the system can be found in our paper.
00039  *
00040  * If you are using this implementation in your research, please consider citing our work:
00041  *
00042 @inproceedings{martinmartin_ip_iros_2014,
00043 Title = {Online Interactive Perception of Articulated Objects with Multi-Level Recursive Estimation Based on Task-Specific Priors},
00044 Author = {Roberto {Mart\'in-Mart\'in} and Oliver Brock},
00045 Booktitle = {Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems},
00046 Pages = {2494-2501},
00047 Year = {2014},
00048 Location = {Chicago, Illinois, USA},
00049 Note = {http://www.robotics.tu-berlin.de/fileadmin/fg170/Publikationen_pdf/martinmartin_ip_iros_2014.pdf},
00050 Url = {http://www.robotics.tu-berlin.de/fileadmin/fg170/Publikationen_pdf/martinmartin_ip_iros_2014.pdf},
00051 Projectname = {Interactive Perception}
00052 }
00053 
00054 @inproceedings{martinmartin_hoefer_iros_2016,
00055 Title = {An Integrated Approach to Visual Perception of Articulated Objects},
00056 Author = {Roberto {Mart\'{i}n-Mart\'{i}n} and Sebastian H\"ofer and Oliver Brock},
00057 Booktitle = {Proceedings of the IEEE International Conference on Robotics and Automation},
00058 Pages = {5091 - 5097},
00059 Year = {2016},
00060 Doi = {10.1109/ICRA.2016.7487714},
00061 Location = {Stockholm, Sweden},
00062 Month = {05},
00063 Note = {http://www.redaktion.tu-berlin.de/fileadmin/fg170/Publikationen_pdf/martin_hoefer_15_iros_sr_opt.pdf},
00064 Url = {http://www.redaktion.tu-berlin.de/fileadmin/fg170/Publikationen_pdf/martin_hoefer_15_iros_sr_opt.pdf},
00065 Url2 = {http://ieeexplore.ieee.org/xpl/articleDetails.jsp?tp=&arnumber=7487714},
00066 Projectname = {Interactive Perception}
00067 }
00068  * If you have questions or suggestions, contact us:
00069  * roberto.martinmartin@tu-berlin.de
00070  *
00071  * Enjoy!
00072  */
00073 
00074 
00075 #ifndef __POINTMATCHER_ROS_POINT_CLOUD_H
00076 #define __POINTMATCHER_ROS_POINT_CLOUD_H
00077 
00078 #include "pointmatcher/PointMatcher.h"
00079 #include "sensor_msgs/PointCloud2.h"
00080 #include "sensor_msgs/LaserScan.h"
00081 
00082 namespace ros
00083 {
00084         struct Time;
00085 };
00086 namespace tf
00087 {
00088         struct TransformListener;
00089 };
00090 
00091 namespace PointMatcher_ros
00092 {
00093         template<typename T>
00094         typename PointMatcher<T>::DataPoints rosMsgToPointMatcherCloud(const sensor_msgs::PointCloud2& rosMsg);
00095         
00096         template<typename T>
00097         typename PointMatcher<T>::DataPoints rosMsgToPointMatcherCloud(const sensor_msgs::LaserScan& rosMsg, const tf::TransformListener* listener = 0, const std::string& fixed_frame = "/world", const bool force3D = false, const bool addTimestamps=false);
00098         
00099         template<typename T>
00100         sensor_msgs::PointCloud2 pointMatcherCloudToRosMsg(const typename PointMatcher<T>::DataPoints& pmCloud, const std::string& frame_id, const ros::Time& stamp);
00101 }
00102 
00103 #endif //__POINTMATCHER_ROS_POINT_CLOUD_H


shape_tracker
Author(s): Roberto Martín-Martín
autogenerated on Sat Jun 8 2019 18:54:11