Public Types | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
rviz::InteractiveMarkerControl Class Reference

#include <interactive_marker_control.h>

Inheritance diagram for rviz::InteractiveMarkerControl:
Inheritance graph
[legend]

Public Types

enum  ControlHighlight { NO_HIGHLIGHT = 0, HOVER_HIGHLIGHT = 3, ACTIVE_HIGHLIGHT = 5 }
 

Public Member Functions

void enableInteraction (bool enable) override
 
const QString & getDescription ()
 
int getInteractionMode ()
 
const std::string & getName ()
 
int getOrientationMode ()
 
InteractiveMarkergetParent ()
 
bool getVisible ()
 
virtual void handle3DCursorEvent (ViewportMouseEvent event, const Ogre::Vector3 &cursor_3D_pos, const Ogre::Quaternion &cursor_3D_orientation)
 
void handleMouseEvent (ViewportMouseEvent &event) override
 
 InteractiveMarkerControl (DisplayContext *context, Ogre::SceneNode *reference_node, InteractiveMarker *parent)
 Constructor. More...
 
void interactiveMarkerPoseChanged (Ogre::Vector3 int_marker_position, Ogre::Quaternion int_marker_orientation)
 
bool isInteractive () override
 
void processMessage (const visualization_msgs::InteractiveMarkerControl &message)
 Set up or update the contents of this control to match the specification in the message. More...
 
void setHighlight (const ControlHighlight &hl)
 
void setShowVisualAids (bool show)
 If true, will show some geometric helpers while dragging. More...
 
void setVisible (bool visible)
 
void update ()
 
 ~InteractiveMarkerControl () override
 
- Public Member Functions inherited from rviz::InteractiveObject
virtual ~InteractiveObject ()
 

Protected Types

typedef boost::shared_ptr< MarkerBaseMarkerBasePtr
 
typedef boost::shared_ptr< PointsMarkerPointsMarkerPtr
 

Protected Member Functions

void addHighlightPass (S_MaterialPtr materials)
 take all the materials, add a highlight pass and store a pointer to the pass for later use More...
 
void beginMouseMovement (ViewportMouseEvent &event, bool line_visible)
 
void beginRelativeMouseMotion (const ViewportMouseEvent &event)
 
Ogre::Vector3 closestPointOnLineToPoint (const Ogre::Vector3 &line_start, const Ogre::Vector3 &line_dir, const Ogre::Vector3 &test_point)
 
bool findClosestPoint (const Ogre::Ray &target_ray, const Ogre::Ray &mouse_ray, Ogre::Vector3 &closest_point)
 
const QCursor & getCursor () const override
 
Ogre::Ray getMouseRayInReferenceFrame (const ViewportMouseEvent &event, int x, int y)
 
bool getRelativeMouseMotion (const ViewportMouseEvent &event, int &dx, int &dy)
 
void handleMouseMovement (ViewportMouseEvent &event)
 
void handleMouseWheelMovement (ViewportMouseEvent &event)
 
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. More...
 
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 More...
 
void makeMarkers (const visualization_msgs::InteractiveMarkerControl &message)
 Create marker objects from the message and add them to the internal marker arrays. More...
 
void move3D (const Ogre::Vector3 &cursor_position_in_reference_frame, const Ogre::Quaternion &cursor_orientation_in_reference_frame)
 
void moveAxis (const Ogre::Ray &mouse_ray, const ViewportMouseEvent &event)
 
void moveAxis (const Ogre::Vector3 &cursor_position_in_reference_frame)
 
void movePlane (Ogre::Ray &mouse_ray)
 
void movePlane (const Ogre::Vector3 &cursor_position_in_reference_frame)
 
void moveRotate (Ogre::Ray &mouse_ray)
 
void moveRotate (const Ogre::Vector3 &cursor_position_in_reference_frame, bool lock_axis=true)
 
void moveRotate3D (const Ogre::Vector3 &cursor_position_in_reference_frame, const Ogre::Quaternion &cursor_orientation_in_reference_frame)
 
void moveViewPlane (Ogre::Ray &mouse_ray, const ViewportMouseEvent &event)
 
void moveZAxisRelative (const ViewportMouseEvent &event)
 
void moveZAxisWheel (const ViewportMouseEvent &event)
 
void preFindVisibleObjects (Ogre::SceneManager *source, Ogre::SceneManager::IlluminationRenderStage irs, Ogre::Viewport *v) override
 
void recordDraggingInPlaceEvent (ViewportMouseEvent &event)
 
void rotate (Ogre::Ray &mouse_ray)
 
void rotate (const Ogre::Vector3 &cursor_position_in_reference_frame)
 
void rotate3D (const Ogre::Vector3 &cursor_position_in_reference_frame, const Ogre::Quaternion &cursor_orientation_in_reference_frame)
 
void rotateXYRelative (const ViewportMouseEvent &event)
 
void rotateZRelative (const ViewportMouseEvent &event)
 
void setHighlight (float a)
 
void stopDragging (bool force=false)
 
void updateControlOrientationForViewFacing (Ogre::Viewport *v)
 
void worldToScreen (const Ogre::Vector3 &pos_rel_reference, const Ogre::Viewport *viewport, Ogre::Vector2 &screen_pos)
 

Protected Attributes

bool always_visible_
 
CollObjectHandle coll_object_handle_
 
DisplayContextcontext_
 
Ogre::SceneNode * control_frame_node_
 
Ogre::Quaternion control_frame_orientation_at_mouse_down_
 
Ogre::Quaternion control_orientation_
 
QCursor cursor_
 
QString description_
 
Ogre::Viewport * drag_viewport_
 
ViewportMouseEvent dragging_in_place_event_
 
Ogre::Quaternion grab_orientation_in_reference_frame_
 
Ogre::Vector3 grab_point_in_reference_frame_
 
Ogre::Vector3 grab_point_rel_control_
 
bool has_focus_
 
std::set< Ogre::Pass * > highlight_passes_
 
bool independent_marker_orientation_
 
bool interaction_enabled_
 
int interaction_mode_
 
boost::shared_ptr< Lineline_
 
std::vector< MarkerBasePtrmarkers_
 
Ogre::SceneNode * markers_node_
 
Qt::KeyboardModifiers modifiers_at_drag_begin_
 
bool mouse_down_
 
bool mouse_dragging_
 
Ogre::Ray mouse_ray_at_drag_begin_
 
int mouse_relative_to_absolute_x_
 
int mouse_relative_to_absolute_y_
 
int mouse_x_at_drag_begin_
 
int mouse_y_at_drag_begin_
 
double mouse_z_scale_
 
std::string name_
 
int orientation_mode_
 
InteractiveMarkerparent_
 
Ogre::Quaternion parent_orientation_at_mouse_down_
 
Ogre::Vector3 parent_position_at_mouse_down_
 
Ogre::Vector3 parent_to_cursor_in_cursor_frame_at_grab_
 
Ogre::Vector3 parent_to_grab_position_
 
std::vector< PointsMarkerPtrpoints_markers_
 
Ogre::SceneNode * reference_node_
 
Ogre::Radian rotation_
 
Ogre::Radian rotation_at_mouse_down_
 
Ogre::Vector3 rotation_axis_
 
Ogre::Vector3 rotation_center_rel_control_
 
Ogre::Quaternion rotation_cursor_to_parent_at_grab_
 
bool show_visual_aids_
 
QString status_msg_
 
bool view_facing_
 
bool visible_
 

Detailed Description

A single control element of an InteractiveMarker.

Definition at line 68 of file interactive_marker_control.h.

Member Typedef Documentation

◆ MarkerBasePtr

Definition at line 386 of file interactive_marker_control.h.

◆ PointsMarkerPtr

Definition at line 396 of file interactive_marker_control.h.

Member Enumeration Documentation

◆ ControlHighlight

Enumerator
NO_HIGHLIGHT 
HOVER_HIGHLIGHT 
ACTIVE_HIGHLIGHT 

Definition at line 146 of file interactive_marker_control.h.

Constructor & Destructor Documentation

◆ InteractiveMarkerControl()

rviz::InteractiveMarkerControl::InteractiveMarkerControl ( DisplayContext context,
Ogre::SceneNode *  reference_node,
InteractiveMarker parent 
)

Constructor.

Just creates Ogre::SceneNodes and sets some defaults. To actually make it look like a visualization_msgs::InteractiveMarkerControl message specifies, call processMessage().

Definition at line 63 of file interactive_marker_control.cpp.

◆ ~InteractiveMarkerControl()

rviz::InteractiveMarkerControl::~InteractiveMarkerControl ( )
override

Definition at line 127 of file interactive_marker_control.cpp.

Member Function Documentation

◆ addHighlightPass()

void rviz::InteractiveMarkerControl::addHighlightPass ( S_MaterialPtr  materials)
protected

take all the materials, add a highlight pass and store a pointer to the pass for later use

Definition at line 1457 of file interactive_marker_control.cpp.

◆ beginMouseMovement()

void rviz::InteractiveMarkerControl::beginMouseMovement ( ViewportMouseEvent event,
bool  line_visible 
)
protected

Definition at line 1270 of file interactive_marker_control.cpp.

◆ beginRelativeMouseMotion()

void rviz::InteractiveMarkerControl::beginRelativeMouseMotion ( const ViewportMouseEvent event)
protected

begin a relative-motion drag.

Definition at line 465 of file interactive_marker_control.cpp.

◆ closestPointOnLineToPoint()

Ogre::Vector3 rviz::InteractiveMarkerControl::closestPointOnLineToPoint ( const Ogre::Vector3 &  line_start,
const Ogre::Vector3 &  line_dir,
const Ogre::Vector3 &  test_point 
)
protected

Definition at line 375 of file interactive_marker_control.cpp.

◆ enableInteraction()

void rviz::InteractiveMarkerControl::enableInteraction ( bool  enable)
overridevirtual

Implements rviz::InteractiveObject.

Definition at line 324 of file interactive_marker_control.cpp.

◆ findClosestPoint()

bool rviz::InteractiveMarkerControl::findClosestPoint ( const Ogre::Ray &  target_ray,
const Ogre::Ray &  mouse_ray,
Ogre::Vector3 &  closest_point 
)
protected

Find the closest point on target_ray to mouse_ray.

Parameters
closest_pointcontains result point on target_ray if rays are not effectively parallel.
Returns
false if rays are effectively parallel, true otherwise.

Find the closest point on target_ray to mouse_ray.

Returns
false if rays are effectively parallel, true otherwise.

Definition at line 634 of file interactive_marker_control.cpp.

◆ getCursor()

const QCursor& rviz::InteractiveMarkerControl::getCursor ( ) const
inlineoverrideprotectedvirtual

Implements rviz::InteractiveObject.

Definition at line 336 of file interactive_marker_control.h.

◆ getDescription()

const QString& rviz::InteractiveMarkerControl::getDescription ( )
inline
Returns
the description for this control

Definition at line 175 of file interactive_marker_control.h.

◆ getInteractionMode()

int rviz::InteractiveMarkerControl::getInteractionMode ( )
inline
Returns
the visualization_msgs::InteractiveMarkerControl interaction_mode for this control

Definition at line 183 of file interactive_marker_control.h.

◆ getMouseRayInReferenceFrame()

Ogre::Ray rviz::InteractiveMarkerControl::getMouseRayInReferenceFrame ( const ViewportMouseEvent event,
int  x,
int  y 
)
protected

calculate a mouse ray in the reference frame. A mouse ray is a ray starting at the camera and pointing towards the mouse position.

Definition at line 449 of file interactive_marker_control.cpp.

◆ getName()

const std::string& rviz::InteractiveMarkerControl::getName ( )
inline
Returns
the name of this control

Definition at line 167 of file interactive_marker_control.h.

◆ getOrientationMode()

int rviz::InteractiveMarkerControl::getOrientationMode ( )
inline
Returns
the visualization_msgs::InteractiveMarkerControl orientation_mode for this control

Definition at line 191 of file interactive_marker_control.h.

◆ getParent()

InteractiveMarker* rviz::InteractiveMarkerControl::getParent ( )
inline
Returns
pointer to the parent InteractiveMarker

Definition at line 159 of file interactive_marker_control.h.

◆ getRelativeMouseMotion()

bool rviz::InteractiveMarkerControl::getRelativeMouseMotion ( const ViewportMouseEvent event,
int &  dx,
int &  dy 
)
protected

get the relative motion of the mouse, and put the mouse back where it was when beginRelativeMouseMotion() was called.

Definition at line 477 of file interactive_marker_control.cpp.

◆ getVisible()

bool rviz::InteractiveMarkerControl::getVisible ( )

Definition at line 297 of file interactive_marker_control.cpp.

◆ handle3DCursorEvent()

void rviz::InteractiveMarkerControl::handle3DCursorEvent ( ViewportMouseEvent  event,
const Ogre::Vector3 &  cursor_3D_pos,
const Ogre::Quaternion &  cursor_3D_orientation 
)
virtual

This is the main entry-point for interaction using a 3D cursor.

The ViewportMouseEvent struct is used to "fake" a mouse event. An event must have the panel, viewport, and type members filled in. The acting_button and buttons_down members can be specified as well, if appropriate. All other fields are currently ignored.

A sample construction of a "right-button mouse-up" event:

ViewportMouseEvent event;
event.viewport = context_->getViewManager()->getRenderPanel()->getRenderWindow()->getViewport(0);
event.type = QEvent::MouseButtonRelease;
event.acting_button = Qt::RightButton;
event.buttons_down = Qt::NoButton;

For more examples, see the implementation in the interaction_cursor_rviz package.

Parameters
eventA struct holding certain event data (see description above).
cursor_posThe world-relative position of the 3D cursor.
cursor_rotThe world-relative orientation of the 3D cursor.
control_nameThe name of the child InteractiveMarkerControl calling this function.

Definition at line 1011 of file interactive_marker_control.cpp.

◆ handleMouseEvent()

void rviz::InteractiveMarkerControl::handleMouseEvent ( ViewportMouseEvent event)
overridevirtual

Implements rviz::InteractiveObject.

Definition at line 1158 of file interactive_marker_control.cpp.

◆ handleMouseMovement()

void rviz::InteractiveMarkerControl::handleMouseMovement ( ViewportMouseEvent event)
protected

Definition at line 1350 of file interactive_marker_control.cpp.

◆ handleMouseWheelMovement()

void rviz::InteractiveMarkerControl::handleMouseWheelMovement ( ViewportMouseEvent event)
protected

Definition at line 1402 of file interactive_marker_control.cpp.

◆ interactiveMarkerPoseChanged()

void rviz::InteractiveMarkerControl::interactiveMarkerPoseChanged ( Ogre::Vector3  int_marker_position,
Ogre::Quaternion  int_marker_orientation 
)

Update the pose of the interactive marker being controlled, relative to the reference frame. Each InteractiveMarkerControl maintains its pose relative to the reference frame independently, so when the parent InteractiveMarker mvoes, it calls this function on all its child controls.

Definition at line 339 of file interactive_marker_control.cpp.

◆ intersectSomeYzPlane()

bool rviz::InteractiveMarkerControl::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 
)
protected

compute intersection between mouse ray and a y-z plane.

Definition at line 1426 of file interactive_marker_control.cpp.

◆ intersectYzPlane()

bool rviz::InteractiveMarkerControl::intersectYzPlane ( const Ogre::Ray &  mouse_ray,
Ogre::Vector3 &  intersection_3d,
Ogre::Vector2 &  intersection_2d,
float &  ray_t 
)
protected

compute intersection between mouse ray and y-z plane given in local coordinates

Definition at line 1416 of file interactive_marker_control.cpp.

◆ isInteractive()

bool rviz::InteractiveMarkerControl::isInteractive ( )
inlineoverridevirtual

Implements rviz::InteractiveObject.

Definition at line 133 of file interactive_marker_control.h.

◆ makeMarkers()

void rviz::InteractiveMarkerControl::makeMarkers ( const visualization_msgs::InteractiveMarkerControl &  message)
protected

Create marker objects from the message and add them to the internal marker arrays.

Definition at line 85 of file interactive_marker_control.cpp.

◆ move3D()

void rviz::InteractiveMarkerControl::move3D ( const Ogre::Vector3 &  cursor_position_in_reference_frame,
const Ogre::Quaternion &  cursor_orientation_in_reference_frame 
)
protected

Translate in 3-degrees-of-freedom, following the 3D cursor translation.

Definition at line 859 of file interactive_marker_control.cpp.

◆ moveAxis() [1/2]

void rviz::InteractiveMarkerControl::moveAxis ( const Ogre::Ray &  mouse_ray,
const ViewportMouseEvent event 
)
protected

Translate along the local X-axis, following the mouse movement. mouse_ray is relative to the reference frame.

Definition at line 665 of file interactive_marker_control.cpp.

◆ moveAxis() [2/2]

void rviz::InteractiveMarkerControl::moveAxis ( const Ogre::Vector3 &  cursor_position_in_reference_frame)
protected

Translate along the local X-axis, following the 3D cursor movement.

Definition at line 713 of file interactive_marker_control.cpp.

◆ movePlane() [1/2]

void rviz::InteractiveMarkerControl::movePlane ( Ogre::Ray &  mouse_ray)
protected

Translate in the plane perpendicular to the local X-axis, following the mouse movement. mouse_ray is relative to the reference frame.

Definition at line 575 of file interactive_marker_control.cpp.

◆ movePlane() [2/2]

void rviz::InteractiveMarkerControl::movePlane ( const Ogre::Vector3 &  cursor_position_in_reference_frame)
protected

Translate in the plane perpendicular to the local X-axis, following the 3D cursor movement.

Definition at line 595 of file interactive_marker_control.cpp.

◆ moveRotate() [1/2]

void rviz::InteractiveMarkerControl::moveRotate ( Ogre::Ray &  mouse_ray)
protected

Rotate about, and translate perpendicular to, the local X-axis, following the mouse movement. mouse_ray is relative to the reference frame.

Definition at line 727 of file interactive_marker_control.cpp.

◆ moveRotate() [2/2]

void rviz::InteractiveMarkerControl::moveRotate ( const Ogre::Vector3 &  cursor_position_in_reference_frame,
bool  lock_axis = true 
)
protected

Rotate about, and translate perpendicular to, the local X-axis, following the 3D cursor movement.

Definition at line 792 of file interactive_marker_control.cpp.

◆ moveRotate3D()

void rviz::InteractiveMarkerControl::moveRotate3D ( const Ogre::Vector3 &  cursor_position_in_reference_frame,
const Ogre::Quaternion &  cursor_orientation_in_reference_frame 
)
protected

Rotate and translate in full 6-DOF, following the 3D cursor movement.

Definition at line 929 of file interactive_marker_control.cpp.

◆ moveViewPlane()

void rviz::InteractiveMarkerControl::moveViewPlane ( Ogre::Ray &  mouse_ray,
const ViewportMouseEvent event 
)
protected

Move the pose around the XY view plane (perpendicular to the camera direction).

Definition at line 558 of file interactive_marker_control.cpp.

◆ moveZAxisRelative()

void rviz::InteractiveMarkerControl::moveZAxisRelative ( const ViewportMouseEvent event)
protected

Move the pose along the mouse ray, based on relative mouse movement.

Definition at line 526 of file interactive_marker_control.cpp.

◆ moveZAxisWheel()

void rviz::InteractiveMarkerControl::moveZAxisWheel ( const ViewportMouseEvent event)
protected

Move the pose along the mouse ray, based on mouse wheel movement.

Definition at line 545 of file interactive_marker_control.cpp.

◆ preFindVisibleObjects()

void rviz::InteractiveMarkerControl::preFindVisibleObjects ( Ogre::SceneManager *  source,
Ogre::SceneManager::IlluminationRenderStage  irs,
Ogre::Viewport *  v 
)
overrideprotected

Definition at line 264 of file interactive_marker_control.cpp.

◆ processMessage()

void rviz::InteractiveMarkerControl::processMessage ( const visualization_msgs::InteractiveMarkerControl &  message)

Set up or update the contents of this control to match the specification in the message.

Definition at line 138 of file interactive_marker_control.cpp.

◆ recordDraggingInPlaceEvent()

void rviz::InteractiveMarkerControl::recordDraggingInPlaceEvent ( ViewportMouseEvent event)
protected

Definition at line 989 of file interactive_marker_control.cpp.

◆ rotate() [1/2]

void rviz::InteractiveMarkerControl::rotate ( Ogre::Ray &  mouse_ray)
protected

Rotate the pose around the local X-axis, following the mouse movement. mouse_ray is relative to the reference frame.

Definition at line 393 of file interactive_marker_control.cpp.

◆ rotate() [2/2]

void rviz::InteractiveMarkerControl::rotate ( const Ogre::Vector3 &  cursor_position_in_reference_frame)
protected

Rotate the pose around the local X axis, following the 3D cursor movement.

Definition at line 415 of file interactive_marker_control.cpp.

◆ rotate3D()

void rviz::InteractiveMarkerControl::rotate3D ( const Ogre::Vector3 &  cursor_position_in_reference_frame,
const Ogre::Quaternion &  cursor_orientation_in_reference_frame 
)
protected

Rotate in 3-degrees-of-freedom, following the 3D cursor rotation.

Definition at line 893 of file interactive_marker_control.cpp.

◆ rotateXYRelative()

void rviz::InteractiveMarkerControl::rotateXYRelative ( const ViewportMouseEvent event)
protected

Rotate the pose around the camera-frame XY (right/up) axes, based on relative mouse movement.

Definition at line 489 of file interactive_marker_control.cpp.

◆ rotateZRelative()

void rviz::InteractiveMarkerControl::rotateZRelative ( const ViewportMouseEvent event)
protected

Rotate the pose around the camera-frame Z (look) axis, based on relative mouse movement.

Definition at line 507 of file interactive_marker_control.cpp.

◆ setHighlight() [1/2]

void rviz::InteractiveMarkerControl::setHighlight ( const ControlHighlight hl)

Definition at line 964 of file interactive_marker_control.cpp.

◆ setHighlight() [2/2]

void rviz::InteractiveMarkerControl::setHighlight ( float  a)
protected

Definition at line 974 of file interactive_marker_control.cpp.

◆ setShowVisualAids()

void rviz::InteractiveMarkerControl::setShowVisualAids ( bool  show)
inline

If true, will show some geometric helpers while dragging.

Definition at line 199 of file interactive_marker_control.h.

◆ setVisible()

void rviz::InteractiveMarkerControl::setVisible ( bool  visible)

Definition at line 302 of file interactive_marker_control.cpp.

◆ stopDragging()

void rviz::InteractiveMarkerControl::stopDragging ( bool  force = false)
protected

Definition at line 995 of file interactive_marker_control.cpp.

◆ update()

void rviz::InteractiveMarkerControl::update ( )

Definition at line 316 of file interactive_marker_control.cpp.

◆ updateControlOrientationForViewFacing()

void rviz::InteractiveMarkerControl::updateControlOrientationForViewFacing ( Ogre::Viewport *  v)
protected

Definition at line 271 of file interactive_marker_control.cpp.

◆ worldToScreen()

void rviz::InteractiveMarkerControl::worldToScreen ( const Ogre::Vector3 &  pos_rel_reference,
const Ogre::Viewport *  viewport,
Ogre::Vector2 &  screen_pos 
)
protected

Project a reference position onto the viewport to find screen coordinates in pixels.

Parameters
screen_posthe resultant screen position, in pixels.

Project a world position onto the viewport to find screen coordinates in pixels.

Parameters
screen_posthe resultant screen position, in pixels.

Definition at line 614 of file interactive_marker_control.cpp.

Member Data Documentation

◆ always_visible_

bool rviz::InteractiveMarkerControl::always_visible_
protected

Definition at line 380 of file interactive_marker_control.h.

◆ coll_object_handle_

CollObjectHandle rviz::InteractiveMarkerControl::coll_object_handle_
protected

Definition at line 348 of file interactive_marker_control.h.

◆ context_

DisplayContext* rviz::InteractiveMarkerControl::context_
protected

Definition at line 346 of file interactive_marker_control.h.

◆ control_frame_node_

Ogre::SceneNode* rviz::InteractiveMarkerControl::control_frame_node_
protected

Represents the local frame of this control relative to reference node/frame. There is no intermediate InteractiveMarker node or frame, each control keeps track of its pose relative to the reference frame independently. In INHERIT mode, this will have an identical pose as the rest of the interactive marker, otherwise its orientation might be different.

Definition at line 360 of file interactive_marker_control.h.

◆ control_frame_orientation_at_mouse_down_

Ogre::Quaternion rviz::InteractiveMarkerControl::control_frame_orientation_at_mouse_down_
protected

The orientation of the control_frame_node_ when the mouse button is pressed.

Definition at line 449 of file interactive_marker_control.h.

◆ control_orientation_

Ogre::Quaternion rviz::InteractiveMarkerControl::control_orientation_
protected

Defines the axis / plane along which to transform. This is not keeping track of rotations applied to the control by the user, this is just a copy of the "orientation" parameter from the InteractiveMarkerControl message.

Definition at line 378 of file interactive_marker_control.h.

◆ cursor_

QCursor rviz::InteractiveMarkerControl::cursor_
protected

Definition at line 474 of file interactive_marker_control.h.

◆ description_

QString rviz::InteractiveMarkerControl::description_
protected

Definition at line 382 of file interactive_marker_control.h.

◆ drag_viewport_

Ogre::Viewport* rviz::InteractiveMarkerControl::drag_viewport_
protected

Definition at line 342 of file interactive_marker_control.h.

◆ dragging_in_place_event_

ViewportMouseEvent rviz::InteractiveMarkerControl::dragging_in_place_event_
protected

Definition at line 344 of file interactive_marker_control.h.

◆ grab_orientation_in_reference_frame_

Ogre::Quaternion rviz::InteractiveMarkerControl::grab_orientation_in_reference_frame_
protected

The orientation of the cursor when the 'grab' button is pressed, relative to the reference frame.

Definition at line 414 of file interactive_marker_control.h.

◆ grab_point_in_reference_frame_

Ogre::Vector3 rviz::InteractiveMarkerControl::grab_point_in_reference_frame_
protected

The 3D position of the mouse click/cursor when the 'grab' button is pressed, relative to the reference frame.

Definition at line 410 of file interactive_marker_control.h.

◆ grab_point_rel_control_

Ogre::Vector3 rviz::InteractiveMarkerControl::grab_point_rel_control_
protected

The grab point during a mouse drag, relative to the control frame. Computed on mouse down event.

Definition at line 466 of file interactive_marker_control.h.

◆ has_focus_

bool rviz::InteractiveMarkerControl::has_focus_
protected

Definition at line 468 of file interactive_marker_control.h.

◆ highlight_passes_

std::set<Ogre::Pass*> rviz::InteractiveMarkerControl::highlight_passes_
protected

Definition at line 391 of file interactive_marker_control.h.

◆ independent_marker_orientation_

bool rviz::InteractiveMarkerControl::independent_marker_orientation_
protected

Definition at line 372 of file interactive_marker_control.h.

◆ interaction_enabled_

bool rviz::InteractiveMarkerControl::interaction_enabled_
protected

Definition at line 469 of file interactive_marker_control.h.

◆ interaction_mode_

int rviz::InteractiveMarkerControl::interaction_mode_
protected

Definition at line 366 of file interactive_marker_control.h.

◆ line_

boost::shared_ptr<Line> rviz::InteractiveMarkerControl::line_
protected

Definition at line 479 of file interactive_marker_control.h.

◆ markers_

std::vector<MarkerBasePtr> rviz::InteractiveMarkerControl::markers_
protected

Definition at line 387 of file interactive_marker_control.h.

◆ markers_node_

Ogre::SceneNode* rviz::InteractiveMarkerControl::markers_node_
protected

Definition at line 363 of file interactive_marker_control.h.

◆ modifiers_at_drag_begin_

Qt::KeyboardModifiers rviz::InteractiveMarkerControl::modifiers_at_drag_begin_
protected

The modifier state when drag begins.

Definition at line 425 of file interactive_marker_control.h.

◆ mouse_down_

bool rviz::InteractiveMarkerControl::mouse_down_
protected

Definition at line 477 of file interactive_marker_control.h.

◆ mouse_dragging_

bool rviz::InteractiveMarkerControl::mouse_dragging_
protected

Definition at line 341 of file interactive_marker_control.h.

◆ mouse_ray_at_drag_begin_

Ogre::Ray rviz::InteractiveMarkerControl::mouse_ray_at_drag_begin_
protected

Definition at line 432 of file interactive_marker_control.h.

◆ mouse_relative_to_absolute_x_

int rviz::InteractiveMarkerControl::mouse_relative_to_absolute_x_
protected

offset of the absolute mouse position from the relative mouse position

Definition at line 438 of file interactive_marker_control.h.

◆ mouse_relative_to_absolute_y_

int rviz::InteractiveMarkerControl::mouse_relative_to_absolute_y_
protected

Definition at line 439 of file interactive_marker_control.h.

◆ mouse_x_at_drag_begin_

int rviz::InteractiveMarkerControl::mouse_x_at_drag_begin_
protected

position of mouse when drag begins.

Definition at line 428 of file interactive_marker_control.h.

◆ mouse_y_at_drag_begin_

int rviz::InteractiveMarkerControl::mouse_y_at_drag_begin_
protected

Definition at line 429 of file interactive_marker_control.h.

◆ mouse_z_scale_

double rviz::InteractiveMarkerControl::mouse_z_scale_
protected

Definition at line 435 of file interactive_marker_control.h.

◆ name_

std::string rviz::InteractiveMarkerControl::name_
protected

Definition at line 384 of file interactive_marker_control.h.

◆ orientation_mode_

int rviz::InteractiveMarkerControl::orientation_mode_
protected

Definition at line 367 of file interactive_marker_control.h.

◆ parent_

InteractiveMarker* rviz::InteractiveMarkerControl::parent_
protected

Definition at line 389 of file interactive_marker_control.h.

◆ parent_orientation_at_mouse_down_

Ogre::Quaternion rviz::InteractiveMarkerControl::parent_orientation_at_mouse_down_
protected

The orientation of the parent when the mouse button is pressed.

Definition at line 453 of file interactive_marker_control.h.

◆ parent_position_at_mouse_down_

Ogre::Vector3 rviz::InteractiveMarkerControl::parent_position_at_mouse_down_
protected

The position of the parent when the mouse button is pressed.

Definition at line 445 of file interactive_marker_control.h.

◆ parent_to_cursor_in_cursor_frame_at_grab_

Ogre::Vector3 rviz::InteractiveMarkerControl::parent_to_cursor_in_cursor_frame_at_grab_
protected

Records the 3D position of the cursor relative to the parent marker, expressed in the cursor frame, when the 'grab' button is pressed.

Definition at line 418 of file interactive_marker_control.h.

◆ parent_to_grab_position_

Ogre::Vector3 rviz::InteractiveMarkerControl::parent_to_grab_position_
protected

position of grab relative to parent in world coordinates.

Definition at line 442 of file interactive_marker_control.h.

◆ points_markers_

std::vector<PointsMarkerPtr> rviz::InteractiveMarkerControl::points_markers_
protected

Definition at line 397 of file interactive_marker_control.h.

◆ reference_node_

Ogre::SceneNode* rviz::InteractiveMarkerControl::reference_node_
protected

Node representing reference frame in tf, like /map, /base_link, /head, etc. Same as the field in InteractiveMarker.

Definition at line 352 of file interactive_marker_control.h.

◆ rotation_

Ogre::Radian rviz::InteractiveMarkerControl::rotation_
protected

Stores the rotation around the x axis of the control. Only relevant for fixed-orientation rotation controls.

Definition at line 401 of file interactive_marker_control.h.

◆ rotation_at_mouse_down_

Ogre::Radian rviz::InteractiveMarkerControl::rotation_at_mouse_down_
protected

Stores the rotation around the x axis of the control as it was when the mouse-down event happened. Only relevant for fixed-orientation rotation controls.

Definition at line 406 of file interactive_marker_control.h.

◆ rotation_axis_

Ogre::Vector3 rviz::InteractiveMarkerControl::rotation_axis_
protected

The direction vector of the axis of rotation during a mouse drag, relative to the reference frame. Computed on mouse down event.

Definition at line 458 of file interactive_marker_control.h.

◆ rotation_center_rel_control_

Ogre::Vector3 rviz::InteractiveMarkerControl::rotation_center_rel_control_
protected

The center of rotation during a mouse drag, relative to the control frame. Computed on mouse down event.

Definition at line 462 of file interactive_marker_control.h.

◆ rotation_cursor_to_parent_at_grab_

Ogre::Quaternion rviz::InteractiveMarkerControl::rotation_cursor_to_parent_at_grab_
protected

Records the rotation of the parent from the cursor frame, when the 'grab' button is pressed.

Definition at line 422 of file interactive_marker_control.h.

◆ show_visual_aids_

bool rviz::InteractiveMarkerControl::show_visual_aids_
protected

Definition at line 481 of file interactive_marker_control.h.

◆ status_msg_

QString rviz::InteractiveMarkerControl::status_msg_
protected

Definition at line 475 of file interactive_marker_control.h.

◆ view_facing_

bool rviz::InteractiveMarkerControl::view_facing_
protected

Definition at line 472 of file interactive_marker_control.h.

◆ visible_

bool rviz::InteractiveMarkerControl::visible_
protected

Definition at line 471 of file interactive_marker_control.h.


The documentation for this class was generated from the following files:


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