interactive_marker_control.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2011, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #ifndef INTERACTIVE_MARKER_CONTROL_H_
00031 #define INTERACTIVE_MARKER_CONTROL_H_
00032 
00033 
00034 #ifndef Q_MOC_RUN
00035 #include <boost/shared_ptr.hpp>
00036 #include <boost/enable_shared_from_this.hpp>
00037 
00038 #include <OgreRay.h>
00039 #include <OgreVector3.h>
00040 #include <OgreQuaternion.h>
00041 #include <OgreSceneManager.h>
00042 #endif
00043 
00044 #include <QCursor>
00045 
00046 #include <visualization_msgs/InteractiveMarkerControl.h>
00047 
00048 #include "rviz/default_plugin/markers/marker_base.h"
00049 #include "rviz/selection/forwards.h"
00050 #include "rviz/viewport_mouse_event.h"
00051 #include "rviz/interactive_object.h"
00052 
00053 namespace Ogre
00054 {
00055   class SceneNode;
00056 }
00057 
00058 namespace rviz
00059 {
00060 class DisplayContext;
00061 class InteractiveMarker;
00062 class PointsMarker;
00063 class Line;
00064 
00068 class InteractiveMarkerControl: public Ogre::SceneManager::Listener,
00069                                 public InteractiveObject,
00070                                 public boost::enable_shared_from_this<InteractiveMarkerControl>
00071 {
00072 public:
00080   InteractiveMarkerControl( DisplayContext* context,
00081                             Ogre::SceneNode *reference_node,
00082                             InteractiveMarker *parent );
00083 
00084   virtual ~InteractiveMarkerControl();
00085 
00088   void processMessage( const visualization_msgs::InteractiveMarkerControl &message );
00089 
00090   // called when interactive mode is globally switched on/off
00091   virtual void enableInteraction(bool enable);
00092 
00093   // will receive all mouse events while the handler has focus
00094   virtual void handleMouseEvent(ViewportMouseEvent& event);
00095 
00121   virtual void handle3DCursorEvent( ViewportMouseEvent event, const Ogre::Vector3& cursor_3D_pos, const Ogre::Quaternion& cursor_3D_orientation);
00122 
00128   void interactiveMarkerPoseChanged( Ogre::Vector3 int_marker_position, Ogre::Quaternion int_marker_orientation );
00129 
00130   bool isInteractive() { return interaction_mode_ != visualization_msgs::InteractiveMarkerControl::NONE; }
00131 
00132   // Called every frame by parent's update() function.
00133   void update();
00134 
00135   void setVisible( bool visible );
00136 
00137   bool getVisible();
00138 
00139   // Highlight types
00140   enum ControlHighlight { NO_HIGHLIGHT = 0,
00141          HOVER_HIGHLIGHT = 3,
00142          ACTIVE_HIGHLIGHT = 5};
00143 
00144   // Public access to highlight controls
00145   void setHighlight( const ControlHighlight &hl  );
00146 
00150   InteractiveMarker* getParent() { return parent_ ;}
00151 
00155   const std::string& getName() { return name_; }
00156 
00160   const QString& getDescription() { return description_; }
00161 
00165   int getInteractionMode() { return interaction_mode_; }
00166 
00170   int getOrientationMode() { return orientation_mode_; }
00171 
00175   void setShowVisualAids( bool show ) { show_visual_aids_ = show; }
00176 
00177 protected:
00178 
00179   // when this is called, we will face the camera
00180   virtual void preFindVisibleObjects(Ogre::SceneManager *source, Ogre::SceneManager::IlluminationRenderStage irs, Ogre::Viewport *v);
00181 
00182   void updateControlOrientationForViewFacing( Ogre::Viewport* v );
00183 
00186   Ogre::Ray getMouseRayInReferenceFrame( const ViewportMouseEvent& event, int x, int y );
00187 
00189   void beginRelativeMouseMotion( const ViewportMouseEvent& event );
00190 
00193   bool getRelativeMouseMotion( const ViewportMouseEvent& event, int& dx, int& dy );
00194 
00196   void rotateXYRelative( const ViewportMouseEvent& event );
00197 
00199   void rotateZRelative( const ViewportMouseEvent& event );
00200 
00202   void moveZAxisRelative( const ViewportMouseEvent& event );
00203 
00205   void moveZAxisWheel( const ViewportMouseEvent& event );
00206 
00208   void moveViewPlane( Ogre::Ray &mouse_ray, const ViewportMouseEvent& event );
00209 
00212   void rotate( Ogre::Ray &mouse_ray );
00213 
00215   void rotate(const Ogre::Vector3& cursor_position_in_reference_frame);
00216 
00219   void moveRotate( Ogre::Ray &mouse_ray );
00220 
00222   void moveRotate( const Ogre::Vector3& cursor_position_in_reference_frame, bool lock_axis = true);
00223 
00226   void movePlane( Ogre::Ray &mouse_ray );
00227 
00229   void movePlane( const Ogre::Vector3& cursor_position_in_reference_frame );
00230 
00233   void moveAxis( const Ogre::Ray& mouse_ray, const ViewportMouseEvent& event );
00234 
00236   void moveAxis( const Ogre::Vector3& cursor_position_in_reference_frame );
00237 
00239   void move3D( const Ogre::Vector3& cursor_position_in_reference_frame,
00240                const Ogre::Quaternion &cursor_orientation_in_reference_frame );
00241 
00243   void rotate3D( const Ogre::Vector3& cursor_position_in_reference_frame,
00244                  const Ogre::Quaternion &cursor_orientation_in_reference_frame );
00245 
00247   void moveRotate3D( const Ogre::Vector3& cursor_position_in_reference_frame,
00248                      const Ogre::Quaternion& cursor_orientation_in_reference_frame );
00249 
00251   bool intersectYzPlane( const Ogre::Ray& mouse_ray,
00252                          Ogre::Vector3& intersection_3d,
00253                          Ogre::Vector2& intersection_2d,
00254                          float& ray_t );
00255 
00257   bool intersectSomeYzPlane( const Ogre::Ray& mouse_ray,
00258                              const Ogre::Vector3& point_in_plane,
00259                              const Ogre::Quaternion& plane_orientation,
00260                              Ogre::Vector3& intersection_3d,
00261                              Ogre::Vector2& intersection_2d,
00262                              float& ray_t );
00263 
00267   bool findClosestPoint( const Ogre::Ray& target_ray,
00268                          const Ogre::Ray& mouse_ray,
00269                          Ogre::Vector3& closest_point );
00270 
00273   void worldToScreen( const Ogre::Vector3& pos_rel_reference,
00274                       const Ogre::Viewport* viewport,
00275                       Ogre::Vector2& screen_pos );
00276 
00278   void addHighlightPass( S_MaterialPtr materials );
00279 
00280   // set the highlight color to (a,a,a)
00281   void setHighlight( float a );
00282 
00283   // Save a copy of the latest mouse event with the event type set to
00284   // QEvent::MouseMove, so that update() can resend the mouse event during
00285   // drag actions to maintain consistent behavior.
00286   void recordDraggingInPlaceEvent( ViewportMouseEvent& event );
00287 
00288   // Begin a new mouse motion.  Called when left button is pressed to begin a drag.
00289   void beginMouseMovement( ViewportMouseEvent& event, bool line_visible );
00290 
00291   // Motion part of mouse event handling.
00292   void handleMouseMovement( ViewportMouseEvent& event );
00293 
00294   // Mouse wheel part of mouse event handling.
00295   void handleMouseWheelMovement( ViewportMouseEvent& event );
00296 
00297   // Return closest point on a line to a test point.
00298   Ogre::Vector3 closestPointOnLineToPoint( const Ogre::Vector3& line_start,
00299                                            const Ogre::Vector3& line_dir,
00300                                            const Ogre::Vector3& test_point );
00301 
00303   void makeMarkers( const visualization_msgs::InteractiveMarkerControl &message );
00304 
00305   void stopDragging( bool force = false );
00306 
00307   virtual const QCursor& getCursor() const { return cursor_; }
00308 
00309   bool mouse_dragging_;
00310   Ogre::Viewport* drag_viewport_;
00311 
00312   ViewportMouseEvent dragging_in_place_event_;
00313 
00314   DisplayContext* context_;
00315 
00316   CollObjectHandle coll_object_handle_;
00317 
00320   Ogre::SceneNode *reference_node_;
00321 
00328   Ogre::SceneNode *control_frame_node_;
00329 
00330   // this is a child of scene_node, but might be oriented differently
00331   Ogre::SceneNode *markers_node_;
00332 
00333   // interaction mode
00334   int interaction_mode_;
00335   int orientation_mode_;
00336 
00337   // if in view facing mode, the markers should be
00338   // view facing as well
00339   // if set to false, they will follow the parent's transformations
00340   bool independent_marker_orientation_;
00341 
00346   Ogre::Quaternion control_orientation_;
00347 
00348   bool always_visible_;
00349 
00350   QString description_;
00351 
00352   std::string name_;
00353 
00354   typedef boost::shared_ptr<MarkerBase> MarkerBasePtr;
00355   std::vector< MarkerBasePtr > markers_;
00356 
00357   InteractiveMarker *parent_;
00358 
00359   std::set<Ogre::Pass*> highlight_passes_;
00360 
00361   // PointsMarkers are rendered by special shader programs, so the
00362   // regular highlighting method does not work for them.  Keep a
00363   // vector of them so we can call their setHighlightColor() function.
00364   typedef boost::shared_ptr<PointsMarker> PointsMarkerPtr;
00365   std::vector< PointsMarkerPtr > points_markers_;
00366 
00369   Ogre::Radian rotation_;
00370 
00374   Ogre::Radian rotation_at_mouse_down_;
00375 
00378   Ogre::Vector3 grab_point_in_reference_frame_;
00379 
00382   Ogre::Quaternion grab_orientation_in_reference_frame_;
00383 
00386   Ogre::Vector3 parent_to_cursor_in_cursor_frame_at_grab_;
00387 
00390   Ogre::Quaternion rotation_cursor_to_parent_at_grab_;
00391 
00393   Qt::KeyboardModifiers modifiers_at_drag_begin_;
00394 
00396   int mouse_x_at_drag_begin_;
00397   int mouse_y_at_drag_begin_;
00398 
00399   /* mouse ray when drag begins. */
00400   Ogre::Ray mouse_ray_at_drag_begin_;
00401 
00402   /* how far to move in Z when mouse moves 1 pixel. */
00403   double mouse_z_scale_;
00404 
00406   int mouse_relative_to_absolute_x_;
00407   int mouse_relative_to_absolute_y_;
00408 
00410   Ogre::Vector3 parent_to_grab_position_; // obsolete now, but left for ABI compatibility
00411 
00413   Ogre::Vector3 parent_position_at_mouse_down_;
00414 
00417   Ogre::Quaternion control_frame_orientation_at_mouse_down_;
00418 
00421   Ogre::Quaternion parent_orientation_at_mouse_down_;
00422 
00426   Ogre::Vector3 rotation_axis_;
00427 
00430   Ogre::Vector3 rotation_center_rel_control_;
00431 
00434   Ogre::Vector3 grab_point_rel_control_;
00435 
00436   bool has_focus_;
00437   bool interaction_enabled_;
00438 
00439   bool visible_;
00440   bool view_facing_;
00441 
00442   QCursor cursor_;
00443   QString status_msg_;
00444 
00445   bool mouse_down_;
00446 
00447   boost::shared_ptr<Line> line_;
00448 
00449   bool show_visual_aids_;
00450 };
00451 
00452 }
00453 
00454 #endif /* INTERACTIVE_MARKER_CONTROL_H_ */


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Jun 6 2019 18:02:15