5252
5353#include < rviz_mesh_tools_plugins/Types.hpp>
5454
55- // TODO: Make CL optional
56- // enable exceptions for OpenCL
57- // #define CL_HPP_TARGET_OPENCL_VERSION 120
58- // #define CL_HPP_MINIMUM_OPENCL_VERSION 110
59- // #define CL_HPP_ENABLE_EXCEPTIONS
60- // #include <CL/cl2.hpp>
61-
6255#include < vector>
63- #include < map>
6456#include < memory>
6557#include < boost/lexical_cast.hpp>
6658#include < boost/optional.hpp>
@@ -136,6 +128,10 @@ class ClusterLabelTool : public rviz_common::Tool
136128{
137129 Q_OBJECT
138130public:
131+ // Constants
132+ static constexpr float MIN_BRUSH_SIZE = 20 .0f ;
133+ static constexpr float MOUSE_WHEEL_BRUSH_SIZE_STEP = 10 ;
134+
139135 /* *
140136 * @brief Constructor
141137 */
@@ -181,10 +177,15 @@ class ClusterLabelTool : public rviz_common::Tool
181177 void setVisual (std::shared_ptr<ClusterLabelVisual> visual);
182178
183179 /* *
184- * @brief Adjust the sphere size for the brush tool
185- * @param size The sphere size
180+ * @brief Adjust the circle size for the brush tool
181+ * @param size The circle diameter in screen Pixels
182+ */
183+ void setBrushSize (float size);
184+
185+ /* *
186+ * @brief Set the culling mode for selection to match the MeshVisual
186187 */
187- void setSphereSize ( float size );
188+ void setCullingMode (Ogre::CullingMode mode );
188189
189190public Q_SLOTS:
190191
@@ -213,71 +214,70 @@ public Q_SLOTS:
213214private:
214215 std::vector<uint32_t > m_selectedFaces;
215216 std::vector<bool > m_faceSelectedArray;
216- bool m_displayInitialized;
217217 ClusterLabelDisplay* m_display;
218218 std::shared_ptr<ClusterLabelVisual> m_visual;
219219 std::shared_ptr<Geometry> m_meshGeometry;
220- float m_sphereSize = 1 . 0f ;
220+ float m_brushSize ;
221221
222222 // Selection Box
223- rviz_common::DisplayContext* m_displayContext;
224223 Ogre::SceneNode* m_sceneNode;
225224 Ogre::ManualObject* m_selectionBox;
226225 Ogre::MaterialPtr m_selectionBoxMaterial;
227-
228- // rviz_common::ViewportMouseEvent m_evt_start;
229- // rviz_common::ViewportMouseEvent m_evt_stop;
226+
227+ // Selection Circle
228+ Ogre::ManualObject* m_selectionCircle;
229+ Ogre::SceneNode* m_selectionCircleNode;
230230
231231 int m_bb_x1;
232232 int m_bb_y1;
233233 int m_bb_x2;
234234 int m_bb_y2;
235235
236236 rviz_common::RenderPanel* m_evt_panel;
237-
237+
238+ // Selection Modes
238239 bool m_multipleSelect = false ;
239240 bool m_singleSelect = false ;
240- bool m_singleDeselect = false ;
241+ bool m_circleSelect = false ;
242+ // Select = true Deselect = false
243+ bool m_selectionMode = false ;
241244
242245 std::vector<Ogre::Vector3> m_vertexPositions;
243246
247+ void initSelectionCircle ();
248+ void updateSelectionCircle (rviz_common::ViewportMouseEvent& event);
244249 void updateSelectionBox ();
245250 void selectionBoxStart (rviz_common::ViewportMouseEvent& event);
246251 void selectionBoxMove (rviz_common::ViewportMouseEvent& event);
247252 void selectMultipleFaces (rviz_common::ViewportMouseEvent& event, bool selectMode);
248- void selectFacesInBoxParallel (Ogre::PlaneBoundedVolume& volume, bool selectMode);
249253 void selectSingleFace (rviz_common::ViewportMouseEvent& event, bool selectMode);
250- void selectSingleFaceParallel (Ogre::Ray& ray, bool selectMode);
251- void selectSphereFaces (rviz_common::ViewportMouseEvent& event, bool selectMode);
252- void selectSphereFacesParallel (Ogre::Ray& ray, bool selectMode);
253- boost::optional<std::pair<uint32_t , float >> getClosestIntersectedFaceParallel (Ogre::Ray& ray);
254+ void selectCircleFaces (rviz_common::ViewportMouseEvent& event, bool selectMode);
254255
255256 rclcpp::Publisher<mesh_msgs::msg::MeshFaceClusterStamped>::SharedPtr m_labelPublisher;
256257
257- std::vector<float > m_vertexData;
258- std::array<float , 6 > m_rayData;
259- std::array<float , 4 > m_sphereData;
260- std::array<float , 3 > m_startNormalData;
261- std::vector<float > m_boxData;
262- std::vector<float > m_resultDistances;
263-
264- // OpenCL
265- // cl::Device m_clDevice;
266- // cl::Context m_clContext;
267- // cl::Program::Sources m_clProgramSources;
268- // cl::Program m_clProgram;
269- // cl::CommandQueue m_clQueue;
270- // cl::Buffer m_clVertexBuffer;
271- // cl::Buffer m_clResultBuffer;
272- // cl::Buffer m_clRayBuffer;
273- // cl::Buffer m_clSphereBuffer;
274- // cl::Buffer m_clBoxBuffer;
275- // cl::Buffer m_clStartNormalBuffer;
276- // cl::Kernel m_clKernelSingleRay;
277- // cl::Kernel m_clKernelSphere;
278- // cl::Kernel m_clKernelBox;
279- // cl::Kernel m_clKernelDirAndDist;
258+ /* *
259+ * @brief Renders the current Mesh to an Offscreen Buffer using the FaceIDs as colors.
260+ *
261+ * The resulting Image can be used to determine which faces are visible from the Camera.
262+ *
263+ * @return The rendered Image.
264+ */
265+ Ogre::Image renderMeshWithFaceID ();
266+
267+ /* *
268+ * @brief Setup the Selection Mesh from the current geometry
269+ */
270+ void updateSelectionMesh ();
271+
272+ // Accelerated area picking via Ogre render pass
273+ Ogre::TexturePtr m_selectionTexture;
274+ Ogre::MaterialPtr m_selectionMaterial;
275+ Ogre::ManualObject* m_selectionMesh;
276+ Ogre::SceneNode* m_selectionSceneNode;
277+ // Used to render only the selectionMesh to the offscreen Texture
278+ uint32_t m_selectionVisibilityBit;
279+ Ogre::CullingMode m_cullingMode;
280280};
281281} // end namespace rviz_mesh_tools_plugins
282282
283- #endif
283+ #endif
0 commit comments