renderer.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2010, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #ifndef RVE_RENDER_SERVER_RENDERER_H
00031 #define RVE_RENDER_SERVER_RENDERER_H
00032 
00033 #include <string>
00034 #include <vector>
00035 #include <map>
00036 
00037 #include <boost/unordered_map.hpp>
00038 #include <boost/random/linear_congruential.hpp>
00039 #include <boost/thread/thread.hpp>
00040 #include <boost/thread/mutex.hpp>
00041 
00042 #include <rve_common/uuid.h>
00043 
00044 #include <ros/publisher.h>
00045 #include <ros/subscriber.h>
00046 #include <ros/message_forward.h>
00047 
00048 namespace ros
00049 {
00050 class CallbackQueue;
00051 }
00052 
00053 namespace std_msgs
00054 {
00055 ROS_DECLARE_MESSAGE(Empty);
00056 }
00057 
00058 namespace Ogre
00059 {
00060 class RenderWindow;
00061 }
00062 
00063 namespace rve_render_server
00064 {
00065 
00066 class RenderWindow;
00067 class RenderTexture;
00068 class RenderTarget;
00069 class Scene;
00070 class Camera;
00071 class Material;
00072 typedef boost::shared_ptr<Material> MaterialPtr;
00073 class Texture;
00074 typedef boost::shared_ptr<Texture> TexturePtr;
00075 class Mesh;
00076 typedef boost::shared_ptr<Mesh> MeshPtr;
00077 class DisableRenderingSchemeListener;
00078 typedef boost::shared_ptr<DisableRenderingSchemeListener> DisableRenderingSchemeListenerPtr;
00079 class Pickable;
00080 struct PickRenderValues;
00081 typedef std::vector<PickRenderValues> V_PickRenderValues;
00082 struct Picked;
00083 typedef std::vector<Picked> V_Picked;
00084 
00085 class Renderer;
00086 Renderer* getRenderer();
00087 
00088 class Renderer
00089 {
00090 public:
00091   Renderer(bool enable_ogre_log);
00092   ~Renderer();
00093 
00094   void start();
00095   void stop();
00096 
00097    void destroyRenderTarget(const rve_common::UUID& id);
00098    RenderTarget* getRenderTarget(const rve_common::UUID& id);
00099 
00100    RenderTexture* createRenderTexture(const rve_common::UUID& id, uint32_t width, uint32_t height);
00101    RenderWindow* createRenderWindow(const rve_common::UUID& id, const std::string& parent_window, uint32_t width, uint32_t height);
00102    RenderWindow* getRenderWindow(const rve_common::UUID& id);
00103 
00104    Scene* createScene(const rve_common::UUID& id);
00105    void destroyScene(const rve_common::UUID& id);
00106    Scene* getScene(const rve_common::UUID& id);
00107 
00108    Camera* getCamera(const rve_common::UUID& id);
00109 
00110    ros::CallbackQueue* getServerThreadCallbackQueue() { return callback_queue_.get(); }
00111 
00112    void addMaterial(const rve_common::UUID& id, const MaterialPtr& mat);
00113    void removeMaterial(const rve_common::UUID& id);
00114    MaterialPtr getMaterial(const rve_common::UUID& id);
00115 
00116    void addMesh(const rve_common::UUID& id, const MeshPtr& mesh);
00117    void removeMesh(const rve_common::UUID& id);
00118    MeshPtr getMesh(const rve_common::UUID& id);
00119    bool meshExists(const rve_common::UUID& id);
00120 
00121    void addTexture(const rve_common::UUID& id, const TexturePtr& tex);
00122    void removeTexture(const rve_common::UUID& id);
00123    TexturePtr getTexture(const rve_common::UUID& id);
00124    bool textureExists(const rve_common::UUID& id);
00125 
00126    bool useGeometryShaders();
00127 
00128    uint32_t allocatePickID(Pickable* p);
00129    void deallocatePickID(uint32_t pick_id);
00130    void translatePickIDs(const V_PickRenderValues& ids, V_Picked& out_picked);
00131 
00132    typedef boost::function<void(void)> InitFunction;
00133    void registerInitFunction(const InitFunction& func);
00134 
00135 private:
00136   void init();
00137   void renderThread();
00138 
00139   void threadInit();
00140 
00141 #if USE_NVPERFSDK
00142   void doExperimentCallback(const std_msgs::EmptyConstPtr&);
00143 #endif
00144 
00145   boost::thread render_thread_;
00146   bool running_;
00147   bool first_window_created_;
00148   bool enable_ogre_log_;
00149   Ogre::RenderWindow* primary_render_window_;
00150 
00151   typedef boost::shared_ptr<RenderTarget> RenderTargetPtr;
00152   typedef std::map<rve_common::UUID, RenderTargetPtr> M_RenderTarget;
00153   M_RenderTarget render_targets_;
00154 
00155   typedef boost::shared_ptr<Scene> ScenePtr;
00156   typedef std::map<rve_common::UUID, ScenePtr> M_Scene;
00157   M_Scene scenes_;
00158 
00159   typedef boost::shared_ptr<ros::CallbackQueue> CallbackQueuePtr;
00160   CallbackQueuePtr callback_queue_;
00161 
00162   typedef std::map<rve_common::UUID, MaterialPtr> M_Material;
00163   M_Material materials_;
00164 
00165   typedef std::map<rve_common::UUID, TexturePtr> M_Texture;
00166   M_Texture textures_;
00167 
00168   typedef std::map<rve_common::UUID, MeshPtr> M_Mesh;
00169   M_Mesh meshes_;
00170 
00171   typedef boost::unordered_map<uint32_t, Pickable*> M_Pickable;
00172   M_Pickable pickables_;
00173   boost::rand48 pickable_id_gen_;
00174 
00175   DisableRenderingSchemeListenerPtr scheme_listener_;
00176 
00177   ros::Publisher frame_stats_pub_;
00178 
00179   std::vector<InitFunction> init_functions_;
00180 
00181 #if USE_NVPERFSDK
00182   bool nvperfsdk_initialized_;
00183   bool do_experiment_;
00184   bool start_experiment_;
00185 
00186   ros::Subscriber do_experiment_sub_;
00187   ros::Publisher experiment_stats_pub_;
00188 #endif
00189 };
00190 
00191 } // namespace rve_render_server
00192 
00193 #endif // RVE_RENDER_SERVER_RENDERER_H


rve_render_server
Author(s): Josh Faust
autogenerated on Wed Dec 11 2013 14:31:15