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 #ifndef Q_MOC_RUN
34 #include <boost/shared_ptr.hpp>
35 #include <boost/enable_shared_from_this.hpp>
36 
37 #include <OgreRay.h>
39 #include <OgreQuaternion.h>
40 #include <OgreSceneManager.h>
41 #endif
42 
43 #include <QCursor>
44 
45 #include <visualization_msgs/InteractiveMarkerControl.h>
46 
47 #include <rviz/windows_compat.h>
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  {
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(const 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.
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.
322 
323  // Mouse wheel part of mouse event handling.
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_ */
rviz::InteractiveMarkerControl::cursor_
QCursor cursor_
Definition: interactive_marker_control.h:474
rviz::InteractiveMarkerControl::getDescription
const QString & getDescription()
Definition: interactive_marker_control.h:175
rviz::InteractiveMarkerControl::moveRotate
void moveRotate(Ogre::Ray &mouse_ray)
Definition: interactive_marker_control.cpp:727
rviz::InteractiveMarkerControl::worldToScreen
void worldToScreen(const Ogre::Vector3 &pos_rel_reference, const Ogre::Viewport *viewport, Ogre::Vector2 &screen_pos)
Definition: interactive_marker_control.cpp:614
rviz::S_MaterialPtr
std::set< Ogre::MaterialPtr > S_MaterialPtr
Definition: marker_base.h:51
rviz::InteractiveMarkerControl::highlight_passes_
std::set< Ogre::Pass * > highlight_passes_
Definition: interactive_marker_control.h:391
rviz::InteractiveMarkerControl::parent_to_cursor_in_cursor_frame_at_grab_
Ogre::Vector3 parent_to_cursor_in_cursor_frame_at_grab_
Definition: interactive_marker_control.h:418
rviz::InteractiveMarkerControl::view_facing_
bool view_facing_
Definition: interactive_marker_control.h:472
rviz::InteractiveMarkerControl::parent_orientation_at_mouse_down_
Ogre::Quaternion parent_orientation_at_mouse_down_
Definition: interactive_marker_control.h:453
windows_compat.h
Ogre
Definition: axes_display.h:35
rviz::InteractiveMarkerControl::getParent
InteractiveMarker * getParent()
Definition: interactive_marker_control.h:159
rviz::InteractiveMarkerControl::coll_object_handle_
CollObjectHandle coll_object_handle_
Definition: interactive_marker_control.h:348
boost::shared_ptr
rviz::InteractiveMarkerControl::MarkerBasePtr
boost::shared_ptr< MarkerBase > MarkerBasePtr
Definition: interactive_marker_control.h:386
rviz::InteractiveMarkerControl::reference_node_
Ogre::SceneNode * reference_node_
Definition: interactive_marker_control.h:352
rviz::InteractiveMarkerControl::markers_node_
Ogre::SceneNode * markers_node_
Definition: interactive_marker_control.h:363
forwards.h
rviz::InteractiveMarkerControl::setShowVisualAids
void setShowVisualAids(bool show)
If true, will show some geometric helpers while dragging.
Definition: interactive_marker_control.h:199
rviz::InteractiveMarkerControl::move3D
void move3D(const Ogre::Vector3 &cursor_position_in_reference_frame, const Ogre::Quaternion &cursor_orientation_in_reference_frame)
Definition: interactive_marker_control.cpp:859
rviz::InteractiveMarkerControl::update
void update()
Definition: interactive_marker_control.cpp:316
rviz::InteractiveMarkerControl::moveViewPlane
void moveViewPlane(Ogre::Ray &mouse_ray, const ViewportMouseEvent &event)
Definition: interactive_marker_control.cpp:558
rviz::InteractiveMarkerControl::line_
boost::shared_ptr< Line > line_
Definition: interactive_marker_control.h:479
rviz::InteractiveMarkerControl::beginRelativeMouseMotion
void beginRelativeMouseMotion(const ViewportMouseEvent &event)
Definition: interactive_marker_control.cpp:465
rviz::InteractiveMarkerControl::dragging_in_place_event_
ViewportMouseEvent dragging_in_place_event_
Definition: interactive_marker_control.h:344
rviz::InteractiveMarkerControl::name_
std::string name_
Definition: interactive_marker_control.h:384
interactive_object.h
rviz::ViewportMouseEvent
Definition: viewport_mouse_event.h:45
rviz::InteractiveMarkerControl::moveZAxisWheel
void moveZAxisWheel(const ViewportMouseEvent &event)
Definition: interactive_marker_control.cpp:545
rviz::InteractiveMarkerControl::getRelativeMouseMotion
bool getRelativeMouseMotion(const ViewportMouseEvent &event, int &dx, int &dy)
Definition: interactive_marker_control.cpp:477
viewport_mouse_event.h
rviz::InteractiveMarkerControl::markers_
std::vector< MarkerBasePtr > markers_
Definition: interactive_marker_control.h:387
rviz::InteractiveMarkerControl::rotateXYRelative
void rotateXYRelative(const ViewportMouseEvent &event)
Definition: interactive_marker_control.cpp:489
rviz::InteractiveMarkerControl::points_markers_
std::vector< PointsMarkerPtr > points_markers_
Definition: interactive_marker_control.h:397
rviz::InteractiveMarkerControl::getOrientationMode
int getOrientationMode()
Definition: interactive_marker_control.h:191
rviz::InteractiveMarkerControl::status_msg_
QString status_msg_
Definition: interactive_marker_control.h:475
rviz::InteractiveMarkerControl::parent_
InteractiveMarker * parent_
Definition: interactive_marker_control.h:389
rviz::InteractiveMarkerControl::handleMouseWheelMovement
void handleMouseWheelMovement(ViewportMouseEvent &event)
Definition: interactive_marker_control.cpp:1402
rviz::InteractiveMarkerControl::grab_point_in_reference_frame_
Ogre::Vector3 grab_point_in_reference_frame_
Definition: interactive_marker_control.h:410
rviz::InteractiveMarkerControl::modifiers_at_drag_begin_
Qt::KeyboardModifiers modifiers_at_drag_begin_
Definition: interactive_marker_control.h:425
rviz::InteractiveMarkerControl::rotation_center_rel_control_
Ogre::Vector3 rotation_center_rel_control_
Definition: interactive_marker_control.h:462
rviz::InteractiveMarkerControl::interaction_mode_
int interaction_mode_
Definition: interactive_marker_control.h:366
rviz::CollObjectHandle
uint32_t CollObjectHandle
Definition: forwards.h:45
rviz::InteractiveMarkerControl::enableInteraction
void enableInteraction(bool enable) override
Definition: interactive_marker_control.cpp:324
rviz::InteractiveMarkerControl::addHighlightPass
void addHighlightPass(const S_MaterialPtr &materials)
take all the materials, add a highlight pass and store a pointer to the pass for later use
Definition: interactive_marker_control.cpp:1457
rviz::InteractiveMarkerControl::getInteractionMode
int getInteractionMode()
Definition: interactive_marker_control.h:183
rviz::InteractiveMarkerControl::mouse_ray_at_drag_begin_
Ogre::Ray mouse_ray_at_drag_begin_
Definition: interactive_marker_control.h:432
rviz::InteractiveMarkerControl::rotate3D
void rotate3D(const Ogre::Vector3 &cursor_position_in_reference_frame, const Ogre::Quaternion &cursor_orientation_in_reference_frame)
Definition: interactive_marker_control.cpp:893
rviz::InteractiveMarkerControl::recordDraggingInPlaceEvent
void recordDraggingInPlaceEvent(ViewportMouseEvent &event)
Definition: interactive_marker_control.cpp:989
rviz::InteractiveMarkerControl::mouse_down_
bool mouse_down_
Definition: interactive_marker_control.h:477
rviz::InteractiveMarkerControl::moveAxis
void moveAxis(const Ogre::Ray &mouse_ray, const ViewportMouseEvent &event)
Definition: interactive_marker_control.cpp:665
rviz::InteractiveMarkerControl::always_visible_
bool always_visible_
Definition: interactive_marker_control.h:380
rviz::InteractiveMarkerControl::beginMouseMovement
void beginMouseMovement(ViewportMouseEvent &event, bool line_visible)
Definition: interactive_marker_control.cpp:1270
rviz::InteractiveMarkerControl::findClosestPoint
bool findClosestPoint(const Ogre::Ray &target_ray, const Ogre::Ray &mouse_ray, Ogre::Vector3 &closest_point)
Definition: interactive_marker_control.cpp:634
rviz::InteractiveMarkerControl::movePlane
void movePlane(Ogre::Ray &mouse_ray)
Definition: interactive_marker_control.cpp:575
rviz::InteractiveMarkerControl::makeMarkers
void makeMarkers(const visualization_msgs::InteractiveMarkerControl &message)
Create marker objects from the message and add them to the internal marker arrays.
Definition: interactive_marker_control.cpp:85
rviz::InteractiveMarkerControl::rotation_axis_
Ogre::Vector3 rotation_axis_
Definition: interactive_marker_control.h:458
rviz::InteractiveMarkerControl::interactiveMarkerPoseChanged
void interactiveMarkerPoseChanged(Ogre::Vector3 int_marker_position, Ogre::Quaternion int_marker_orientation)
Definition: interactive_marker_control.cpp:339
rviz::InteractiveMarkerControl::InteractiveMarkerControl
InteractiveMarkerControl(DisplayContext *context, Ogre::SceneNode *reference_node, InteractiveMarker *parent)
Constructor.
Definition: interactive_marker_control.cpp:63
rviz::InteractiveMarkerControl::mouse_dragging_
bool mouse_dragging_
Definition: interactive_marker_control.h:341
rviz::InteractiveMarkerControl::getMouseRayInReferenceFrame
Ogre::Ray getMouseRayInReferenceFrame(const ViewportMouseEvent &event, int x, int y)
Definition: interactive_marker_control.cpp:449
rviz
Definition: add_display_dialog.cpp:54
rviz::InteractiveObject
Abstract base class of things in the scene which handle mouse events.
Definition: interactive_object.h:48
rviz::InteractiveMarkerControl::mouse_y_at_drag_begin_
int mouse_y_at_drag_begin_
Definition: interactive_marker_control.h:429
rviz::InteractiveMarkerControl::control_orientation_
Ogre::Quaternion control_orientation_
Definition: interactive_marker_control.h:378
rviz::InteractiveMarkerControl::handleMouseMovement
void handleMouseMovement(ViewportMouseEvent &event)
Definition: interactive_marker_control.cpp:1350
rviz::InteractiveMarkerControl::getName
const std::string & getName()
Definition: interactive_marker_control.h:167
rviz::InteractiveMarkerControl::rotation_cursor_to_parent_at_grab_
Ogre::Quaternion rotation_cursor_to_parent_at_grab_
Definition: interactive_marker_control.h:422
rviz::InteractiveMarkerControl::HOVER_HIGHLIGHT
@ HOVER_HIGHLIGHT
Definition: interactive_marker_control.h:149
rviz::InteractiveMarkerControl
Definition: interactive_marker_control.h:68
ogre_vector.h
rviz::InteractiveMarkerControl::show_visual_aids_
bool show_visual_aids_
Definition: interactive_marker_control.h:481
rviz::InteractiveMarkerControl::ACTIVE_HIGHLIGHT
@ ACTIVE_HIGHLIGHT
Definition: interactive_marker_control.h:150
rviz::DisplayContext
Pure-virtual base class for objects which give Display subclasses context in which to work.
Definition: display_context.h:81
rviz::InteractiveMarkerControl::intersectYzPlane
bool intersectYzPlane(const Ogre::Ray &mouse_ray, Ogre::Vector3 &intersection_3d, Ogre::Vector2 &intersection_2d, float &ray_t)
compute intersection between mouse ray and y-z plane given in local coordinates
Definition: interactive_marker_control.cpp:1416
rviz::InteractiveMarkerControl::parent_position_at_mouse_down_
Ogre::Vector3 parent_position_at_mouse_down_
Definition: interactive_marker_control.h:445
rviz::InteractiveMarkerControl::moveRotate3D
void moveRotate3D(const Ogre::Vector3 &cursor_position_in_reference_frame, const Ogre::Quaternion &cursor_orientation_in_reference_frame)
Definition: interactive_marker_control.cpp:929
rviz::InteractiveMarkerControl::rotateZRelative
void rotateZRelative(const ViewportMouseEvent &event)
Definition: interactive_marker_control.cpp:507
rviz::InteractiveMarkerControl::grab_orientation_in_reference_frame_
Ogre::Quaternion grab_orientation_in_reference_frame_
Definition: interactive_marker_control.h:414
rviz::InteractiveMarkerControl::description_
QString description_
Definition: interactive_marker_control.h:382
rviz::InteractiveMarkerControl::getVisible
bool getVisible()
Definition: interactive_marker_control.cpp:297
rviz::InteractiveMarkerControl::rotation_at_mouse_down_
Ogre::Radian rotation_at_mouse_down_
Definition: interactive_marker_control.h:406
rviz::InteractiveMarkerControl::interaction_enabled_
bool interaction_enabled_
Definition: interactive_marker_control.h:469
rviz::InteractiveMarkerControl::processMessage
void processMessage(const visualization_msgs::InteractiveMarkerControl &message)
Set up or update the contents of this control to match the specification in the message.
Definition: interactive_marker_control.cpp:138
rviz::InteractiveMarkerControl::NO_HIGHLIGHT
@ NO_HIGHLIGHT
Definition: interactive_marker_control.h:148
rviz::InteractiveMarkerControl::isInteractive
bool isInteractive() override
Definition: interactive_marker_control.h:133
rviz::InteractiveMarkerControl::setHighlight
void setHighlight(const ControlHighlight &hl)
Definition: interactive_marker_control.cpp:964
rviz::InteractiveMarkerControl::closestPointOnLineToPoint
Ogre::Vector3 closestPointOnLineToPoint(const Ogre::Vector3 &line_start, const Ogre::Vector3 &line_dir, const Ogre::Vector3 &test_point)
Definition: interactive_marker_control.cpp:375
rviz::InteractiveMarkerControl::mouse_x_at_drag_begin_
int mouse_x_at_drag_begin_
Definition: interactive_marker_control.h:428
rviz::InteractiveMarkerControl::preFindVisibleObjects
void preFindVisibleObjects(Ogre::SceneManager *source, Ogre::SceneManager::IlluminationRenderStage irs, Ogre::Viewport *v) override
Definition: interactive_marker_control.cpp:264
rviz::InteractiveMarkerControl::~InteractiveMarkerControl
~InteractiveMarkerControl() override
Definition: interactive_marker_control.cpp:127
rviz::InteractiveMarkerControl::stopDragging
void stopDragging(bool force=false)
Definition: interactive_marker_control.cpp:995
rviz::InteractiveMarkerControl::intersectSomeYzPlane
bool intersectSomeYzPlane(const Ogre::Ray &mouse_ray, const Ogre::Vector3 &point_in_plane, const Ogre::Quaternion &plane_orientation, Ogre::Vector3 &intersection_3d, Ogre::Vector2 &intersection_2d, float &ray_t)
compute intersection between mouse ray and a y-z plane.
Definition: interactive_marker_control.cpp:1426
rviz::InteractiveMarkerControl::rotation_
Ogre::Radian rotation_
Definition: interactive_marker_control.h:401
rviz::InteractiveMarkerControl::independent_marker_orientation_
bool independent_marker_orientation_
Definition: interactive_marker_control.h:372
rviz::InteractiveMarkerControl::control_frame_orientation_at_mouse_down_
Ogre::Quaternion control_frame_orientation_at_mouse_down_
Definition: interactive_marker_control.h:449
rviz::InteractiveMarkerControl::ControlHighlight
ControlHighlight
Definition: interactive_marker_control.h:146
marker_base.h
rviz::InteractiveMarkerControl::visible_
bool visible_
Definition: interactive_marker_control.h:471
rviz::InteractiveMarkerControl::rotate
void rotate(Ogre::Ray &mouse_ray)
Definition: interactive_marker_control.cpp:393
rviz::InteractiveMarkerControl::has_focus_
bool has_focus_
Definition: interactive_marker_control.h:468
rviz::InteractiveMarkerControl::handle3DCursorEvent
virtual void handle3DCursorEvent(ViewportMouseEvent event, const Ogre::Vector3 &cursor_3D_pos, const Ogre::Quaternion &cursor_3D_orientation)
Definition: interactive_marker_control.cpp:1011
rviz::InteractiveMarker
Definition: interactive_marker.h:69
rviz::InteractiveMarkerControl::PointsMarkerPtr
boost::shared_ptr< PointsMarker > PointsMarkerPtr
Definition: interactive_marker_control.h:396
rviz::InteractiveMarkerControl::drag_viewport_
Ogre::Viewport * drag_viewport_
Definition: interactive_marker_control.h:342
rviz::InteractiveMarkerControl::setVisible
void setVisible(bool visible)
Definition: interactive_marker_control.cpp:302
rviz::InteractiveMarkerControl::mouse_relative_to_absolute_x_
int mouse_relative_to_absolute_x_
Definition: interactive_marker_control.h:438
rviz::InteractiveMarkerControl::parent_to_grab_position_
Ogre::Vector3 parent_to_grab_position_
Definition: interactive_marker_control.h:442
rviz::InteractiveMarkerControl::handleMouseEvent
void handleMouseEvent(ViewportMouseEvent &event) override
Definition: interactive_marker_control.cpp:1158
rviz::InteractiveMarkerControl::grab_point_rel_control_
Ogre::Vector3 grab_point_rel_control_
Definition: interactive_marker_control.h:466
rviz::InteractiveMarkerControl::context_
DisplayContext * context_
Definition: interactive_marker_control.h:346
rviz::InteractiveMarkerControl::mouse_z_scale_
double mouse_z_scale_
Definition: interactive_marker_control.h:435
rviz::InteractiveMarkerControl::control_frame_node_
Ogre::SceneNode * control_frame_node_
Definition: interactive_marker_control.h:360
rviz::InteractiveMarkerControl::moveZAxisRelative
void moveZAxisRelative(const ViewportMouseEvent &event)
Definition: interactive_marker_control.cpp:526
rviz::InteractiveMarkerControl::mouse_relative_to_absolute_y_
int mouse_relative_to_absolute_y_
Definition: interactive_marker_control.h:439
rviz::InteractiveMarkerControl::orientation_mode_
int orientation_mode_
Definition: interactive_marker_control.h:367
rviz::InteractiveMarkerControl::updateControlOrientationForViewFacing
void updateControlOrientationForViewFacing(Ogre::Viewport *v)
Definition: interactive_marker_control.cpp:271
rviz::InteractiveMarkerControl::getCursor
const QCursor & getCursor() const override
Definition: interactive_marker_control.h:336


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Sat Jun 1 2024 02:31:53