Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifndef RVE_RENDER_SERVER_BATCH_RENDERER_H
00031 #define RVE_RENDER_SERVER_BATCH_RENDERER_H
00032
00033 #include <OGRE/OgreMaterial.h>
00034
00035 #include "points_renderer_desc.h"
00036
00037 #include <ros/message_forward.h>
00038
00039 #include <boost/unordered_map.hpp>
00040 #include <boost/random/linear_congruential.hpp>
00041 #include <boost/shared_ptr.hpp>
00042
00043 #include <OGRE/OgreSceneManager.h>
00044 #include <OGRE/OgreSceneNode.h>
00045
00046 namespace rve_common
00047 {
00048 class UUID;
00049 }
00050
00051 namespace rve_render_server
00052 {
00053
00054 template<typename Child, typename Input, typename Renderable, typename Description>
00055 class BatchRenderer
00056 {
00057 private:
00058 typedef boost::shared_ptr<Renderable> RenderablePtr;
00059 typedef std::vector<RenderablePtr> V_Renderable;
00060
00061 struct InputInfo
00062 {
00063 struct RenderableInfo
00064 {
00065 RenderablePtr opaque_rend;
00066 uint32_t opaque_start;
00067 uint32_t opaque_count;
00068
00069 RenderablePtr alpha_rend;
00070 uint32_t alpha_start;
00071 uint32_t alpha_count;
00072 };
00073
00074 std::vector<RenderableInfo> rends;
00075 };
00076
00077 typedef boost::unordered_map<uint32_t, InputInfo> M_InputInfo;
00078
00079 public:
00080 BatchRenderer(Ogre::SceneManager* scene_manager, const Description& desc)
00081 : desc_(desc)
00082 , scene_manager_(scene_manager)
00083 , scene_node_(0)
00084 {
00085 std::pair<Ogre::MaterialPtr, Ogre::MaterialPtr> mats = static_cast<Child*>(this)->createMaterials(desc);
00086 opaque_material_ = mats.first;
00087 alpha_material_ = mats.second;
00088
00089 scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00090
00091 id_gen_.seed(time(0));
00092 }
00093
00094 ~BatchRenderer()
00095 {
00096 scene_manager_->destroySceneNode(scene_node_);
00097 }
00098
00099 uint32_t add(const rve_common::UUID& id, const Input& input)
00100 {
00101 InputInfo pinfo;
00102
00103 uint32_t total_count = 0;
00104 uint32_t total_opaque_count = 0;
00105 uint32_t total_alpha_count = 0;
00106 uint32_t input_count = static_cast<Child*>(this)->getInputCount(input);
00107 while (total_count < input_count)
00108 {
00109
00110 RenderablePtr opaque_rend = getOrCreateRenderable(false);
00111
00112 uint32_t opaque_count = 0;
00113 uint32_t opaque_start = 0;
00114 opaque_rend->add(id, input, total_opaque_count, opaque_start, opaque_count);
00115 total_opaque_count += opaque_count;
00116
00117
00118 RenderablePtr alpha_rend = getOrCreateRenderable(true);
00119
00120 uint32_t alpha_count = 0;
00121 uint32_t alpha_start = 0;
00122 alpha_rend->add(id, input, total_alpha_count, alpha_start, alpha_count);
00123 total_alpha_count += alpha_count;
00124
00125 total_count = total_alpha_count + total_opaque_count;
00126
00127 typename InputInfo::RenderableInfo rinfo;
00128 rinfo.opaque_rend = opaque_rend;
00129 rinfo.opaque_start = opaque_start;
00130 rinfo.opaque_count = opaque_count;
00131 rinfo.alpha_rend = alpha_rend;
00132 rinfo.alpha_start = alpha_start;
00133 rinfo.alpha_count = alpha_count;
00134 pinfo.rends.push_back(rinfo);
00135 }
00136
00137 uint32_t internal_id = 0;
00138
00139 while (internal_id == 0 || !points_.insert(std::make_pair(internal_id, pinfo)).second)
00140 {
00141 internal_id = id_gen_();
00142 }
00143
00144 scene_node_->needUpdate();
00145
00146 return internal_id;
00147 }
00148
00149 void remove(uint32_t id)
00150 {
00151 typename M_InputInfo::iterator it = points_.find(id);
00152 if (it == points_.end())
00153 {
00154 return;
00155 }
00156
00157 const InputInfo& pinfo = it->second;
00158 for (size_t i = 0; i < pinfo.rends.size(); ++i)
00159 {
00160 const typename InputInfo::RenderableInfo& rinfo = pinfo.rends[i];
00161 rinfo.opaque_rend->remove(rinfo.opaque_start, rinfo.opaque_count);
00162 rinfo.alpha_rend->remove(rinfo.alpha_start, rinfo.alpha_count);
00163 }
00164
00165 points_.erase(it);
00166
00167 shrinkRenderables();
00168
00169 scene_node_->needUpdate();
00170 }
00171
00172 void clear()
00173 {
00174 points_.clear();
00175 renderables_.clear();
00176
00177 scene_node_->needUpdate();
00178 }
00179
00180 private:
00181 RenderablePtr getOrCreateRenderable(bool alpha)
00182 {
00183 typename V_Renderable::iterator it = renderables_.begin();
00184 typename V_Renderable::iterator end = renderables_.end();
00185 for (; it != end; ++it)
00186 {
00187 const RenderablePtr& rend = *it;
00188 if (!rend->isFull() && alpha == rend->isAlpha())
00189 {
00190 return rend;
00191 }
00192 }
00193
00194 RenderablePtr rend(new Renderable(desc_, alpha));
00195 rend->setMaterial(alpha ? alpha_material_->getName() : opaque_material_->getName());
00196 scene_node_->attachObject(rend.get());
00197 renderables_.push_back(rend);
00198
00199 return rend;
00200 }
00201
00202 void shrinkRenderables()
00203 {
00204 uint32_t empty_count = 0;
00205 typename V_Renderable::iterator it = renderables_.begin();
00206 for (; it != renderables_.end();)
00207 {
00208 const RenderablePtr& rend = *it;
00209 if (rend->isEmpty())
00210 {
00211 ++empty_count;
00212 }
00213 else
00214 {
00215 ++it;
00216 continue;
00217 }
00218
00219
00220 if (empty_count > 0)
00221 {
00222 it = renderables_.erase(it);
00223 }
00224 else
00225 {
00226 ++it;
00227 }
00228 }
00229
00230 scene_node_->needUpdate();
00231 }
00232
00233 M_InputInfo points_;
00234 boost::rand48 id_gen_;
00235
00236 Description desc_;
00237 Ogre::SceneManager* scene_manager_;
00238
00239 V_Renderable renderables_;
00240
00241 Ogre::MaterialPtr opaque_material_;
00242 Ogre::MaterialPtr alpha_material_;
00243 Ogre::SceneNode* scene_node_;
00244 };
00245
00246 }
00247
00248 #endif // RVE_RENDER_SERVER_BATCH_RENDERER_H