interactive_marker_control.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef INTERACTIVE_MARKER_CONTROL_H_
31 #define INTERACTIVE_MARKER_CONTROL_H_
32 
33 
34 #ifndef Q_MOC_RUN
35 #include <boost/shared_ptr.hpp>
36 #include <boost/enable_shared_from_this.hpp>
37 
38 #include <OgreRay.h>
39 #include <OgreVector3.h>
40 #include <OgreQuaternion.h>
41 #include <OgreSceneManager.h>
42 #endif
43 
44 #include <QCursor>
45 
46 #include <visualization_msgs/InteractiveMarkerControl.h>
47 
52 
53 namespace Ogre
54 {
55 class SceneNode;
56 }
57 
58 namespace rviz
59 {
60 class DisplayContext;
61 class InteractiveMarker;
62 class PointsMarker;
63 class Line;
64 
68 class InteractiveMarkerControl : public Ogre::SceneManager::Listener,
69  public InteractiveObject,
70  public boost::enable_shared_from_this<InteractiveMarkerControl>
71 {
72 public:
81  Ogre::SceneNode* reference_node,
82  InteractiveMarker* parent);
83 
84  ~InteractiveMarkerControl() override;
85 
88  void processMessage(const visualization_msgs::InteractiveMarkerControl& message);
89 
90  // called when interactive mode is globally switched on/off
91  void enableInteraction(bool enable) override;
92 
93  // will receive all mouse events while the handler has focus
94  void handleMouseEvent(ViewportMouseEvent& event) override;
95 
121  virtual void handle3DCursorEvent(ViewportMouseEvent event,
122  const Ogre::Vector3& cursor_3D_pos,
123  const Ogre::Quaternion& cursor_3D_orientation);
124 
130  void interactiveMarkerPoseChanged(Ogre::Vector3 int_marker_position,
131  Ogre::Quaternion int_marker_orientation);
132 
133  bool isInteractive() override
134  {
135  return interaction_mode_ != visualization_msgs::InteractiveMarkerControl::NONE;
136  }
137 
138  // Called every frame by parent's update() function.
139  void update();
140 
141  void setVisible(bool visible);
142 
143  bool getVisible();
144 
145  // Highlight types
147  {
148  NO_HIGHLIGHT = 0,
149  HOVER_HIGHLIGHT = 3,
150  ACTIVE_HIGHLIGHT = 5
151  };
152 
153  // Public access to highlight controls
154  void setHighlight(const ControlHighlight& hl);
155 
160  {
161  return parent_;
162  }
163 
167  const std::string& getName()
168  {
169  return name_;
170  }
171 
175  const QString& getDescription()
176  {
177  return description_;
178  }
179 
184  {
185  return interaction_mode_;
186  }
187 
192  {
193  return orientation_mode_;
194  }
195 
199  void setShowVisualAids(bool show)
200  {
201  show_visual_aids_ = show;
202  }
203 
204 protected:
205  // when this is called, we will face the camera
206  void preFindVisibleObjects(Ogre::SceneManager* source,
207  Ogre::SceneManager::IlluminationRenderStage irs,
208  Ogre::Viewport* v) override;
209 
210  void updateControlOrientationForViewFacing(Ogre::Viewport* v);
211 
214  Ogre::Ray getMouseRayInReferenceFrame(const ViewportMouseEvent& event, int x, int y);
215 
217  void beginRelativeMouseMotion(const ViewportMouseEvent& event);
218 
221  bool getRelativeMouseMotion(const ViewportMouseEvent& event, int& dx, int& dy);
222 
224  void rotateXYRelative(const ViewportMouseEvent& event);
225 
227  void rotateZRelative(const ViewportMouseEvent& event);
228 
230  void moveZAxisRelative(const ViewportMouseEvent& event);
231 
233  void moveZAxisWheel(const ViewportMouseEvent& event);
234 
236  void moveViewPlane(Ogre::Ray& mouse_ray, const ViewportMouseEvent& event);
237 
240  void rotate(Ogre::Ray& mouse_ray);
241 
243  void rotate(const Ogre::Vector3& cursor_position_in_reference_frame);
244 
247  void moveRotate(Ogre::Ray& mouse_ray);
248 
251  void moveRotate(const Ogre::Vector3& cursor_position_in_reference_frame, bool lock_axis = true);
252 
255  void movePlane(Ogre::Ray& mouse_ray);
256 
258  void movePlane(const Ogre::Vector3& cursor_position_in_reference_frame);
259 
262  void moveAxis(const Ogre::Ray& mouse_ray, const ViewportMouseEvent& event);
263 
265  void moveAxis(const Ogre::Vector3& cursor_position_in_reference_frame);
266 
268  void move3D(const Ogre::Vector3& cursor_position_in_reference_frame,
269  const Ogre::Quaternion& cursor_orientation_in_reference_frame);
270 
272  void rotate3D(const Ogre::Vector3& cursor_position_in_reference_frame,
273  const Ogre::Quaternion& cursor_orientation_in_reference_frame);
274 
276  void moveRotate3D(const Ogre::Vector3& cursor_position_in_reference_frame,
277  const Ogre::Quaternion& cursor_orientation_in_reference_frame);
278 
280  bool intersectYzPlane(const Ogre::Ray& mouse_ray,
281  Ogre::Vector3& intersection_3d,
282  Ogre::Vector2& intersection_2d,
283  float& ray_t);
284 
286  bool intersectSomeYzPlane(const Ogre::Ray& mouse_ray,
287  const Ogre::Vector3& point_in_plane,
288  const Ogre::Quaternion& plane_orientation,
289  Ogre::Vector3& intersection_3d,
290  Ogre::Vector2& intersection_2d,
291  float& ray_t);
292 
296  bool findClosestPoint(const Ogre::Ray& target_ray,
297  const Ogre::Ray& mouse_ray,
298  Ogre::Vector3& closest_point);
299 
302  void worldToScreen(const Ogre::Vector3& pos_rel_reference,
303  const Ogre::Viewport* viewport,
304  Ogre::Vector2& screen_pos);
305 
307  void addHighlightPass(S_MaterialPtr materials);
308 
309  // set the highlight color to (a,a,a)
310  void setHighlight(float a);
311 
312  // Save a copy of the latest mouse event with the event type set to
313  // QEvent::MouseMove, so that update() can resend the mouse event during
314  // drag actions to maintain consistent behavior.
315  void recordDraggingInPlaceEvent(ViewportMouseEvent& event);
316 
317  // Begin a new mouse motion. Called when left button is pressed to begin a drag.
318  void beginMouseMovement(ViewportMouseEvent& event, bool line_visible);
319 
320  // Motion part of mouse event handling.
321  void handleMouseMovement(ViewportMouseEvent& event);
322 
323  // Mouse wheel part of mouse event handling.
324  void handleMouseWheelMovement(ViewportMouseEvent& event);
325 
326  // Return closest point on a line to a test point.
327  Ogre::Vector3 closestPointOnLineToPoint(const Ogre::Vector3& line_start,
328  const Ogre::Vector3& line_dir,
329  const Ogre::Vector3& test_point);
330 
332  void makeMarkers(const visualization_msgs::InteractiveMarkerControl& message);
333 
334  void stopDragging(bool force = false);
335 
336  const QCursor& getCursor() const override
337  {
338  return cursor_;
339  }
340 
342  Ogre::Viewport* drag_viewport_;
343 
345 
347 
349 
352  Ogre::SceneNode* reference_node_;
353 
360  Ogre::SceneNode* control_frame_node_;
361 
362  // this is a child of scene_node, but might be oriented differently
363  Ogre::SceneNode* markers_node_;
364 
365  // interaction mode
368 
369  // if in view facing mode, the markers should be
370  // view facing as well
371  // if set to false, they will follow the parent's transformations
373 
378  Ogre::Quaternion control_orientation_;
379 
381 
382  QString description_;
383 
384  std::string name_;
385 
387  std::vector<MarkerBasePtr> markers_;
388 
390 
391  std::set<Ogre::Pass*> highlight_passes_;
392 
393  // PointsMarkers are rendered by special shader programs, so the
394  // regular highlighting method does not work for them. Keep a
395  // vector of them so we can call their setHighlightColor() function.
397  std::vector<PointsMarkerPtr> points_markers_;
398 
401  Ogre::Radian rotation_;
402 
407 
411 
415 
419 
423 
425  Qt::KeyboardModifiers modifiers_at_drag_begin_;
426 
430 
431  /* mouse ray when drag begins. */
433 
434  /* how far to move in Z when mouse moves 1 pixel. */
436 
440 
442  Ogre::Vector3 parent_to_grab_position_; // obsolete now, but left for ABI compatibility
443 
446 
450 
454 
458  Ogre::Vector3 rotation_axis_;
459 
463 
466  Ogre::Vector3 grab_point_rel_control_;
467 
470 
471  bool visible_;
473 
474  QCursor cursor_;
475  QString status_msg_;
476 
478 
480 
482 };
483 
484 } // namespace rviz
485 
486 #endif /* INTERACTIVE_MARKER_CONTROL_H_ */
std::set< Ogre::Pass * > highlight_passes_
void setShowVisualAids(bool show)
If true, will show some geometric helpers while dragging.
std::vector< PointsMarkerPtr > points_markers_
void setVisible(PanelDockWidget *widget, bool visible)
Definition: display.cpp:293
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
Abstract base class of things in the scene which handle mouse events.
Pure-virtual base class for objects which give Display subclasses context in which to work...
boost::shared_ptr< MarkerBase > MarkerBasePtr
std::vector< MarkerBasePtr > markers_
std::set< Ogre::MaterialPtr > S_MaterialPtr
Definition: marker_base.h:57
const QCursor & getCursor() const override
uint32_t CollObjectHandle
Definition: forwards.h:45
boost::shared_ptr< PointsMarker > PointsMarkerPtr


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:24