Class InteractiveMarkerControl

Inheritance Relationships

Base Types

  • public Ogre::SceneManager::Listener

  • public rviz_common::InteractiveObject

  • public std::enable_shared_from_this< InteractiveMarkerControl >

Class Documentation

class InteractiveMarkerControl : public Ogre::SceneManager::Listener, public rviz_common::InteractiveObject, public std::enable_shared_from_this<InteractiveMarkerControl>

A single control element of an InteractiveMarker.

Public Types

enum ControlHighlight

Highlight types.

Values:

enumerator NO_HIGHLIGHT
enumerator HOVER_HIGHLIGHT
enumerator ACTIVE_HIGHLIGHT
using SharedPtr = std::shared_ptr<InteractiveMarkerControl>

Public Functions

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

Constructor.

Creates Ogre::SceneNodes and sets some defaults. To make it look like a visualization_msgs::msg::InteractiveMarkerControl message, call processMessage().

virtual ~InteractiveMarkerControl()
void processMessage(const visualization_msgs::msg::InteractiveMarkerControl &message)

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

virtual void enableInteraction(bool enable)

Called when interactive mode is globally switched on/off.

virtual void handleMouseEvent(rviz_common::ViewportMouseEvent &event)

Receives all mouse events while the handler has focus.

virtual void handle3DCursorEvent(rviz_common::ViewportMouseEvent event, const Ogre::Vector3 &cursor_pos, const Ogre::Quaternion &cursor_orientation)

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

The rviz_common::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:

rviz_common::ViewportMouseEvent event;
event.panel = context_->getViewManager()->getRenderPanel();
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:
  • event – A struct holding certain event data (see description above).

  • cursor_pos – The world-relative position of the 3D cursor.

  • cursor_orientation – The world-relative orientation of the 3D cursor.

void 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 moves, it calls this function on all its child controls.

inline bool isInteractive()
void update()

Called every frame by parent’s update() function.

void setVisible(bool visible)
bool getVisible()
void setHighlight(const ControlHighlight &hl)

Public access to highlight controls.

inline InteractiveMarker *getParent()
Returns:

Pointer to the parent InteractiveMarker.

inline const std::string &getName()
Returns:

The name of this control.

inline const QString &getDescription()
Returns:

The description for this control.

inline int getInteractionMode()
Returns:

The visualization_msgs::msg::InteractiveMarkerControl interaction_mode for this control.

inline int getOrientationMode()
Returns:

The visualization_msgs::msg::InteractiveMarkerControl orientation_mode for this control.

inline void setShowVisualAids(bool show)
Parameters:

show – If true, will show some geometric helpers while dragging.

Protected Functions

virtual void preFindVisibleObjects(Ogre::SceneManager *source, Ogre::SceneManager::IlluminationRenderStage irs, Ogre::Viewport *v)

When this is called, we will face the camera.

void updateControlOrientationForViewFacing(Ogre::Viewport *v)
Ogre::Ray getMouseRayInReferenceFrame(const rviz_common::ViewportMouseEvent &event, int x, int y)

Calculate a mouse ray in the reference frame.

A mouse ray is a ray starting at the camera and pointing towards the mouse position.

void beginRelativeMouseMotion(const rviz_common::ViewportMouseEvent &event)

Begin a relative-motion drag.

bool getRelativeMouseMotion(const rviz_common::ViewportMouseEvent &event, int &dx, int &dy)

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

void rotateXYRelative(const rviz_common::ViewportMouseEvent &event)

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

void rotateZRelative(const rviz_common::ViewportMouseEvent &event)

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

void moveZAxisRelative(const rviz_common::ViewportMouseEvent &event)

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

void moveZAxisWheel(const rviz_common::ViewportMouseEvent &event)

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

void moveViewPlane(Ogre::Ray &mouse_ray, const rviz_common::ViewportMouseEvent &event)

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

void rotate(Ogre::Ray &mouse_ray)

Rotate the pose around the local X-axis, following the mouse movement.

void rotate(const Ogre::Vector3 &cursor_position_in_reference_frame)

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

void moveRotate(Ogre::Ray &mouse_ray)

Translate and rotate following the mouse movement.

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

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

Translate and rotate following the 3D cursor movement.

Rotate about, and translate perpendicular to, the local X-axis.

void movePlane(Ogre::Ray &mouse_ray)

Translate in the plane perpendicular to the local X-axis, following the mouse movement.

mouse_ray is relative to the reference frame.

void movePlane(const Ogre::Vector3 &cursor_position_in_reference_frame)

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

void moveAxis(const Ogre::Ray &mouse_ray, const rviz_common::ViewportMouseEvent &event)

Translate along the local X-axis, following the mouse movement.

mouse_ray is relative to the reference frame.

void moveAxis(const Ogre::Vector3 &cursor_position_in_reference_frame)

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

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

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

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

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

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

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

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.

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.

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

Find the closest point on target_ray to mouse_ray.

Parameters:

closest_point[out] Contains result point on target_ray if rays are not effectively parallel.

Returns:

false if rays are effectively parallel, true otherwise.

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

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

Parameters:

screen_pos[out] the resultant screen position, in pixels.

void addHighlightPass(markers::S_MaterialPtr materials)

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

void setHighlight(float a)
void recordDraggingInPlaceEvent(rviz_common::ViewportMouseEvent &event)

Save a copy of the latest mouse event with the event type set to QEvent::MouseMove, so that update() can resend the mouse event during drag actions to maintain consistent behavior.

void beginMouseMovement(rviz_common::ViewportMouseEvent &event, bool line_visible)

Begin a new mouse motion.

Called when left button is pressed to begin a drag.

void handleMouseMovement(rviz_common::ViewportMouseEvent &event)

Motion part of mouse event handling.

void handleMouseWheelMovement(rviz_common::ViewportMouseEvent &event)

Mouse wheel part of mouse event handling.

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

Return closest point on a line to a test point.

void makeMarkers(const visualization_msgs::msg::InteractiveMarkerControl &message)

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

void stopDragging(bool force = false)
inline virtual const QCursor &getCursor() const

Protected Attributes

bool mouse_dragging_
Ogre::Viewport *drag_viewport_
std::shared_ptr<rviz_common::ViewportMouseEvent> dragging_in_place_event_
rviz_common::DisplayContext *context_
rviz_common::interaction::CollObjectHandle coll_object_handle_
Ogre::SceneNode *reference_node_

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

Ogre::SceneNode *control_frame_node_

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.

Ogre::SceneNode *markers_node_

This is a child of scene_node, but might be oriented differently.

int interaction_mode_
int orientation_mode_
bool independent_marker_orientation_

If in view facing mode, the markers should be view facing as well. If set to false, they will follow the parent’s transformations.

Ogre::Quaternion control_orientation_

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.

bool always_visible_
QString description_
std::string name_
std::vector<markers::MarkerBase::SharedPtr> markers_
InteractiveMarker *parent_
std::set<Ogre::Pass*> highlight_passes_
std::vector<markers::PointsMarker::SharedPtr> points_markers_

PointsMarkers are rendered by special shader programs, so the regular highlighting method does not work for them. Keep a vector of them so we can call their setHighlightColor() function.

Ogre::Radian rotation_

Stores the rotation around the x axis of the control.

Only relevant for fixed-orientation rotation controls.

Ogre::Radian rotation_at_mouse_down_

Stores the rotation around the x axis of the control when the mouse-down event happened.

Only relevant for fixed-orientation rotation controls.

Ogre::Vector3 grab_point_in_reference_frame_

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

Ogre::Quaternion grab_orientation_in_reference_frame_

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

Ogre::Vector3 parent_to_cursor_in_cursor_frame_at_grab_

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

Ogre::Quaternion rotation_cursor_to_parent_at_grab_

Records the rotation of the parent from the cursor frame when the ‘grab’ button is pressed.

Qt::KeyboardModifiers modifiers_at_drag_begin_

The modifier state when drag begins.

int mouse_x_at_drag_begin_

X-position of the mouse when drag begins.

int mouse_y_at_drag_begin_

Y-position of the mouse when drag begins.

Ogre::Ray mouse_ray_at_drag_begin_

Mouse ray when drag begins.

double mouse_z_scale_

How far to move in Z when the mouse moves 1 pixel.

int mouse_relative_to_absolute_x_

X-offset of the absolute mouse position from the relative mouse position.

int mouse_relative_to_absolute_y_

Y-offset of the absolute mouse position from the relative mouse position.

Ogre::Vector3 parent_position_at_mouse_down_

Position of grab relative to parent in world coordinates.

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

Ogre::Quaternion control_frame_orientation_at_mouse_down_

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

Ogre::Quaternion parent_orientation_at_mouse_down_

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

Ogre::Vector3 rotation_axis_

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

Ogre::Vector3 rotation_center_rel_control_

The center of rotation during a mouse drag, relative to the control frame.

Computed on mouse down event.

Ogre::Vector3 grab_point_rel_control_

The grab point during a mouse drag, relative to the control frame.

Computed on mouse down event.

bool has_focus_
bool interaction_enabled_
bool visible_
bool view_facing_
QCursor cursor_
QString status_msg_
bool mouse_down_
bool show_visual_aids_
std::shared_ptr<rviz_rendering::Line> line_