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_client/render_target.h"
00031 #include <rve_render_client/client_context.h>
00032 #include "rve_render_client/camera.h"
00033 #include "rve_render_client/scene.h"
00034 #include "rve_render_client/screen_rect.h"
00035 
00036 #include <rve_interfaces/RenderTarget.h>
00037 #include <rve_interfaces/RenderTarget_pickResponse.h>
00038 #include <rve_rpc/method_response.h>
00039 
00040 #include <ros/node_handle.h>
00041 
00042 #include <boost/bind.hpp>
00043 
00044 using namespace rve_common;
00045 
00046 namespace rve_render_client
00047 {
00048 
00049 RenderTarget::RenderTarget(uint32_t width, uint32_t height)
00050 : context_(0)
00051 , proxy_handle_(NullHandle)
00052 , width_(width)
00053 , height_(height)
00054 , id_(UUID::generate())
00055 {
00056 }
00057 
00058 RenderTarget::~RenderTarget()
00059 {
00060 }
00061 
00062 rve_interfaces::RenderTargetProxy* RenderTarget::getProxy()
00063 {
00064   ROS_ASSERT(proxy_handle_ != NullHandle);
00065   ROS_ASSERT(context_);
00066   return context_->getInterface<rve_interfaces::RenderTargetProxy>(proxy_handle_);
00067 }
00068 
00069 void RenderTarget::create(ClientContext* context)
00070 {
00071   // Render targets only support a single context
00072   ROS_ASSERT(!context_);
00073   ROS_ASSERT(proxy_handle_ == NullHandle);
00074   context_ = context;
00075   proxy_handle_ = context->lookupInterface("render_target");
00076 
00077   // Call through to the derived class to do the actual creation
00078   doCreate();
00079 
00080   if (camera_id_ != UUID::Null)
00081   {
00082     rve_interfaces::RenderTargetProxy* proxy = getProxy();
00083     proxy->attachCamera(getID(), camera_scene_id_, camera_id_);
00084   }
00085   rve_render_client::CameraPtr cam = camera_.lock();
00086   if( cam )
00087   {
00088     cam->setAspectRatio( float(width_)/float(height_) );
00089   }
00090 }
00091 
00092 void RenderTarget::destroy(ClientContext* context)
00093 {
00094   ROS_ASSERT(context == context_);
00095   rve_interfaces::RenderTargetProxy* proxy = getProxy();
00096   proxy->destroy(getID());
00097 
00098   proxy_handle_ = NullHandle;
00099   context_ = 0;
00100 }
00101 
00102 void RenderTarget::resize(uint32_t width, uint32_t height)
00103 {
00104   width_ = width;
00105   height_ = height;
00106 
00107   CameraPtr cam = camera_.lock();
00108   if (cam)
00109   {
00110     cam->setAspectRatio( float(width)/float(height) );
00111   }
00112 
00113   if (context_)
00114   {
00115     rve_interfaces::RenderTargetProxy* proxy = getProxy();
00116     proxy->resizeAsync(getID(), width, height);
00117   }
00118 }
00119 
00120 void RenderTarget::attachCamera(const CameraPtr& cam)
00121 {
00122   camera_ = cam;
00123   if (context_)
00124   {
00125     rve_interfaces::RenderTargetProxy* proxy = getProxy();
00126     if (cam)
00127     {
00128       cam->setAspectRatio( float(width_)/float(height_) );
00129 
00130       proxy->attachCameraAsync(getID(), cam->getScene()->getID(), cam->getID());
00131       camera_id_ = cam->getID();
00132       camera_scene_id_ = cam->getScene()->getID();
00133     }
00134     else
00135     {
00136       proxy->detachCameraAsync(getID());
00137       camera_id_ = UUID::Null;
00138       camera_scene_id_ = UUID::Null;
00139     }
00140   }
00141 }
00142 
00143 void RenderTarget::pick(uint32_t x1, uint32_t y1, uint32_t x2, uint32_t y2,
00144                         boost::function<void(const rve_rpc::MethodResponse<rve_interfaces::RenderTarget::pickResponse>&)> callback)
00145 {
00146   if (context_)
00147   {
00148     rve_interfaces::RenderTargetProxy* proxy = getProxy();
00149     proxy->pickAsync(getID(), x1, y1, x2, y2, callback);
00150   }
00151 }
00152 
00153 void RenderTarget::requestRender()
00154 {
00155   if (context_)
00156   {
00157     rve_interfaces::RenderTargetProxy* proxy = getProxy();
00158     proxy->requestRenderAsync(getID());
00159   }
00160 }
00161 
00162 void RenderTarget::destroyScreenRect(ScreenRect* rect)
00163 {
00164   if (context_)
00165   {
00166     rect->destroy(context_);
00167   }
00168 
00169   delete rect;
00170 }
00171 
00172 ScreenRectPtr RenderTarget::createScreenRect(uint32_t zorder, float x0, float y0, float x1, float y1)
00173 {
00174   ScreenRectPtr rect(new ScreenRect(getID(), zorder, x0, y0, x1, y1), boost::bind(&RenderTarget::destroyScreenRect, this, _1));
00175   if (context_)
00176   {
00177     rect->create(context_);
00178   }
00179   return rect;
00180 }
00181 
00182 std::string dashToUnderscore(const std::string& str)
00183 {
00184   std::string out = str;
00185   for (size_t i = 0; i < out.size(); ++i)
00186   {
00187     if (out[i] == '-')
00188     {
00189       out[i] = '_';
00190     }
00191   }
00192 
00193   return out;
00194 }
00195 
00196 std::string RenderTarget::getNamespace()
00197 {
00198   return context_->getNodeHandle().getNamespace() + "/render_targets/" + dashToUnderscore(getID().toString());
00199 }
00200 
00201 }
00202 


rve_render_client
Author(s): Josh Faust
autogenerated on Wed Dec 11 2013 14:31:32