render_target.cpp
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 #include "rve_render_server/render_target.h"
00031 #include "rve_render_server/camera.h"
00032 #include "rve_render_server/renderer.h"
00033 #include "rve_render_server/init.h"
00034 #include "rve_render_server/server.h"
00035 #include "rve_render_server/pickable.h"
00036 #include "rve_render_server/screen_rect.h"
00037 
00038 #include <OGRE/OgreRenderTarget.h>
00039 #include <OGRE/OgreTextureManager.h>
00040 #include <OGRE/OgreMaterialManager.h>
00041 #include <OGRE/OgreTechnique.h>
00042 #include <OGRE/OgrePass.h>
00043 #include <OGRE/OgreTextureUnitState.h>
00044 #include <OGRE/OgreRoot.h>
00045 #include <OGRE/OgreRenderSystem.h>
00046 #include <OGRE/OgreRenderTarget.h>
00047 #include <OGRE/OgreRenderTexture.h>
00048 #include <OGRE/OgreHardwarePixelBuffer.h>
00049 #include <OGRE/OgreRectangle2D.h>
00050 #include <OGRE/OgreSceneManager.h>
00051 #include <OGRE/OgreSceneNode.h>
00052 #include <OGRE/OgreSceneQuery.h>
00053 
00054 #include <ros/assert.h>
00055 #include <ros/ros.h>
00056 #include <sensor_msgs/Image.h>
00057 #include <sensor_msgs/image_encodings.h>
00058 
00059 #include <boost/foreach.hpp>
00060 
00061 
00062 using namespace rve_common;
00063 
00064 namespace rve_render_server
00065 {
00066 
00067 std::string dashToUnderscore(const std::string& str)
00068 {
00069   std::string out = str;
00070   for (size_t i = 0; i < out.size(); ++i)
00071   {
00072     if (out[i] == '-')
00073     {
00074       out[i] = '_';
00075     }
00076   }
00077 
00078   return out;
00079 }
00080 
00081 class RenderTargetToROSImage
00082 {
00083 public:
00084   RenderTargetToROSImage(Ogre::RenderTarget* target, const std::string& name)
00085   {
00086     setTarget(target);
00087     pub_ = getServer()->getNodeHandle().advertise<sensor_msgs::Image>("render_targets/" + name, 1);
00088   }
00089 
00090   void setTarget(Ogre::RenderTarget* target)
00091   {
00092     target_ = target;
00093   }
00094 
00095   ~RenderTargetToROSImage()
00096   {
00097   }
00098 
00099   void update()
00100   {
00101     if (pub_.getNumSubscribers() == 0)
00102     {
00103       return;
00104     }
00105 
00106     uint32_t width = target_->getWidth();
00107     uint32_t height = target_->getHeight();
00108 
00109     sensor_msgs::ImagePtr image(new sensor_msgs::Image);
00110     image->encoding = sensor_msgs::image_encodings::RGBA8;
00111     image->width = width;
00112     image->height = height;
00113     image->step = width * 4;
00114     image->data.resize(image->step * height);
00115 
00116     Ogre::PixelBox pbox(width, height, 1, Ogre::PF_BYTE_RGBA, &image->data.front());
00117     target_->copyContentsToMemory(pbox, Ogre::RenderTarget::FB_FRONT);
00118     pub_.publish(image);
00119   }
00120 
00121 private:
00122 
00123   Ogre::RenderTarget* target_;
00124   ros::Publisher pub_;
00125 };
00126 
00127 
00128 
00129 RenderTarget::RenderTarget(const rve_common::UUID& id, Renderer* rend, uint32_t width, uint32_t height)
00130 : id_(id)
00131 , final_target_(0)
00132 , renderer_(rend)
00133 , cam_(0)
00134 , width_(width)
00135 , height_(height)
00136 , recreate_resources_(false)
00137 , screen_rect_(0)
00138 , picked_(false)
00139 , pick_target_updated_this_frame_(false)
00140 , pick_buffer_valid_(false)
00141 , pick_scene_query_(0)
00142 , render_needed_(false)
00143 , render_in_progress_(false)
00144 {
00145   screen_rect_ = new Ogre::Rectangle2D(true);
00146   screen_rect_->setCorners(-1, 1, 1, -1, false);
00147   screen_rect_->setBoundingBox(Ogre::AxisAlignedBox::BOX_INFINITE);
00148 
00149   std::stringstream ss;
00150   ss << getID() << "RectMaterial";
00151   rect_material_ = Ogre::MaterialManager::getSingleton().getByName("DeferredShading/DeferredWithWeightedFinal", ROS_PACKAGE_NAME);
00152   rect_material_ = rect_material_->clone(ss.str());
00153   screen_rect_->setMaterial(rect_material_->getName());
00154 
00155   createResources();
00156 
00157   stats_.id = getID();
00158 }
00159 
00160 RenderTarget::~RenderTarget()
00161 {
00162   if (cam_)
00163   {
00164     cam_->removeRenderTarget(this);
00165   }
00166 
00167   destroyResources();
00168 
00169   {
00170     V_ScreenRect::iterator it = screen_rects_.begin();
00171     V_ScreenRect::iterator end = screen_rects_.end();
00172     for (; it != end; ++it)
00173     {
00174       delete *it;
00175     }
00176     screen_rects_.clear();
00177   }
00178 }
00179 
00180 void RenderTarget::setTarget(Ogre::RenderTarget* target)
00181 {
00182   if (!final_target_)
00183   {
00184     final_target_out_.reset(new RenderTargetToROSImage(final_target_, dashToUnderscore(getID().toString())));
00185   }
00186 
00187   final_target_ = target;
00188   final_target_out_->setTarget(final_target_);
00189 }
00190 
00191 void RenderTarget::destroyMRT(MRT& mrt)
00192 {
00193   uint32_t count = mrt.textures.size() - 1;
00194 
00195   Ogre::Root::getSingleton().getRenderSystem()->destroyRenderTarget(mrt.mrt->getName());
00196 
00197   V_OgreTexture::reverse_iterator it = mrt.textures.rbegin();
00198   V_OgreTexture::reverse_iterator end = mrt.textures.rend();
00199   for (; it != end; ++it, --count)
00200   {
00201     Ogre::TexturePtr& tex = *it;
00202     Ogre::TextureManager::getSingleton().remove(tex->getName());
00203   }
00204 
00205   mrt.textures.clear();
00206   mrt.rtts.clear();
00207   mrt.mrt = 0;
00208 }
00209 
00210 void RenderTarget::destroyResources()
00211 {
00212   destroyMRT(gbuffer_target_);
00213   destroyMRT(weighted_average_alpha_target_);
00214 
00215   // Only destroy the picking MRT if it exists
00216   if (picked_)
00217   {
00218     destroyMRT(picking_target_);
00219   }
00220 }
00221 
00222 void RenderTarget::createMRT(MRT& mrt, const std::string& name, const std::string& scheme, uint32_t format)
00223 {
00224   std::stringstream ss;
00225   ss << getID() << "_" << name;
00226   mrt.mrt = Ogre::Root::getSingleton().getRenderSystem()->createMultiRenderTarget(ss.str());
00227   mrt.mrt->setAutoUpdated(false);
00228   mrt.mrt->setActive(true);
00229 
00230   mrt.ros_output.resize(2);
00231   for (uint32_t i = 0; i < 2; ++i)
00232   {
00233     std::stringstream ss2;
00234     ss2 << ss.str() << "rt" << i;
00235     mrt.textures.push_back(Ogre::TextureManager::getSingleton().createManual(ss2.str(), ROS_PACKAGE_NAME, Ogre::TEX_TYPE_2D, width_, height_, 0, (Ogre::PixelFormat)format, Ogre::TU_RENDERTARGET));
00236     mrt.rtts.push_back(mrt.textures[i]->getBuffer()->getRenderTarget());
00237     mrt.mrt->bindSurface(i, mrt.rtts[i]);
00238 
00239     if (!mrt.ros_output[i])
00240     {
00241       mrt.ros_output[i].reset(new RenderTargetToROSImage(mrt.rtts[i], dashToUnderscore(ss2.str())));
00242     }
00243     else
00244     {
00245       mrt.ros_output[i]->setTarget(mrt.rtts[i]);
00246     }
00247   }
00248 
00249   setupRT(mrt.mrt);
00250   if (mrt.mrt->getNumViewports())
00251   {
00252     mrt.mrt->getViewport(0)->setMaterialScheme(scheme);
00253   }
00254 }
00255 
00256 void RenderTarget::createResources()
00257 {
00258   createMRT(gbuffer_target_, "gbuffer", "GBuffer", Ogre::PF_FLOAT16_RGBA);
00259   createMRT(weighted_average_alpha_target_, "waa", "WeightedAverageAlpha", Ogre::PF_FLOAT16_RGBA);
00260 
00261   // Only create the picking MRT and buffer if we've been asked to pick before
00262   if (picked_)
00263   {
00264     createMRT(picking_target_, "pick", "Pick", Ogre::PF_BYTE_RGBA);
00265     pick_buffer_.reset(new uint32_t[width_ * height_ * 2]);
00266   }
00267 
00268   rect_material_->getTechnique(0)->getPass(0)->getTextureUnitState(0)->setTextureName(gbuffer_target_.textures[0]->getName());
00269   rect_material_->getTechnique(0)->getPass(0)->getTextureUnitState(1)->setTextureName(gbuffer_target_.textures[1]->getName());
00270   rect_material_->getTechnique(0)->getPass(0)->getTextureUnitState(2)->setTextureName(weighted_average_alpha_target_.textures[0]->getName());
00271   rect_material_->getTechnique(0)->getPass(0)->getTextureUnitState(3)->setTextureName(weighted_average_alpha_target_.textures[1]->getName());
00272 }
00273 
00274 void RenderTarget::setupRT(Ogre::RenderTarget* rt)
00275 {
00276   rt->removeAllViewports();
00277 
00278   if (cam_)
00279   {
00280     Ogre::Viewport* vp = rt->addViewport(cam_->getOgreCamera());
00281     ROS_INFO("RenderTarget::setupRT() ogre_viewport size: %d x %d",
00282              vp->getActualWidth(), vp->getActualHeight());
00283     vp->setBackgroundColour(Ogre::ColourValue(0.0, 0.0, 0.0, 0.0));
00284     vp->setClearEveryFrame(false);
00285     vp->setOverlaysEnabled(false);
00286   }
00287 }
00288 
00289 const rve_common::UUID& RenderTarget::getID()
00290 {
00291   return id_;
00292 }
00293 
00294 void RenderTarget::resize(uint32_t width, uint32_t height)
00295 {
00296   width_ = width;
00297   height_ = height;
00298 
00299   recreate_resources_ = true;
00300 }
00301 
00302 void RenderTarget::attachCamera(Camera* cam)
00303 {
00304   if (cam_ && pick_scene_query_)
00305   {
00306     cam_->getOgreCamera()->getSceneManager()->destroyQuery(pick_scene_query_);
00307   }
00308 
00309   if (cam_ && !cam)
00310   {
00311     destroyResources();
00312     cam_ = 0;
00313     createResources();
00314     return;
00315   }
00316 
00317   cam_ = cam;
00318 
00319   setupRT(gbuffer_target_.mrt);
00320   setupRT(weighted_average_alpha_target_.mrt);
00321   setupRT(final_target_);
00322 
00323   if (picked_)
00324   {
00325     setupRT(picking_target_.mrt);
00326     pick_scene_query_ = cam_->getOgreCamera()->getSceneManager()->createPlaneBoundedVolumeQuery(Ogre::PlaneBoundedVolumeList());
00327   }
00328 
00329   gbuffer_target_.mrt->getViewport(0)->setMaterialScheme("GBuffer");
00330   weighted_average_alpha_target_.mrt->getViewport(0)->setMaterialScheme("WeightedAverageAlpha");
00331 }
00332 
00333 struct Timer
00334 {
00335   Timer()
00336   : start_(ros::WallTime::now())
00337   {}
00338 
00339   double elapsed() { return (ros::WallTime::now() - start_).toSec(); }
00340 
00341   ros::WallTime start_;
00342 };
00343 
00344 bool rectSort(ScreenRect* lhs, ScreenRect* rhs)
00345 {
00346   return lhs->getZOrder() > rhs->getZOrder();
00347 }
00348 
00349 void RenderTarget::requestRender()
00350 {
00351   render_needed_ = true;
00352 }
00353 
00354 void RenderTarget::beginRender()
00355 {
00356   ROS_ASSERT(!render_in_progress_);
00357 
00358   if (recreate_resources_)
00359   {
00360     destroyResources();
00361     createResources();
00362     recreate_resources_ = false;
00363     render_needed_ = true;
00364   }
00365 
00366   if (render_needed_)
00367   {
00368     render_in_progress_ = true;
00369     render_needed_ = false;
00370   }
00371   else
00372   {
00373     return;
00374   }
00375 
00376   if (cam_)
00377   {
00378     // Work around OGRE bug #340: http://www.ogre3d.org/mantis/view.php?id=340
00379     Ogre::Root::getSingleton().getRenderSystem()->_setViewport(gbuffer_target_.mrt->getViewport(0));
00380     gbuffer_target_.mrt->getViewport(0)->clear(Ogre::FBT_COLOUR|Ogre::FBT_DEPTH|Ogre::FBT_STENCIL, Ogre::ColourValue(0.0, 0.0, 0.0, 0.0));
00381     weighted_average_alpha_target_.mrt->getViewport(0)->clear(Ogre::FBT_COLOUR|Ogre::FBT_DEPTH|Ogre::FBT_STENCIL, Ogre::ColourValue(0.0, 0.0, 0.0, 0.0));
00382   }
00383 
00384   {
00385     Timer t;
00386     gbuffer_target_.mrt->update(false);
00387     gbuffer_target_.ros_output[0]->update();
00388     gbuffer_target_.ros_output[1]->update();
00389     stats_.gbuffer_update = t.elapsed();
00390   }
00391 
00392   {
00393     Timer t;
00394     weighted_average_alpha_target_.mrt->update(false);
00395     weighted_average_alpha_target_.ros_output[0]->update();
00396     weighted_average_alpha_target_.ros_output[1]->update();
00397     t.elapsed(); // TODO
00398   }
00399 
00400   {
00401     Timer t;
00402     if (cam_)
00403     {
00404       final_target_->getViewport(0)->clear(Ogre::FBT_COLOUR|Ogre::FBT_DEPTH|Ogre::FBT_STENCIL);
00405 #if 01
00406       cam_->getOgreCamera()->getSceneManager()->manualRender(screen_rect_, rect_material_->getTechnique(0)->getPass(0),
00407                                                              final_target_->getViewport(0), cam_->getOgreCamera()->getViewMatrix(),
00408                                                              cam_->getOgreCamera()->getProjectionMatrix(), true, false, false, 0);
00409 #else
00410       final_target_->update(false);
00411 #endif
00412 
00413       {
00414         // Now render the screen elements
00415         std::sort(screen_rects_.begin(), screen_rects_.end(), rectSort);
00416         V_ScreenRect::iterator it = screen_rects_.begin();
00417         V_ScreenRect::iterator end = screen_rects_.end();
00418         for (; it != end; ++it)
00419         {
00420           ScreenRect* rect = *it;
00421           Ogre::Renderable* rend = rect->getRenderable();
00422           cam_->getOgreCamera()->getSceneManager()->manualRender(rend, rend->getMaterial()->getTechnique(0)->getPass(0),
00423                                                                  final_target_->getViewport(0), cam_->getOgreCamera()->getViewMatrix(),
00424                                                                  cam_->getOgreCamera()->getProjectionMatrix(), true, false, false, 0);
00425         }
00426       }
00427 
00428       final_target_out_->update();
00429     }
00430 
00431     stats_.blit_to_main = t.elapsed();
00432   }
00433 
00434   pick_buffer_valid_ = false;
00435   pick_target_updated_this_frame_ = false;
00436   pick_requests_.swap(new_pick_requests_);
00437 
00438   if (!pick_requests_.empty())
00439   {
00440     if (cam_)
00441     {
00442       // Work around OGRE bug #340: http://www.ogre3d.org/mantis/view.php?id=340
00443       Ogre::Root::getSingleton().getRenderSystem()->_setViewport(picking_target_.mrt->getViewport(0));
00444       picking_target_.mrt->getViewport(0)->clear(Ogre::FBT_COLOUR|Ogre::FBT_DEPTH|Ogre::FBT_STENCIL, Ogre::ColourValue(0.0, 0.0, 0.0, 0.0));
00445     }
00446 
00447     // Figure out the min/max x/y
00448     uint32_t x0 = 9999999;
00449     uint32_t y0 = 9999999;
00450     uint32_t x1 = 0;
00451     uint32_t y1 = 0;
00452     V_PickRequest::iterator it = pick_requests_.begin();
00453     V_PickRequest::iterator end = pick_requests_.end();
00454     for (; it != end; ++it)
00455     {
00456       const PickRequest& r = *it;
00457       x0 = std::min(x0, std::min(r.x0, r.x1));
00458       x1 = std::max(x1, std::max(r.x0, r.x1));
00459       y0 = std::min(y0, std::min(r.y0, r.y1));
00460       y1 = std::max(y1, std::max(r.y0, r.y1));
00461     }
00462 
00463     x1 += 1;
00464     y1 += 1;
00465     x0 = std::min(x0, width_);
00466     x1 = std::min(x1, width_);
00467     y0 = std::min(y0, height_);
00468     y1 = std::min(y1, height_);
00469     float left = (float)x0 / width_;
00470     float right = (float)x1 / width_;
00471     float top = (float)y0 / height_;
00472     float bottom = (float)y1 / height_;
00473 
00474     // ROS_INFO("right,bottom = %f,%f", right, bottom);
00475 
00476     Ogre::Viewport* vp = picking_target_.mrt->getViewport(0);
00477     vp->setVisibilityMask(0x10000000);
00478 
00479     Ogre::Camera* cam = cam_->getOgreCamera();
00480 
00481     Ogre::PlaneBoundedVolumeList pbvl;
00482     pbvl.push_back(cam->getCameraToViewportBoxVolume(left, top, right, bottom, false));
00483 
00484     pick_scene_query_->setVolumes(pbvl);
00485     pick_scene_query_->clearResults();
00486     Ogre::SceneQueryResult& results = pick_scene_query_->execute();
00487     //ROS_INFO("****************************************");
00488     BOOST_FOREACH(Ogre::MovableObject* obj, results.movables)
00489     {
00490       obj->addVisibilityFlags(0x10000000);
00491       //ROS_INFO("%p", obj);
00492     }
00493 
00494     Timer t;
00495     picking_target_.mrt->update(false);
00496     picking_target_.ros_output[0]->update();
00497     picking_target_.ros_output[1]->update();
00498     //ROS_INFO_STREAM(t.elapsed()); // TODO
00499 
00500     pick_target_updated_this_frame_ = true;
00501 
00502     BOOST_FOREACH(Ogre::MovableObject* obj, results.movables)
00503     {
00504       obj->removeVisibilityFlags(0x10000000);
00505     }
00506   }
00507 }
00508 
00509 void RenderTarget::finishRender()
00510 {
00511   if (!render_in_progress_)
00512   {
00513     return;
00514   }
00515 
00516   {
00517     Timer t;
00518     gbuffer_target_.mrt->swapBuffers(false);
00519     stats_.gbuffer_swap = t.elapsed();
00520   }
00521 
00522   {
00523     Timer t;
00524     weighted_average_alpha_target_.mrt->swapBuffers(false);
00525     t.elapsed(); // TODO
00526   }
00527 
00528   {
00529     Timer t;
00530     final_target_->swapBuffers(false);
00531     stats_.main_swap = t.elapsed();
00532   }
00533 
00534   if (pick_target_updated_this_frame_)
00535   {
00536     Timer t;
00537     updatePickBuffer();
00538     processPickRequests();
00539     t.elapsed(); // TODO
00540   }
00541 
00542   render_in_progress_ = false;
00543 }
00544 
00545 void RenderTarget::pick(const PickRequest& pr)
00546 {
00547   ROS_ASSERT(pick_buffer_valid_);
00548 
00549   uint32_t x0 = std::min(std::min(pr.x0, pr.x1), width_);
00550   uint32_t x1 = std::min(std::max(pr.x0, pr.x1), width_);
00551   uint32_t y0 = std::min(std::min(pr.y0, pr.y1), height_);
00552   uint32_t y1 = std::min(std::max(pr.y0, pr.y1), height_);
00553   uint32_t pick_width = x1 - x0 + 1;
00554   uint32_t pick_height = y1 - y0 + 1;
00555   uint32_t width = width_;
00556   uint32_t height = height_;
00557   uint32_t target_array_size = width * height;
00558 
00559   if (x0 >= width_ - 1 || y0 >= height_ - 1)
00560   {
00561     V_PickRenderValues vals;
00562     pr.cb(vals);
00563     return;
00564   }
00565 
00566   uint32_t* buf = pick_buffer_.get();
00567 
00568   V_PickRenderValues out_picked;
00569   for (uint32_t y = y0; y < y0 + pick_height; ++y)
00570   {
00571     for (uint32_t x = x0; x < x0 + pick_width; ++x)
00572     {
00573       uint32_t offset = y * width + x;
00574       uint32_t obj = buf[offset];
00575       uint32_t extra = buf[target_array_size + offset];
00576       out_picked.push_back(PickRenderValues(obj, extra));
00577     }
00578   }
00579 
00580   pr.cb(out_picked);
00581 }
00582 
00583 void RenderTarget::updatePickBuffer()
00584 {
00585   //Ogre::Viewport* vp = picking_target_.mrt->getViewport(0);
00586   //vp->setDimensions((double)x / width_, (double)y / height_, 1, 1);
00587 
00588   ROS_ASSERT(pick_target_updated_this_frame_);
00589 
00590   picking_target_.mrt->swapBuffers(false);
00591 
00592   uint32_t width = width_;
00593   uint32_t height = height_;
00594   uint32_t target_array_size = width * height;
00595   Ogre::PixelBox pbox(width, height, 1, Ogre::PF_BYTE_RGBA, pick_buffer_.get());
00596   picking_target_.rtts[0]->copyContentsToMemory(pbox, Ogre::RenderTarget::FB_AUTO);
00597   pbox = Ogre::PixelBox(width, height, 1, Ogre::PF_BYTE_RGBA, pick_buffer_.get() + target_array_size);
00598   picking_target_.rtts[1]->copyContentsToMemory(pbox, Ogre::RenderTarget::FB_AUTO);
00599 
00600   //vp->setDimensions(0, 0, 1.0, 1.0);
00601 
00602   pick_buffer_valid_ = true;
00603 }
00604 
00605 void RenderTarget::pick(uint32_t x0, uint32_t y0, uint32_t x1, uint32_t y1, const PickCallback& cb)
00606 {
00607   if (!cam_)
00608   {
00609     V_PickRenderValues empty;
00610     cb(empty);
00611     return;
00612   }
00613 
00614   if (!picked_)
00615   {
00616     picked_ = true;
00617     pick_buffer_.reset(new uint32_t[width_ * height_ * 2]);
00618     createMRT(picking_target_, "pick", "Pick", Ogre::PF_BYTE_RGBA);
00619     pick_scene_query_ = cam_->getOgreCamera()->getSceneManager()->createPlaneBoundedVolumeQuery(Ogre::PlaneBoundedVolumeList());
00620   }
00621 
00622   PickRequest pr(x0, y0, x1, y1, cb);
00623 #if 0
00624   if (pick_buffer_valid_)
00625   {
00626     pick(pr);
00627   }
00628   else
00629 #endif
00630   {
00631     new_pick_requests_.push_back(pr);
00632   }
00633 
00634   render_needed_ = true;
00635 }
00636 
00637 void RenderTarget::processPickRequests()
00638 {
00639   V_PickRequest::iterator it = pick_requests_.begin();
00640   V_PickRequest::iterator end = pick_requests_.end();
00641   for (; it != end; ++it)
00642   {
00643     pick(*it);
00644   }
00645   pick_requests_.clear();
00646 }
00647 
00648 ScreenRect* RenderTarget::createScreenRect(const rve_common::UUID& id, uint32_t zorder, float x0, float y0, float x1, float y1)
00649 {
00650   ScreenRect* rect = new ScreenRect(id);
00651   rect->setZOrder(zorder);
00652   rect->setCorners(x0, y0, x1, y1);
00653   screen_rects_.push_back(rect);
00654   return rect;
00655 }
00656 
00657 bool rectMatches(ScreenRect* rect, const rve_common::UUID& id)
00658 {
00659   return rect->getID() == id;
00660 }
00661 
00662 ScreenRect* RenderTarget::getScreenRect(const rve_common::UUID& id)
00663 {
00664   V_ScreenRect::iterator it = std::find_if(screen_rects_.begin(), screen_rects_.end(), boost::bind(rectMatches, _1, boost::ref(id)));
00665   if (it == screen_rects_.end())
00666   {
00667     throw std::runtime_error("No ScreenRect with id [" + id.toString() + "]");
00668   }
00669 
00670   return *it;
00671 }
00672 
00673 void RenderTarget::destroyScreenRect(const rve_common::UUID& id)
00674 {
00675   V_ScreenRect::iterator it = std::find_if(screen_rects_.begin(), screen_rects_.end(), boost::bind(rectMatches, _1, boost::ref(id)));
00676   if (it == screen_rects_.end())
00677   {
00678     throw std::runtime_error("No ScreenRect with id [" + id.toString() + "]");
00679   }
00680 
00681   ScreenRect* rect = *it;
00682   screen_rects_.erase(it);
00683   delete rect;
00684 }
00685 
00686 } // namespace rve_render_server


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