facing_visualizer.h
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Willow Garage nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 
00037 #ifndef JSK_RVIZ_PLUGIN_FACING_VISUALIZER_H_
00038 #define JSK_RVIZ_PLUGIN_FACING_VISUALIZER_H_
00039 
00040 #include <OGRE/OgreTexture.h>
00041 #include <OGRE/OgreSceneManager.h>
00042 #include <OGRE/OgreSceneNode.h>
00043 #include <OGRE/OgreTexture.h>
00044 #include <OGRE/OgreMaterial.h>
00045 #include <OGRE/OgreManualObject.h>
00046 #include <rviz/display_context.h>
00047 #include <ros/time.h>
00048 #include <rviz/ogre_helpers/billboard_line.h>
00049 #include <rviz/ogre_helpers/movable_text.h>
00050 #include "overlay_utils.h"
00051 
00052 namespace jsk_rviz_plugin
00053 {
00054 
00055   // outer radius
00056   // inner radius
00057   class SquareObject
00058   {
00059   public:
00060     typedef boost::shared_ptr<SquareObject> Ptr;
00061     SquareObject(Ogre::SceneManager* manager,
00062                  double outer_radius,
00063                  double inner_radius,
00064                  std::string name);
00065     virtual ~SquareObject();
00066     virtual Ogre::ManualObject* getManualObject();
00067     virtual void setOuterRadius(double outer_radius);
00068     virtual void setInnerRadius(double inner_radius);
00069     virtual void rebuildPolygon();
00070   protected:
00071     Ogre::ManualObject* manual_;
00072     Ogre::SceneManager* manager_;
00073     double outer_radius_;
00074     double inner_radius_;
00075     std::string name_;
00076   private:
00077   };
00078 
00079   class TextureObject           // utility class for texture
00080   {
00081   public:
00082     typedef boost::shared_ptr<TextureObject> Ptr;
00083     TextureObject(const int width, const int height, const std::string name);
00084     virtual ~TextureObject();
00085     virtual int getWidth() { return width_; };
00086     virtual int getHeight() { return height_; };
00087     virtual ScopedPixelBuffer getBuffer();
00088     virtual std::string getMaterialName();
00089   protected:
00090     Ogre::TexturePtr texture_;
00091     Ogre::MaterialPtr material_;
00092     const int width_;
00093     const int height_;
00094     const std::string name_;
00095   private:
00096     
00097   };
00098 
00099   class FacingObject
00100   {
00101   public:
00102     typedef boost::shared_ptr<FacingObject> Ptr;
00103     FacingObject(Ogre::SceneManager* manager,
00104                  Ogre::SceneNode* parent,
00105                  double size);
00106     virtual ~FacingObject();
00107     virtual void setPosition(Ogre::Vector3& pos);
00108     virtual void setOrientation(rviz::DisplayContext* context);
00109     virtual void update(float wall_dt, float ros_dt) = 0;
00110     virtual void setSize(double size);
00111     virtual void setEnable(bool enable);
00112     virtual void setColor(QColor color);
00113     virtual void setColor(Ogre::ColourValue color);
00114     virtual void setText(std::string text);
00115     virtual void setAlpha(double alpha);
00116   protected:
00117     virtual void updateColor() = 0;
00118     virtual void updateText() = 0;
00119     Ogre::SceneManager* scene_manager_;
00120     Ogre::SceneNode* node_;
00121     Ogre::ColourValue color_;
00122     double size_;
00123     bool enable_;
00124     std::string text_;
00125   private:
00126     
00127   };
00128 
00129   class SimpleCircleFacingVisualizer: public FacingObject
00130   {
00131   public:
00132     typedef boost::shared_ptr<SimpleCircleFacingVisualizer> Ptr;
00133     SimpleCircleFacingVisualizer(Ogre::SceneManager* manager,
00134                                  Ogre::SceneNode* parent,
00135                                  rviz::DisplayContext* context,
00136                                  double size,
00137                                  std::string text = "");
00138     virtual ~SimpleCircleFacingVisualizer();
00139     virtual void update(float wall_dt, float ros_dt);
00140     virtual void reset();
00141     
00142     virtual void setSize(double size);
00143     virtual void setEnable(bool enable);
00144     virtual void setText(std::string text);
00145   protected:
00146     virtual void updateArrowsObjects(Ogre::ColourValue color);
00147     virtual void createArrows(rviz::DisplayContext* context);
00148     virtual void updateLine();
00149     virtual void updateTextUnderLine();
00150     virtual void updateText();
00151     virtual void updateColor();
00152     rviz::BillboardLine* line_;
00153     rviz::BillboardLine* text_under_line_;
00154     Ogre::ManualObject* upper_arrow_;
00155     Ogre::ManualObject* lower_arrow_;
00156     Ogre::ManualObject* left_arrow_;
00157     Ogre::ManualObject* right_arrow_;
00158     Ogre::SceneNode* upper_arrow_node_;
00159     Ogre::SceneNode* lower_arrow_node_;
00160     Ogre::SceneNode* left_arrow_node_;
00161     Ogre::SceneNode* right_arrow_node_;
00162     Ogre::MaterialPtr upper_material_;
00163     Ogre::MaterialPtr lower_material_;
00164     Ogre::MaterialPtr left_material_;
00165     Ogre::MaterialPtr right_material_;
00166     std::string upper_material_name_;
00167     std::string left_material_name_;
00168     std::string lower_material_name_;
00169     std::string right_material_name_;
00170     rviz::MovableText* msg_;
00171     Ogre::SceneNode* target_text_node_;
00172   private:
00173     
00174   };
00175   
00176   class FacingTexturedObject: public FacingObject
00177   {
00178   public:
00179     typedef boost::shared_ptr<FacingTexturedObject> Ptr;
00180     FacingTexturedObject(Ogre::SceneManager* manager,
00181                          Ogre::SceneNode* parent,
00182                          double size);
00183     virtual void setSize(double size);
00184   protected:
00185     SquareObject::Ptr square_object_;
00186     TextureObject::Ptr texture_object_;
00187 
00188   private:
00189     
00190   };
00191 
00192   
00193   class GISCircleVisualizer: public FacingTexturedObject
00194   {
00195   public:
00196     typedef boost::shared_ptr<GISCircleVisualizer> Ptr;
00197     GISCircleVisualizer(Ogre::SceneManager* manager,
00198                         Ogre::SceneNode* parent,
00199                         double size,
00200                         std::string text = "");
00201     virtual void setText(std::string text) { text_ = text; }
00202     virtual void update(float wall_dt, float ros_dt);
00203     virtual void setAnonymous(bool anonymous);
00204   protected:
00205     virtual void updateColor() {}
00206     virtual void updateText() {}
00207     virtual void setSize(double size);
00208     bool anonymous_;
00209     std::string text_;
00210   private:
00211   };
00212   
00213 }
00214 
00215 #endif


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Mon Oct 6 2014 01:18:44