Jafar
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines
visualizers.hpp
00001 #ifndef VELODYNEUTILS_VISUALIZERS_HPP
00002 #define VELODYNEUTILS_VISUALIZERS_HPP
00003 
00004 #include <string>
00005 #include <vector>
00006 
00007 #include <boost/shared_ptr.hpp>
00008 #include <pcl/pcl_base.h>
00009 #include <pcl/visualization/pcl_visualizer.h>
00010 
00011 namespace jafar {
00012 namespace velodyneutils {
00013 
00017 template<typename PointT>
00018 class VisualizerCloud : public pcl::PCLBase<PointT> {
00019 public:
00020     typedef typename pcl::PCLBase<PointT> BaseClass;
00021     typedef typename BaseClass::PointCloudConstPtr PointCloudConstPtr;
00022     typedef pcl::visualization::PointCloudColorHandlerGenericField<PointT>
00023             ColorHandler;
00024     typedef typename ColorHandler::Ptr ColorHandlerPtr;
00025     typedef boost::shared_ptr<VisualizerCloud> Ptr;
00026     typedef boost::shared_ptr<const VisualizerCloud> ConstPtr;
00027 
00028     VisualizerCloud(pcl::visualization::PCLVisualizer* visualizerIn,
00029                     const std::string& idIn);
00030     ~VisualizerCloud();
00031 
00032     void setInputCloud(const PointCloudConstPtr& input);
00033     int addHandler(const std::string& handlerField);
00034     int setHandler(int handlerNum);
00035     int switchOn(bool on);
00036     int visualize();
00037 
00038 private:
00039     pcl::visualization::PCLVisualizer* visualizer;
00040     std::vector<std::string> handlersFields;
00041     std::vector<ColorHandlerPtr> handlers;
00042     int handlerNum;
00043     bool add;
00044     bool remove;
00045     bool on;
00046     std::string id;
00047 
00048     int findHandler(const std::string& handlerField) const;
00049     void updateHandlers();
00050     bool initCompute();
00051 };
00052 
00056 template<typename PointT>
00057 class VisualizerNormals : public pcl::PCLBase<PointT> {
00058 public:
00059     typedef typename pcl::PCLBase<PointT> BaseClass;
00060     typedef typename BaseClass::PointCloudConstPtr PointCloudConstPtr;
00061     typedef boost::shared_ptr<VisualizerNormals> Ptr;
00062     typedef boost::shared_ptr<const VisualizerNormals> ConstPtr;
00063 
00064     VisualizerNormals(pcl::visualization::PCLVisualizer* visualizerIn,
00065                       const std::string& idIn);
00066     ~VisualizerNormals();
00067 
00068     void setInputCloud(const PointCloudConstPtr& input);
00069     int switchOn(bool on);
00070     int visualize();
00071 
00072 private:
00073     pcl::visualization::PCLVisualizer* visualizer;
00074     bool add;
00075     bool remove;
00076     bool on;
00077     std::string id;
00078 
00079     bool initCompute();
00080 };
00081 
00082 } // namespace velodyneutils
00083 } // namespace jafar
00084 
00085 #endif // VELODYNEUTILS_VISUALIZERS_HPP
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines

Generated on Wed Oct 15 2014 00:37:29 for Jafar by doxygen 1.7.6.1
LAAS-CNRS