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)
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(
141 ss.str() +
"Texture", Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, pixel_stream, 1, 1,
142 Ogre::PF_R8G8B8A8, Ogre::TEX_TYPE_2D, 0);
144 Ogre::MaterialPtr material = Ogre::MaterialManager::getSingleton().create(
145 ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
146 material->setLightingEnabled(
false);
149 Ogre::AxisAlignedBox aabInf;
150 aabInf.setInfinite();
153 material->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
154 material->setCullingMode(Ogre::CULL_NONE);
156 Ogre::TextureUnitState* tex_unit = material->getTechnique(0)->getPass(0)->createTextureUnitState();
157 tex_unit->setTextureName(tex->getName());
158 tex_unit->setTextureFiltering(Ogre::TFO_NONE);
163 camera_ = scene_manager->createCamera(ss.str() +
"_camera");
181 ROS_DEBUG(
"SelectionManager.get3DPoint()");
183 std::vector<Ogre::Vector3> result_points_temp;
184 bool success =
get3DPatch(viewport, x, y, 1, 1,
true, result_points_temp);
185 if (result_points_temp.empty())
190 result_point = result_points_temp[0];
201 std::vector<float>& depth_vector)
203 unsigned int num_pixels = width * height;
204 depth_vector.reserve(num_pixels);
209 M_CollisionObjectToSelectionHandler::iterator handler_it =
objects_.begin();
210 M_CollisionObjectToSelectionHandler::iterator handler_end =
objects_.end();
212 for (; handler_it != handler_end; ++handler_it)
214 handler_it->second->preRenderPass(0);
222 for (uint32_t pixel = 0; pixel < num_pixels; ++pixel)
224 uint8_t a = data_ptr[4 * pixel];
225 uint8_t b = data_ptr[4 * pixel + 1];
226 uint8_t c = data_ptr[4 * pixel + 2];
228 int int_depth = (c << 16) | (b << 8) | a;
229 float normalized_depth = ((float)int_depth) / (float)0xffffff;
230 depth_vector.push_back(normalized_depth *
camera_->getFarClipDistance());
235 ROS_WARN(
"Failed to render depth patch\n");
241 for (; handler_it != handler_end; ++handler_it)
243 handler_it->second->postRenderPass(0);
256 std::vector<Ogre::Vector3>& result_points)
259 ROS_DEBUG(
"SelectionManager.get3DPatch()");
261 std::vector<float> depth_vector;
268 unsigned int pixel_counter = 0;
269 Ogre::Matrix4 projection =
camera_->getProjectionMatrix();
272 for (
unsigned y_iter = 0; y_iter < height; ++y_iter)
273 for (
unsigned x_iter = 0; x_iter < width; ++x_iter)
275 depth = depth_vector[pixel_counter];
278 if ((depth >
camera_->getFarClipDistance()) || (depth == 0))
283 result_points.push_back(Ogre::Vector3(NAN, NAN, NAN));
289 Ogre::Vector3 result_point;
293 Ogre::Real screenx = float(x_iter + .5) / float(width);
294 Ogre::Real screeny = float(y_iter + .5) / float(height);
295 if (projection[3][3] == 0.0)
298 Ogre::Ray vp_ray =
camera_->getCameraToViewportRay(screenx, screeny);
301 Ogre::Vector3 dir_cam =
camera_->getDerivedOrientation().Inverse() * vp_ray.getDirection();
304 dir_cam = dir_cam / dir_cam.z * depth * -1;
307 result_point =
camera_->getDerivedPosition() +
camera_->getDerivedOrientation() * dir_cam;
314 camera_->getCameraToViewportRay(screenx, screeny, &ray);
316 result_point = ray.getPoint(depth);
319 result_points.push_back(result_point);
323 return !result_points.empty();
334 ROS_ERROR_STREAM(
"SelectionManager::setDepthTextureSize invalid width requested. Max Width: 1024 -- "
336 << width <<
". Capping Width at 1024.");
345 ROS_ERROR_STREAM(
"SelectionManager::setDepthTextureSize invalid height requested. Max Height: 1024 "
346 "-- Height requested: "
347 << width <<
". Capping Height at 1024.");
356 std::string tex_name =
"DepthTexture";
362 Ogre::TextureManager::getSingleton().remove(tex_name);
366 tex_name, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, Ogre::TEX_TYPE_2D,
370 render_texture->setAutoUpdated(
false);
389 std::string tex_name;
395 Ogre::TextureManager::getSingleton().remove(tex_name);
399 std::stringstream ss;
400 static int count = 0;
401 ss <<
"SelectionTexture" << count++;
407 tex_name, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, Ogre::TEX_TYPE_2D, size,
408 size, 0, Ogre::PF_R8G8B8, Ogre::TU_STATIC | Ogre::TU_RENDERTARGET);
410 Ogre::RenderTexture* render_texture =
render_textures_[pass]->getBuffer()->getRenderTarget();
411 render_texture->setAutoUpdated(
false);
426 M_CollisionObjectToSelectionHandler::iterator handler_it =
objects_.begin();
427 M_CollisionObjectToSelectionHandler::iterator handler_end =
objects_.end();
428 for (; handler_it != handler_end; ++handler_it)
432 object->enableInteraction(enable);
449 for (
unsigned int i = 0; i < 24; i++)
451 uint32_t shift = (((23 - i) % 3) * 8) + (23 - i) / 3;
452 uint32_t bit = ((uint32_t)(
uid_counter_ >> i) & (uint32_t)1) << shift;
475 bool inserted =
objects_.insert(std::make_pair(obj, handler)).second;
493 objs.insert(std::make_pair(it->first, it->second));
548 pick(viewport, x1, y1, x2, y2, results);
566 float nx1 = ((float)x1 / viewport->getActualWidth()) * 2 - 1;
567 float nx2 = ((float)x2 / viewport->getActualWidth()) * 2 - 1;
568 float ny1 = -(((float)y1 / viewport->getActualHeight()) * 2 - 1);
569 float ny2 = -(((float)y2 / viewport->getActualHeight()) * 2 - 1);
571 nx1 = nx1 < -1 ? -1 : (nx1 > 1 ? 1 : nx1);
572 ny1 = ny1 < -1 ? -1 : (ny1 > 1 ? 1 : ny1);
573 nx2 = nx2 < -1 ? -1 : (nx2 > 1 ? 1 : nx2);
574 ny2 = ny2 < -1 ? -1 : (ny2 > 1 ? 1 : ny2);
581 int w = box.getWidth();
582 int h = box.getHeight();
585 pixels.reserve(w * h);
586 size_t size = Ogre::PixelUtil::getMemorySize(1, 1, 1, box.format);
588 for (
int y = 0; y < h; y++)
590 for (
int x = 0; x < w; x++)
592 uint32_t pos = (x + y * w) * size;
593 uint32_t pix_val = 0;
594 memcpy((uint8_t*)&pix_val, (uint8_t*)box.data + pos, size);
610 std::stringstream scheme;
626 const Ogre::TexturePtr& tex,
631 Ogre::PixelBox& dst_box,
632 const std::string& material_scheme,
633 unsigned texture_width,
634 unsigned texture_height)
647 if (x1 > viewport->getActualWidth() - 2)
648 x1 = viewport->getActualWidth() - 2;
649 if (y1 > viewport->getActualHeight() - 2)
650 y1 = viewport->getActualHeight() - 2;
655 if (x2 > viewport->getActualWidth() - 2)
656 x2 = viewport->getActualWidth() - 2;
657 if (y2 > viewport->getActualHeight() - 2)
658 y2 = viewport->getActualHeight() - 2;
665 if (x2 == x1 || y2 == y1)
667 ROS_WARN(
"SelectionManager::render(): not rendering 0 size area.");
672 unsigned w = x2 - x1;
673 unsigned h = y2 - y1;
675 Ogre::HardwarePixelBufferSharedPtr pixel_buffer = tex->getBuffer();
676 Ogre::RenderTexture* render_texture = pixel_buffer->getRenderTarget();
678 Ogre::Matrix4 proj_matrix = viewport->getCamera()->getProjectionMatrix();
679 Ogre::Matrix4 scale_matrix = Ogre::Matrix4::IDENTITY;
680 Ogre::Matrix4 trans_matrix = Ogre::Matrix4::IDENTITY;
682 float x1_rel =
static_cast<float>(x1) /
static_cast<float>(viewport->getActualWidth() - 1) - 0.5
f;
683 float y1_rel =
static_cast<float>(y1) /
static_cast<float>(viewport->getActualHeight() - 1) - 0.5
f;
684 float x2_rel =
static_cast<float>(x2) /
static_cast<float>(viewport->getActualWidth() - 1) - 0.5
f;
685 float y2_rel =
static_cast<float>(y2) /
static_cast<float>(viewport->getActualHeight() - 1) - 0.5
f;
687 scale_matrix[0][0] = 1.0 / (x2_rel - x1_rel);
688 scale_matrix[1][1] = 1.0 / (y2_rel - y1_rel);
690 trans_matrix[0][3] -= x1_rel + x2_rel;
691 trans_matrix[1][3] += y1_rel + y2_rel;
693 camera_->setCustomProjectionMatrix(
true, scale_matrix * trans_matrix * proj_matrix);
695 camera_->setPosition(viewport->getCamera()->getDerivedPosition());
696 camera_->setOrientation(viewport->getCamera()->getDerivedOrientation());
699 if (render_texture->getNumViewports() == 0)
701 render_texture->removeAllViewports();
702 render_texture->addViewport(
camera_);
703 Ogre::Viewport* render_viewport = render_texture->getViewport(0);
704 render_viewport->setClearEveryFrame(
true);
705 render_viewport->setBackgroundColour(Ogre::ColourValue::Black);
706 render_viewport->setOverlaysEnabled(
false);
707 render_viewport->setMaterialScheme(material_scheme);
710 unsigned render_w = w;
711 unsigned render_h = h;
715 if (render_w > texture_width)
717 render_w = texture_width;
718 render_h = round(
float(h) * (
float)texture_width / (
float)w);
723 if (render_h > texture_height)
725 render_h = texture_height;
726 render_w = round(
float(w) * (
float)texture_height / (
float)h);
731 if (render_w > texture_width)
732 render_w = texture_width;
733 if (render_h > texture_height)
734 render_h = texture_height;
737 Ogre::Viewport* render_viewport = render_texture->getViewport(0);
738 render_viewport->setDimensions(0, 0, (
float)render_w / (
float)texture_width,
739 (
float)render_h / (
float)texture_height);
742 render_viewport->setVisibilityMask(viewport->getVisibilityMask());
747 Ogre::MaterialManager::getSingleton().addListener(
this);
749 render_texture->update();
769 Ogre::MaterialManager::getSingleton().removeListener(
this);
771 render_w = render_viewport->getActualWidth();
772 render_h = render_viewport->getActualHeight();
774 Ogre::PixelFormat format = pixel_buffer->getFormat();
776 int size = Ogre::PixelUtil::getMemorySize(render_w, render_h, 1, format);
777 uint8_t* data =
new uint8_t[size];
779 delete[](uint8_t*) dst_box.data;
780 dst_box = Ogre::PixelBox(render_w, render_h, 1, format, data);
782 pixel_buffer->blitToMemory(dst_box, dst_box);
801 pub = nh.
advertise<sensor_msgs::Image>(
"/rviz_debug/" + label, 2);
809 sensor_msgs::Image msg;
811 msg.width = pixel_box.getWidth();
812 msg.height = pixel_box.getHeight();
814 msg.is_bigendian =
false;
815 msg.step = msg.width * 3;
816 int dest_byte_count = msg.width * msg.height * 3;
817 msg.data.resize(dest_byte_count);
819 uint8_t* source_ptr = (uint8_t*)pixel_box.data;
820 int pre_pixel_padding = 0;
821 int post_pixel_padding = 0;
822 switch (pixel_box.format)
824 case Ogre::PF_R8G8B8:
826 case Ogre::PF_A8R8G8B8:
827 case Ogre::PF_X8R8G8B8:
828 post_pixel_padding = 1;
830 case Ogre::PF_R8G8B8A8:
831 pre_pixel_padding = 1;
834 ROS_ERROR(
"SelectionManager::publishDebugImage(): Incompatible pixel format [%d]", pixel_box.format);
838 while (dest_index < dest_byte_count)
840 source_ptr += pre_pixel_padding;
844 source_ptr += post_pixel_padding;
845 msg.data[dest_index++] = r;
846 msg.data[dest_index++] = g;
847 msg.data[dest_index++] = b;
855 bool& skipThisInvocation)
862 skipThisInvocation =
true;
871 bool single_render_pass)
875 bool need_additional_render =
false;
887 M_CollisionObjectToSelectionHandler::iterator handler_it =
objects_.begin();
888 M_CollisionObjectToSelectionHandler::iterator handler_end =
objects_.end();
889 for (; handler_it != handler_end; ++handler_it)
891 handler_it->second->preRenderPass(0);
898 for (; handler_it != handler_end; ++handler_it)
900 handler_it->second->postRenderPass(0);
903 handles_by_pixel.reserve(pixels.size());
904 V_CollObject::iterator it = pixels.begin();
905 V_CollObject::iterator end = pixels.end();
906 for (; it != end; ++it)
912 handles_by_pixel.push_back(handle);
923 std::pair<M_Picked::iterator, bool> insert_result =
924 results.insert(std::make_pair(handle,
Picked(handle)));
925 if (insert_result.second)
929 need_additional.insert(handle);
930 need_additional_render =
true;
935 insert_result.first->second.pixel_count++;
944 extra_by_pixel.resize(handles_by_pixel.size());
948 S_CollObject::iterator need_it = need_additional.begin();
949 S_CollObject::iterator need_end = need_additional.end();
950 for (; need_it != need_end; ++need_it)
962 S_CollObject::iterator need_it = need_additional.begin();
963 S_CollObject::iterator need_end = need_additional.end();
964 for (; need_it != need_end; ++need_it)
974 V_CollObject::iterator pix_it = pixels.begin();
975 V_CollObject::iterator pix_end = pixels.end();
976 for (; pix_it != pix_end; ++pix_it, ++i)
984 extra_by_pixel[i] = 0;
987 if (need_additional.find(handle) != need_additional.end())
990 extra_by_pixel[i] |= extra_handle << (32 * (pass - 1));
994 extra_by_pixel[i] = 0;
998 need_additional_render =
false;
999 need_additional.clear();
1000 M_Picked::iterator handle_it = results.begin();
1001 M_Picked::iterator handle_end = results.end();
1002 for (; handle_it != handle_end; ++handle_it)
1006 if (
getHandler(handle)->needsAdditionalRenderPass(pass + 1))
1008 need_additional_render =
true;
1009 need_additional.insert(handle);
1015 V_uint64::iterator pix_2_it = extra_by_pixel.begin();
1016 V_uint64::iterator pix_2_end = extra_by_pixel.end();
1017 for (; pix_2_it != pix_2_end; ++pix_2_it, ++i)
1026 M_Picked::iterator picked_it = results.find(handle);
1027 if (picked_it == results.end())
1032 Picked& picked = picked_it->second;
1042 const Ogre::String& scheme_name,
1043 Ogre::Material* original_material,
1045 const Ogre::Renderable* rend)
1048 Ogre::CullingMode culling_mode = Ogre::CULL_CLOCKWISE;
1049 Ogre::Technique* orig_tech = original_material->getTechnique(0);
1050 if (orig_tech && orig_tech->getNumPasses() > 0)
1052 culling_mode = orig_tech->getPass(0)->getCullingMode();
1056 bool has_pick_param = !rend->getUserObjectBindings().getUserAny(
"pick_handle").isEmpty();
1066 if (culling_mode == Ogre::CULL_CLOCKWISE)
1068 if (scheme_name ==
"Pick")
1072 else if (scheme_name ==
"Depth")
1076 if (scheme_name ==
"Pick1")
1087 if (scheme_name ==
"Pick")
1091 else if (scheme_name ==
"Depth")
1095 if (scheme_name ==
"Pick1")
1108 float r = ((handle >> 16) & 0xff) / 255.0f;
1109 float g = ((handle >> 8) & 0xff) / 255.0f;
1110 float b = (handle & 0xff) / 255.0
f;
1111 return Ogre::ColourValue(r, g, b, 1.0
f);
1115 const Ogre::ColourValue& color,
1116 Ogre::SceneNode* node)
1123 Ogre::SceneNode::ObjectIterator obj_it = node->getAttachedObjectIterator();
1124 while (obj_it.hasMoreElements())
1126 Ogre::MovableObject* obj = obj_it.getNext();
1130 Ogre::SceneNode::ChildNodeIterator child_it = node->getChildIterator();
1131 while (child_it.hasMoreElements())
1133 Ogre::SceneNode* child =
dynamic_cast<Ogre::SceneNode*
>(child_it.getNext());
1149 Ogre::Any* =
nullptr)
override
1152 rend->getUserObjectBindings().setUserAny(
"pick_handle", Ogre::Any(
handle_));
1160 const Ogre::ColourValue& color,
1161 Ogre::MovableObject*
object)
1164 object->visitRenderables(&visitor);
1165 object->getUserObjectBindings().setUserAny(
"pick_handle", Ogre::Any(handle));
1172 M_CollisionObjectToSelectionHandler::iterator it =
objects_.find(obj);
1185 M_Picked::const_iterator it = objs.begin();
1186 M_Picked::const_iterator end = objs.end();
1187 for (; it != end; ++it)
1200 M_Picked::const_iterator it = objs.begin();
1201 M_Picked::const_iterator end = objs.end();
1202 for (; it != end; ++it)
1207 added.insert(std::make_pair(it->first, ppb.first));
1228 std::pair<M_Picked::iterator, bool> pib =
selection_.insert(std::make_pair(obj.
handle, obj));
1235 return std::make_pair(obj,
true);
1239 Picked& cur = pib.first->second;
1244 for (; it != end; ++it)
1256 return std::make_pair(added,
true);
1260 return std::make_pair(
Picked(0),
false);
1272 for (; extra_it != extra_end; ++extra_it)
1274 sel_it->second.extra_handles.erase(*extra_it);
1277 if (sel_it->second.extra_handles.empty())
1296 Ogre::AxisAlignedBox combined;
1300 for (; it != end; ++it)
1302 const Picked& p = it->second;
1309 V_AABB::iterator aabb_it = aabbs.begin();
1310 V_AABB::iterator aabb_end = aabbs.end();
1311 for (; aabb_it != aabb_end; ++aabb_it)
1313 combined.merge(*aabb_it);
1317 if (!combined.isInfinite() && !combined.isNull())
1319 Ogre::Vector3 center = combined.getCenter();
1323 controller->
lookAt(center);
1330 M_Picked::const_iterator it = removed.begin();
1331 M_Picked::const_iterator end = removed.end();
1332 for (; it != end; ++it)
1334 const Picked& picked = it->second;
1344 M_Picked::const_iterator it = added.begin();
1345 M_Picked::const_iterator end = added.end();
1346 for (; it != end; ++it)
1348 const Picked& picked = it->second;
1359 M_Picked::const_iterator it =
selection_.begin();
1360 M_Picked::const_iterator end =
selection_.end();
1361 for (; it != end; ++it)