34 #include <OgreCamera.h> 35 #include <OgreEntity.h> 36 #include <OgreHardwarePixelBuffer.h> 37 #include <OgreManualObject.h> 38 #include <OgreMaterialManager.h> 39 #include <OgreRenderSystem.h> 40 #include <OgreRenderTexture.h> 42 #include <OgreSceneManager.h> 43 #include <OgreSceneNode.h> 44 #include <OgreSubEntity.h> 45 #include <OgreTextureManager.h> 46 #include <OgreViewport.h> 47 #include <OgreWireBoundingBox.h> 48 #include <OgreSharedPtr.h> 49 #include <OgreTechnique.h> 50 #include <OgreRectangle2D.h> 53 #include <sensor_msgs/Image.h> 79 : vis_manager_(manager)
80 , highlight_enabled_(false)
82 , interaction_enabled_(false)
83 , debug_mode_( false )
92 QTimer* timer =
new QTimer(
this );
129 highlight_node_ = scene_manager->getRootSceneNode()->createChildSceneNode();
131 std::stringstream ss;
132 static int count = 0;
133 ss <<
"SelectionRect" << count++;
136 const static uint32_t texture_data[1] = { 0xffff0080 };
137 Ogre::DataStreamPtr pixel_stream;
138 pixel_stream.bind(
new Ogre::MemoryDataStream( (
void*)&texture_data[0], 4 ));
140 Ogre::TexturePtr tex = Ogre::TextureManager::getSingleton().loadRawData(ss.str() +
"Texture", Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, pixel_stream, 1, 1, Ogre::PF_R8G8B8A8, Ogre::TEX_TYPE_2D, 0);
142 Ogre::MaterialPtr material = Ogre::MaterialManager::getSingleton().create(ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
143 material->setLightingEnabled(
false);
146 Ogre::AxisAlignedBox aabInf;
147 aabInf.setInfinite();
150 material->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
151 material->setCullingMode(Ogre::CULL_NONE);
153 Ogre::TextureUnitState* tex_unit = material->getTechnique(0)->getPass(0)->createTextureUnitState();
154 tex_unit->setTextureName(tex->getName());
155 tex_unit->setTextureFiltering( Ogre::TFO_NONE );
160 camera_= scene_manager->createCamera( ss.str()+
"_camera" );
178 ROS_DEBUG(
"SelectionManager.get3DPoint()");
180 std::vector<Ogre::Vector3> result_points_temp;
181 bool success =
get3DPatch( viewport, x, y, 1, 1,
true, result_points_temp);
182 if (result_points_temp.size() == 0)
188 result_point = result_points_temp[0];
197 unsigned int num_pixels = width*height;
198 depth_vector.reserve(num_pixels);
203 M_CollisionObjectToSelectionHandler::iterator handler_it =
objects_.begin();
204 M_CollisionObjectToSelectionHandler::iterator handler_end =
objects_.end();
206 for (; handler_it != handler_end; ++handler_it)
208 handler_it->second->preRenderPass(0);
211 bool success =
false;
217 for(uint32_t pixel = 0; pixel < num_pixels; ++pixel)
219 uint8_t a = data_ptr[4*pixel];
220 uint8_t b = data_ptr[4*pixel + 1];
221 uint8_t c = data_ptr[4*pixel + 2];
223 int int_depth = (c << 16) | (b << 8) | a;
224 float normalized_depth = ((float) int_depth) / (float) 0xffffff;
225 depth_vector.push_back(normalized_depth *
camera_->getFarClipDistance());
230 ROS_WARN(
"Failed to render depth patch\n");
236 for (; handler_it != handler_end; ++handler_it)
238 handler_it->second->postRenderPass(0);
246 unsigned height,
bool skip_missing, std::vector<Ogre::Vector3> &result_points )
249 ROS_DEBUG(
"SelectionManager.get3DPatch()");
251 std::vector<float> depth_vector;
258 unsigned int pixel_counter = 0;
259 Ogre::Matrix4 projection =
camera_->getProjectionMatrix();
262 for(
int y_iter = 0; y_iter < height; ++y_iter)
263 for(
int x_iter = 0 ; x_iter < width; ++x_iter)
265 depth = depth_vector[pixel_counter];
268 if( ( depth >
camera_->getFarClipDistance() ) || ( depth == 0 ) )
273 result_points.push_back(Ogre::Vector3(NAN,NAN,NAN));
279 Ogre::Vector3 result_point;
283 Ogre::Real screenx = float(x_iter + .5)/float(width);
284 Ogre::Real screeny = float(y_iter + .5)/float(height);
285 if( projection[3][3] == 0.0 )
288 Ogre::Ray vp_ray =
camera_->getCameraToViewportRay(screenx, screeny );
291 Ogre::Vector3 dir_cam =
camera_->getDerivedOrientation().Inverse() * vp_ray.getDirection();
294 dir_cam = dir_cam / dir_cam.z * depth * -1;
297 result_point =
camera_->getDerivedPosition() +
camera_->getDerivedOrientation() * dir_cam;
304 camera_->getCameraToViewportRay(screenx, screeny, &ray);
306 result_point = ray.getPoint(depth);
309 result_points.push_back(result_point);
313 return result_points.size() > 0;
325 ROS_ERROR_STREAM(
"SelectionManager::setDepthTextureSize invalid width requested. Max Width: 1024 -- Width requested: " << width <<
". Capping Width at 1024.");
334 ROS_ERROR_STREAM(
"SelectionManager::setDepthTextureSize invalid height requested. Max Height: 1024 -- Height requested: " << width <<
". Capping Height at 1024.");
342 std::string tex_name =
"DepthTexture";
348 Ogre::TextureManager::getSingleton().remove( tex_name );
352 Ogre::TextureManager::getSingleton().createManual( tex_name,
353 Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
356 Ogre::TU_RENDERTARGET );
359 render_texture->setAutoUpdated(
false);
378 std::string tex_name;
384 Ogre::TextureManager::getSingleton().remove( tex_name );
388 std::stringstream ss;
389 static int count = 0;
390 ss <<
"SelectionTexture" << count++;
395 render_textures_[pass] = Ogre::TextureManager::getSingleton().createManual( tex_name,
396 Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, Ogre::TEX_TYPE_2D, size, size, 0,
397 Ogre::PF_R8G8B8, Ogre::TU_STATIC | Ogre::TU_RENDERTARGET);
399 Ogre::RenderTexture* render_texture =
render_textures_[pass]->getBuffer()->getRenderTarget();
400 render_texture->setAutoUpdated(
false);
415 M_CollisionObjectToSelectionHandler::iterator handler_it =
objects_.begin();
416 M_CollisionObjectToSelectionHandler::iterator handler_end =
objects_.end();
417 for (; handler_it != handler_end; ++handler_it)
421 object->enableInteraction( enable );
438 for (
unsigned int i=0; i<24; i++ )
440 uint32_t shift = (((23-i)%3)*8) + (23-i)/3;
441 uint32_t bit = ( (uint32_t)(
uid_counter_ >> i) & (uint32_t)1 ) << shift;
464 bool inserted =
objects_.insert( std::make_pair( obj, handler )).second;
481 objs.insert(std::make_pair(it->first, it->second));
536 pick(viewport, x1, y1, x2, y2, results);
554 float nx1 = ((float)x1 / viewport->getActualWidth()) * 2 - 1;
555 float nx2 = ((float)x2 / viewport->getActualWidth()) * 2 - 1;
556 float ny1 = -(((float)y1 / viewport->getActualHeight()) * 2 - 1);
557 float ny2 = -(((float)y2 / viewport->getActualHeight()) * 2 - 1);
559 nx1 = nx1 < -1 ? -1 : (nx1 > 1 ? 1 : nx1);
560 ny1 = ny1 < -1 ? -1 : (ny1 > 1 ? 1 : ny1);
561 nx2 = nx2 < -1 ? -1 : (nx2 > 1 ? 1 : nx2);
562 ny2 = ny2 < -1 ? -1 : (ny2 > 1 ? 1 : ny2);
569 int w = box.getWidth();
570 int h = box.getHeight();
573 pixels.reserve( w*h );
575 for (
int y = 0;
y < h;
y ++)
577 for (
int x = 0;
x < w;
x ++)
579 uint32_t pos = (
x +
y*w) * 4;
581 uint32_t pix_val = *(uint32_t*)((uint8_t*)box.data + pos);
584 pixels.push_back(handle);
593 std::stringstream scheme;
608 int x1,
int y1,
int x2,
int y2,
609 Ogre::PixelBox& dst_box, std::string material_scheme,
610 unsigned texture_width,
unsigned texture_height)
614 if ( x1 > x2 ) std::swap( x1, x2 );
615 if ( y1 > y2 ) std::swap( y1, y2 );
617 if ( x1 < 0 ) x1 = 0;
618 if ( y1 < 0 ) y1 = 0;
619 if ( x1 > viewport->getActualWidth()-2 ) x1 = viewport->getActualWidth()-2;
620 if ( y1 > viewport->getActualHeight()-2 ) y1 = viewport->getActualHeight()-2;
621 if ( x2 < 0 ) x2 = 0;
622 if ( y2 < 0 ) y2 = 0;
623 if ( x2 > viewport->getActualWidth()-2 ) x2 = viewport->getActualWidth()-2;
624 if ( y2 > viewport->getActualHeight()-2 ) y2 = viewport->getActualHeight()-2;
629 if ( x2==x1 || y2==y1 )
631 ROS_WARN(
"SelectionManager::render(): not rendering 0 size area.");
639 Ogre::HardwarePixelBufferSharedPtr pixel_buffer = tex->getBuffer();
640 Ogre::RenderTexture* render_texture = pixel_buffer->getRenderTarget();
642 Ogre::Matrix4 proj_matrix = viewport->getCamera()->getProjectionMatrix();
643 Ogre::Matrix4 scale_matrix = Ogre::Matrix4::IDENTITY;
644 Ogre::Matrix4 trans_matrix = Ogre::Matrix4::IDENTITY;
646 float x1_rel =
static_cast<float>(x1) / static_cast<float>(viewport->getActualWidth() - 1) - 0.5
f;
647 float y1_rel =
static_cast<float>(y1) / static_cast<float>(viewport->getActualHeight() - 1) - 0.5
f;
648 float x2_rel =
static_cast<float>(x2) / static_cast<float>(viewport->getActualWidth() - 1) - 0.5
f;
649 float y2_rel =
static_cast<float>(y2) / static_cast<float>(viewport->getActualHeight() - 1) - 0.5
f;
651 scale_matrix[0][0] = 1.0 / (x2_rel-x1_rel);
652 scale_matrix[1][1] = 1.0 / (y2_rel-y1_rel);
654 trans_matrix[0][3] -= x1_rel+x2_rel;
655 trans_matrix[1][3] += y1_rel+y2_rel;
657 camera_->setCustomProjectionMatrix(
true, scale_matrix * trans_matrix * proj_matrix );
659 camera_->setPosition( viewport->getCamera()->getDerivedPosition() );
660 camera_->setOrientation( viewport->getCamera()->getDerivedOrientation() );
663 if (render_texture->getNumViewports() == 0)
665 render_texture->removeAllViewports();
666 render_texture->addViewport(
camera_ );
667 Ogre::Viewport* render_viewport = render_texture->getViewport(0);
668 render_viewport->setClearEveryFrame(
true);
669 render_viewport->setBackgroundColour( Ogre::ColourValue::Black );
670 render_viewport->setOverlaysEnabled(
false);
671 render_viewport->setMaterialScheme(material_scheme);
674 unsigned render_w = w;
675 unsigned render_h = h;
679 if ( render_w > texture_width )
681 render_w = texture_width;
682 render_h = round(
float(h) * (
float)texture_width / (
float)w );
687 if ( render_h > texture_height )
689 render_h = texture_height;
690 render_w = round(
float(w) * (
float)texture_height / (
float)h );
695 if ( render_w > texture_width ) render_w = texture_width;
696 if ( render_h > texture_height ) render_h = texture_height;
699 Ogre::Viewport* render_viewport = render_texture->getViewport(0);
700 render_viewport->setDimensions( 0, 0,
701 (
float)render_w / (
float)texture_width,
702 (
float)render_h / (
float)texture_height );
705 render_viewport->setVisibilityMask( viewport->getVisibilityMask() );
710 Ogre::MaterialManager::getSingleton().addListener(
this);
712 render_texture->update();
731 Ogre::MaterialManager::getSingleton().removeListener(
this);
733 render_w = render_viewport->getActualWidth();
734 render_h = render_viewport->getActualHeight();
736 Ogre::PixelFormat format = pixel_buffer->getFormat();
738 int size = Ogre::PixelUtil::getMemorySize(render_w, render_h, 1, format);
739 uint8_t* data =
new uint8_t[size];
741 delete [] (uint8_t*)dst_box.data;
742 dst_box = Ogre::PixelBox(render_w, render_h, 1, format, data);
744 pixel_buffer->blitToMemory(dst_box,dst_box);
763 pub = nh.
advertise<sensor_msgs::Image>(
"/rviz_debug/" + label, 2 );
771 sensor_msgs::Image msg;
773 msg.width = pixel_box.getWidth();
774 msg.height = pixel_box.getHeight();
776 msg.is_bigendian =
false;
777 msg.step = msg.width * 3;
778 int dest_byte_count = msg.width * msg.height * 3;
779 msg.data.resize( dest_byte_count );
781 uint8_t* source_ptr = (uint8_t*)pixel_box.data;
782 int pre_pixel_padding = 0;
783 int post_pixel_padding = 0;
784 switch( pixel_box.format )
786 case Ogre::PF_A8R8G8B8:
787 case Ogre::PF_X8R8G8B8:
788 post_pixel_padding = 1;
790 case Ogre::PF_R8G8B8A8:
791 pre_pixel_padding = 1;
794 ROS_ERROR(
"SelectionManager::publishDebugImage(): Incompatible pixel format [%d]", pixel_box.format );
798 while( dest_index < dest_byte_count )
800 source_ptr += pre_pixel_padding;
804 source_ptr += post_pixel_padding;
805 msg.data[ dest_index++ ] = r;
806 msg.data[ dest_index++ ] = g;
807 msg.data[ dest_index++ ] = b;
814 const std::string& invocation,
815 bool& skipThisInvocation )
821 skipThisInvocation =
true;
828 bool need_additional_render =
false;
838 M_CollisionObjectToSelectionHandler::iterator handler_it =
objects_.begin();
839 M_CollisionObjectToSelectionHandler::iterator handler_end =
objects_.end();
840 for (; handler_it != handler_end; ++handler_it)
842 handler_it->second->preRenderPass( 0 );
849 for (; handler_it != handler_end; ++handler_it)
851 handler_it->second->postRenderPass(0);
854 handles_by_pixel.reserve(pixels.size());
855 V_CollObject::iterator it = pixels.begin();
856 V_CollObject::iterator end = pixels.end();
857 for (; it != end; ++it)
863 handles_by_pixel.push_back(handle);
874 std::pair<M_Picked::iterator, bool> insert_result = results.insert(std::make_pair(handle,
Picked(handle)));
875 if (insert_result.second)
879 need_additional.insert(handle);
880 need_additional_render =
true;
885 insert_result.first->second.pixel_count++;
894 extra_by_pixel.resize(handles_by_pixel.size());
898 S_CollObject::iterator need_it = need_additional.begin();
899 S_CollObject::iterator need_end = need_additional.end();
900 for (; need_it != need_end; ++need_it)
912 S_CollObject::iterator need_it = need_additional.begin();
913 S_CollObject::iterator need_end = need_additional.end();
914 for (; need_it != need_end; ++need_it)
924 V_CollObject::iterator pix_it = pixels.begin();
925 V_CollObject::iterator pix_end = pixels.end();
926 for (; pix_it != pix_end; ++pix_it, ++i)
934 extra_by_pixel[i] = 0;
937 if (need_additional.find(handle) != need_additional.end())
940 extra_by_pixel[i] |= extra_handle << (32 * (pass-1));
944 extra_by_pixel[i] = 0;
948 need_additional_render =
false;
949 need_additional.clear();
950 M_Picked::iterator handle_it = results.begin();
951 M_Picked::iterator handle_end = results.end();
952 for (; handle_it != handle_end; ++handle_it)
956 if (
getHandler(handle)->needsAdditionalRenderPass(pass + 1))
958 need_additional_render =
true;
959 need_additional.insert(handle);
965 V_uint64::iterator pix_2_it = extra_by_pixel.begin();
966 V_uint64::iterator pix_2_end = extra_by_pixel.end();
967 for (; pix_2_it != pix_2_end; ++pix_2_it, ++i)
976 M_Picked::iterator picked_it = results.find(handle);
977 if (picked_it == results.end())
982 Picked& picked = picked_it->second;
992 const Ogre::String& scheme_name,
993 Ogre::Material* original_material,
994 unsigned short lod_index,
995 const Ogre::Renderable* rend )
998 Ogre::CullingMode culling_mode = Ogre::CULL_CLOCKWISE;
999 Ogre::Technique* orig_tech = original_material->getTechnique( 0 );
1000 if( orig_tech && orig_tech->getNumPasses() > 0 )
1002 culling_mode = orig_tech->getPass( 0 )->getCullingMode();
1006 bool has_pick_param = ! rend->getUserObjectBindings().getUserAny(
"pick_handle" ).isEmpty();
1016 if( culling_mode == Ogre::CULL_CLOCKWISE )
1018 if( scheme_name ==
"Pick" )
1022 else if( scheme_name ==
"Depth" )
1026 if( scheme_name ==
"Pick1" )
1037 if( scheme_name ==
"Pick" )
1041 else if( scheme_name ==
"Depth" )
1045 if( scheme_name ==
"Pick1" )
1058 float r = ((handle >> 16) & 0xff) / 255.0f;
1059 float g = ((handle >> 8) & 0xff) / 255.0f;
1060 float b = (handle & 0xff) / 255.0
f;
1061 return Ogre::ColourValue( r, g, b, 1.0
f );
1071 Ogre::SceneNode::ObjectIterator obj_it = node->getAttachedObjectIterator();
1072 while( obj_it.hasMoreElements() )
1074 Ogre::MovableObject* obj = obj_it.getNext();
1078 Ogre::SceneNode::ChildNodeIterator child_it = node->getChildIterator();
1079 while( child_it.hasMoreElements() )
1081 Ogre::SceneNode* child =
dynamic_cast<Ogre::SceneNode*
>( child_it.getNext() );
1090 : color_vector_( color.
r, color.g, color.b, 1.0 ), handle_(handle) {}
1092 virtual void visit( Ogre::Renderable* rend, ushort lodIndex,
bool isDebug, Ogre::Any* pAny = 0 )
1095 rend->getUserObjectBindings().setUserAny(
"pick_handle", Ogre::Any( handle_ ));
1105 object->visitRenderables( &visitor );
1106 object->getUserObjectBindings().setUserAny(
"pick_handle", Ogre::Any( handle ));
1113 M_CollisionObjectToSelectionHandler::iterator it =
objects_.find(obj);
1126 M_Picked::const_iterator it = objs.begin();
1127 M_Picked::const_iterator end = objs.end();
1128 for (; it != end; ++it)
1141 M_Picked::const_iterator it = objs.begin();
1142 M_Picked::const_iterator end = objs.end();
1143 for (; it != end; ++it)
1148 added.insert(std::make_pair(it->first, ppb.first));
1169 std::pair<M_Picked::iterator, bool> pib =
selection_.insert(std::make_pair(obj.
handle, obj));
1176 return std::make_pair(obj,
true);
1180 Picked& cur = pib.first->second;
1185 for (; it != end; ++it)
1197 return std::make_pair(added,
true);
1201 return std::make_pair(
Picked(0),
false);
1213 for (; extra_it != extra_end; ++extra_it)
1215 sel_it->second.extra_handles.erase(*extra_it);
1218 if (sel_it->second.extra_handles.empty())
1237 Ogre::AxisAlignedBox combined;
1241 for (; it != end; ++it)
1243 const Picked& p = it->second;
1250 V_AABB::iterator aabb_it = aabbs.begin();
1251 V_AABB::iterator aabb_end = aabbs.end();
1252 for (; aabb_it != aabb_end; ++aabb_it)
1254 combined.merge(*aabb_it);
1258 if (!combined.isInfinite() && !combined.isNull())
1260 Ogre::Vector3 center = combined.getCenter();
1264 controller->
lookAt(center);
1271 M_Picked::const_iterator it = removed.begin();
1272 M_Picked::const_iterator end = removed.end();
1273 for (; it != end; ++it)
1275 const Picked& picked = it->second;
1285 M_Picked::const_iterator it = added.begin();
1286 M_Picked::const_iterator end = added.end();
1287 for (; it != end; ++it)
1289 const Picked& picked = it->second;
1300 M_Picked::const_iterator it =
selection_.begin();
1301 M_Picked::const_iterator end =
selection_.end();
1302 for (; it != end; ++it)
std::vector< uint64_t > V_uint64
virtual bool needsAdditionalRenderPass(uint32_t pass)
void publishDebugImage(const Ogre::PixelBox &pixel_box, const std::string &label)
ViewController * getCurrent() const
Return the current ViewController in use for the main RenderWindow.
CollObjectHandle createHandle()
virtual ViewManager * getViewManager() const
Return a pointer to the ViewManager.
void publish(const boost::shared_ptr< M > &message) const
void removeSelectedObject(const Picked &obj)
void selectionAdded(const M_Picked &added)
virtual void updateProperties()
Override to update property values.
boost::unordered_map< CollObjectHandle, Picked > M_Picked
SelectionManager(VisualizationManager *manager)
Ogre::TexturePtr render_textures_[s_num_render_textures_]
void setSelection(const M_Picked &objs)
A single element of a property tree, with a name, value, description, and possibly children...
void lookAt(float x, float y, float z)
Convenience function which calls lookAt(Ogre::Vector3).
Ogre::SceneManager * getSceneManager() const
Returns the Ogre::SceneManager used for the main RenderPanel.
void removeObject(CollObjectHandle obj)
virtual InteractiveObjectWPtr getInteractiveObject()
Get the object to listen to mouse events and other interaction calls during use of the 'interact' too...
virtual void preRenderPass(uint32_t pass)
void unlockRender()
Unlock a mutex, allowing calls to Ogre::Root::renderOneFrame().
void addObject(CollObjectHandle obj, SelectionHandler *handler)
static Ogre::ColourValue handleToColor(CollObjectHandle handle)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void lockRender()
Lock a mutex to delay calls to Ogre::Root::renderOneFrame().
Ogre::Technique * fallback_black_cull_technique_
void setDebugMode(bool debug)
Enables or disables publishing of picking and depth rendering images.
Ogre::PixelBox pixel_boxes_[s_num_render_textures_]
RenderPanel * getRenderPanel() const
Return the main RenderPanel.
void setDepthTextureSize(unsigned width, unsigned height)
void highlight(Ogre::Viewport *viewport, int x1, int y1, int x2, int y2)
Ogre::Technique * fallback_pick_cull_technique_
uint32_t depth_texture_width_
void enableInteraction(bool enable)
void setHighlightRect(Ogre::Viewport *viewport, int x1, int y1, int x2, int y2)
std::vector< Ogre::AxisAlignedBox > V_AABB
PropertyTreeModel * property_model_
bool get3DPatch(Ogre::Viewport *viewport, const int x, const int y, const unsigned width, const unsigned height, const bool skip_missing, std::vector< Ogre::Vector3 > &result_points)
Gets the 3D points in a box around a point in a view port.
void updateProperties()
Call updateProperties() on all SelectionHandlers in the current selection.
Ogre::Vector4 color_vector_
Ogre::Technique * fallback_pick_technique_
V_CollObject pixel_buffer_
virtual void getAABBs(const Picked &obj, V_AABB &aabbs)
static const uint32_t s_num_render_textures_
Ogre::Technique * fallback_depth_cull_technique_
void select(Ogre::Viewport *viewport, int x1, int y1, int x2, int y2, SelectType type)
void removeSelection(const M_Picked &objs)
The VisualizationManager class is the central manager class of rviz, holding all the Displays...
SelectionHandler * getHandler(CollObjectHandle obj)
std::vector< CollObjectHandle > V_CollObject
TFSIMD_FORCE_INLINE const tfScalar & x() const
PublisherMap debug_publishers_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Ogre::TexturePtr depth_render_texture_
bool render(Ogre::Viewport *viewport, Ogre::TexturePtr tex, int x1, int y1, int x2, int y2, Ogre::PixelBox &dst_box, std::string material_scheme, unsigned texture_width, unsigned textured_height)
std::pair< Picked, bool > addSelectedObject(const Picked &obj)
#define PICK_COLOR_PARAMETER
void pick(Ogre::Viewport *viewport, int x1, int y1, int x2, int y2, M_Picked &results, bool single_render_pass=false)
Ogre::Technique * fallback_depth_technique_
virtual void onSelect(const Picked &obj)
TFSIMD_FORCE_INLINE const tfScalar & w() const
uint32_t colorToHandle(Ogre::PixelFormat fmt, uint32_t col)
void unpackColors(const Ogre::PixelBox &box, V_CollObject &pixels)
Ogre::Viewport * getViewport() const
Ogre::SceneNode * highlight_node_
Ogre::Viewport * viewport
virtual void destroyProperties(const Picked &obj, Property *parent_property)
Destroy all properties for the given picked object(s).
static void setPickData(CollObjectHandle handle, const Ogre::ColourValue &color, Ogre::SceneNode *node)
virtual void postRenderPass(uint32_t pass)
virtual Ogre::Technique * handleSchemeNotFound(unsigned short scheme_index, const Ogre::String &scheme_name, Ogre::Material *original_material, unsigned short lod_index, const Ogre::Renderable *rend)
void addSelection(const M_Picked &objs)
void setTextureSize(unsigned size)
VisualizationManager * vis_manager_
virtual void onDeselect(const Picked &obj)
Ogre::Rectangle2D * highlight_rectangle_
void selectionRemoved(const M_Picked &removed)
virtual void createProperties(const Picked &obj, Property *parent_property)
Override to create properties of the given picked object(s).
void renderAndUnpack(Ogre::Viewport *viewport, uint32_t pass, int x1, int y1, int x2, int y2, V_CollObject &pixels)
#define ROS_ERROR_STREAM(args)
Ogre::MaterialPtr fallback_pick_material_
PickColorSetter(CollObjectHandle handle, const Ogre::ColourValue &color)
bool get3DPoint(Ogre::Viewport *viewport, const int x, const int y, Ogre::Vector3 &result_point)
Ogre::Technique * fallback_black_technique_
Ogre::PixelBox depth_pixel_box_
boost::recursive_mutex global_mutex_
bool interaction_enabled_
Property * getRoot() const
uint32_t depth_texture_height_
std::set< CollObjectHandle > S_CollObject
void renderQueueStarted(uint8_t queueGroupId, const std::string &invocation, bool &skipThisInvocation)
M_CollisionObjectToSelectionHandler objects_
virtual void visit(Ogre::Renderable *rend, ushort lodIndex, bool isDebug, Ogre::Any *pAny=0)
bool getPatchDepthImage(Ogre::Viewport *viewport, const int x, const int y, const unsigned width, const unsigned height, std::vector< float > &depth_vector)
Renders a depth image in a box around a point in a view port.
uint32_t CollObjectHandle