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  virtual ~InteractiveMarkerControl();
85 
88  void processMessage( const visualization_msgs::InteractiveMarkerControl &message );
89 
90  // called when interactive mode is globally switched on/off
91  virtual void enableInteraction(bool enable);
92 
93  // will receive all mouse events while the handler has focus
94  virtual void handleMouseEvent(ViewportMouseEvent& event);
95 
121  virtual void handle3DCursorEvent( ViewportMouseEvent event, const Ogre::Vector3& cursor_3D_pos, const Ogre::Quaternion& cursor_3D_orientation);
122 
128  void interactiveMarkerPoseChanged( Ogre::Vector3 int_marker_position, Ogre::Quaternion int_marker_orientation );
129 
130  bool isInteractive() { return interaction_mode_ != visualization_msgs::InteractiveMarkerControl::NONE; }
131 
132  // Called every frame by parent's update() function.
133  void update();
134 
135  void setVisible( bool visible );
136 
137  bool getVisible();
138 
139  // Highlight types
140  enum ControlHighlight { NO_HIGHLIGHT = 0,
141  HOVER_HIGHLIGHT = 3,
142  ACTIVE_HIGHLIGHT = 5};
143 
144  // Public access to highlight controls
145  void setHighlight( const ControlHighlight &hl );
146 
150  InteractiveMarker* getParent() { return parent_ ;}
151 
155  const std::string& getName() { return name_; }
156 
160  const QString& getDescription() { return description_; }
161 
165  int getInteractionMode() { return interaction_mode_; }
166 
170  int getOrientationMode() { return orientation_mode_; }
171 
175  void setShowVisualAids( bool show ) { show_visual_aids_ = show; }
176 
177 protected:
178 
179  // when this is called, we will face the camera
180  virtual void preFindVisibleObjects(Ogre::SceneManager *source, Ogre::SceneManager::IlluminationRenderStage irs, Ogre::Viewport *v);
181 
182  void updateControlOrientationForViewFacing( Ogre::Viewport* v );
183 
186  Ogre::Ray getMouseRayInReferenceFrame( const ViewportMouseEvent& event, int x, int y );
187 
189  void beginRelativeMouseMotion( const ViewportMouseEvent& event );
190 
193  bool getRelativeMouseMotion( const ViewportMouseEvent& event, int& dx, int& dy );
194 
196  void rotateXYRelative( const ViewportMouseEvent& event );
197 
199  void rotateZRelative( const ViewportMouseEvent& event );
200 
202  void moveZAxisRelative( const ViewportMouseEvent& event );
203 
205  void moveZAxisWheel( const ViewportMouseEvent& event );
206 
208  void moveViewPlane( Ogre::Ray &mouse_ray, const ViewportMouseEvent& event );
209 
212  void rotate( Ogre::Ray &mouse_ray );
213 
215  void rotate(const Ogre::Vector3& cursor_position_in_reference_frame);
216 
219  void moveRotate( Ogre::Ray &mouse_ray );
220 
222  void moveRotate( const Ogre::Vector3& cursor_position_in_reference_frame, bool lock_axis = true);
223 
226  void movePlane( Ogre::Ray &mouse_ray );
227 
229  void movePlane( const Ogre::Vector3& cursor_position_in_reference_frame );
230 
233  void moveAxis( const Ogre::Ray& mouse_ray, const ViewportMouseEvent& event );
234 
236  void moveAxis( const Ogre::Vector3& cursor_position_in_reference_frame );
237 
239  void move3D( const Ogre::Vector3& cursor_position_in_reference_frame,
240  const Ogre::Quaternion &cursor_orientation_in_reference_frame );
241 
243  void rotate3D( const Ogre::Vector3& cursor_position_in_reference_frame,
244  const Ogre::Quaternion &cursor_orientation_in_reference_frame );
245 
247  void moveRotate3D( const Ogre::Vector3& cursor_position_in_reference_frame,
248  const Ogre::Quaternion& cursor_orientation_in_reference_frame );
249 
251  bool intersectYzPlane( const Ogre::Ray& mouse_ray,
252  Ogre::Vector3& intersection_3d,
253  Ogre::Vector2& intersection_2d,
254  float& ray_t );
255 
257  bool intersectSomeYzPlane( const Ogre::Ray& mouse_ray,
258  const Ogre::Vector3& point_in_plane,
259  const Ogre::Quaternion& plane_orientation,
260  Ogre::Vector3& intersection_3d,
261  Ogre::Vector2& intersection_2d,
262  float& ray_t );
263 
267  bool findClosestPoint( const Ogre::Ray& target_ray,
268  const Ogre::Ray& mouse_ray,
269  Ogre::Vector3& closest_point );
270 
273  void worldToScreen( const Ogre::Vector3& pos_rel_reference,
274  const Ogre::Viewport* viewport,
275  Ogre::Vector2& screen_pos );
276 
278  void addHighlightPass( S_MaterialPtr materials );
279 
280  // set the highlight color to (a,a,a)
281  void setHighlight( float a );
282 
283  // Save a copy of the latest mouse event with the event type set to
284  // QEvent::MouseMove, so that update() can resend the mouse event during
285  // drag actions to maintain consistent behavior.
286  void recordDraggingInPlaceEvent( ViewportMouseEvent& event );
287 
288  // Begin a new mouse motion. Called when left button is pressed to begin a drag.
289  void beginMouseMovement( ViewportMouseEvent& event, bool line_visible );
290 
291  // Motion part of mouse event handling.
292  void handleMouseMovement( ViewportMouseEvent& event );
293 
294  // Mouse wheel part of mouse event handling.
295  void handleMouseWheelMovement( ViewportMouseEvent& event );
296 
297  // Return closest point on a line to a test point.
298  Ogre::Vector3 closestPointOnLineToPoint( const Ogre::Vector3& line_start,
299  const Ogre::Vector3& line_dir,
300  const Ogre::Vector3& test_point );
301 
303  void makeMarkers( const visualization_msgs::InteractiveMarkerControl &message );
304 
305  void stopDragging( bool force = false );
306 
307  virtual const QCursor& getCursor() const { return cursor_; }
308 
310  Ogre::Viewport* drag_viewport_;
311 
313 
315 
317 
320  Ogre::SceneNode *reference_node_;
321 
328  Ogre::SceneNode *control_frame_node_;
329 
330  // this is a child of scene_node, but might be oriented differently
331  Ogre::SceneNode *markers_node_;
332 
333  // interaction mode
336 
337  // if in view facing mode, the markers should be
338  // view facing as well
339  // if set to false, they will follow the parent's transformations
341 
346  Ogre::Quaternion control_orientation_;
347 
349 
350  QString description_;
351 
352  std::string name_;
353 
355  std::vector< MarkerBasePtr > markers_;
356 
358 
359  std::set<Ogre::Pass*> highlight_passes_;
360 
361  // PointsMarkers are rendered by special shader programs, so the
362  // regular highlighting method does not work for them. Keep a
363  // vector of them so we can call their setHighlightColor() function.
365  std::vector< PointsMarkerPtr > points_markers_;
366 
369  Ogre::Radian rotation_;
370 
375 
379 
383 
387 
391 
393  Qt::KeyboardModifiers modifiers_at_drag_begin_;
394 
398 
399  /* mouse ray when drag begins. */
401 
402  /* how far to move in Z when mouse moves 1 pixel. */
404 
408 
410  Ogre::Vector3 parent_to_grab_position_; // obsolete now, but left for ABI compatibility
411 
414 
418 
422 
426  Ogre::Vector3 rotation_axis_;
427 
431 
434  Ogre::Vector3 grab_point_rel_control_;
435 
438 
439  bool visible_;
441 
442  QCursor cursor_;
443  QString status_msg_;
444 
446 
448 
450 };
451 
452 }
453 
454 #endif /* INTERACTIVE_MARKER_CONTROL_H_ */
std::set< Ogre::Pass * > highlight_passes_
void setShowVisualAids(bool show)
If true, will show some geometric helpers while dragging.
TFSIMD_FORCE_INLINE const tfScalar & y() const
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
std::vector< PointsMarkerPtr > points_markers_
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
TFSIMD_FORCE_INLINE const tfScalar & x() const
std::vector< MarkerBasePtr > markers_
virtual const QCursor & getCursor() const
TFSIMD_FORCE_INLINE Vector3 rotate(const Vector3 &wAxis, const tfScalar angle) const
std::set< Ogre::MaterialPtr > S_MaterialPtr
Definition: marker_base.h:57
uint32_t CollObjectHandle
Definition: forwards.h:46
boost::shared_ptr< PointsMarker > PointsMarkerPtr


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:51