#include <interactive_marker_control.h>
Public Types | |
enum | ControlHighlight { NO_HIGHLIGHT = 0, HOVER_HIGHLIGHT = 3, ACTIVE_HIGHLIGHT = 5 } |
Public Member Functions | |
virtual void | enableInteraction (bool enable) |
const QString & | getDescription () |
int | getInteractionMode () |
const std::string & | getName () |
int | getOrientationMode () |
InteractiveMarker * | getParent () |
bool | getVisible () |
virtual void | handle3DCursorEvent (ViewportMouseEvent event, const Ogre::Vector3 &cursor_3D_pos, const Ogre::Quaternion &cursor_3D_orientation) |
virtual void | handleMouseEvent (ViewportMouseEvent &event) |
InteractiveMarkerControl (DisplayContext *context, Ogre::SceneNode *reference_node, InteractiveMarker *parent) | |
Constructor. | |
void | interactiveMarkerPoseChanged (Ogre::Vector3 int_marker_position, Ogre::Quaternion int_marker_orientation) |
bool | isInteractive () |
void | processMessage (const visualization_msgs::InteractiveMarkerControl &message) |
Set up or update the contents of this control to match the specification in the message. | |
void | setHighlight (const ControlHighlight &hl) |
void | setShowVisualAids (bool show) |
If true, will show some geometric helpers while dragging. | |
void | setVisible (bool visible) |
void | update () |
virtual | ~InteractiveMarkerControl () |
Protected Types | |
typedef boost::shared_ptr < MarkerBase > | MarkerBasePtr |
typedef boost::shared_ptr < PointsMarker > | PointsMarkerPtr |
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 | |
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) |
virtual const QCursor & | getCursor () const |
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. | |
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 | |
void | makeMarkers (const visualization_msgs::InteractiveMarkerControl &message) |
Create marker objects from the message and add them to the internal marker arrays. | |
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) |
virtual void | preFindVisibleObjects (Ogre::SceneManager *source, Ogre::SceneManager::IlluminationRenderStage irs, Ogre::Viewport *v) |
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_ |
DisplayContext * | context_ |
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< Line > | line_ |
std::vector< MarkerBasePtr > | markers_ |
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_ |
InteractiveMarker * | parent_ |
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< PointsMarkerPtr > | points_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_ |
A single control element of an InteractiveMarker.
Definition at line 66 of file interactive_marker_control.h.
typedef boost::shared_ptr<MarkerBase> rviz::InteractiveMarkerControl::MarkerBasePtr [protected] |
Definition at line 352 of file interactive_marker_control.h.
typedef boost::shared_ptr<PointsMarker> rviz::InteractiveMarkerControl::PointsMarkerPtr [protected] |
Definition at line 362 of file interactive_marker_control.h.
Definition at line 138 of file interactive_marker_control.h.
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 71 of file interactive_marker_control.cpp.
Definition at line 184 of file interactive_marker_control.cpp.
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 1486 of file interactive_marker_control.cpp.
void rviz::InteractiveMarkerControl::beginMouseMovement | ( | ViewportMouseEvent & | event, |
bool | line_visible | ||
) | [protected] |
Definition at line 1290 of file interactive_marker_control.cpp.
void rviz::InteractiveMarkerControl::beginRelativeMouseMotion | ( | const ViewportMouseEvent & | event | ) | [protected] |
begin a relative-motion drag.
Definition at line 517 of file interactive_marker_control.cpp.
Ogre::Vector3 rviz::InteractiveMarkerControl::closestPointOnLineToPoint | ( | const Ogre::Vector3 & | line_start, |
const Ogre::Vector3 & | line_dir, | ||
const Ogre::Vector3 & | test_point | ||
) | [protected] |
Definition at line 427 of file interactive_marker_control.cpp.
void rviz::InteractiveMarkerControl::enableInteraction | ( | bool | enable | ) | [virtual] |
Implements rviz::InteractiveObject.
Definition at line 376 of file interactive_marker_control.cpp.
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.
closest_point | contains result point on target_ray if rays are not effectively parallel. |
Find the closest point on target_ray to mouse_ray.
Definition at line 693 of file interactive_marker_control.cpp.
virtual const QCursor& rviz::InteractiveMarkerControl::getCursor | ( | ) | const [inline, protected, virtual] |
Implements rviz::InteractiveObject.
Definition at line 305 of file interactive_marker_control.h.
const QString& rviz::InteractiveMarkerControl::getDescription | ( | ) | [inline] |
Definition at line 158 of file interactive_marker_control.h.
int rviz::InteractiveMarkerControl::getInteractionMode | ( | ) | [inline] |
Definition at line 163 of file interactive_marker_control.h.
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 502 of file interactive_marker_control.cpp.
const std::string& rviz::InteractiveMarkerControl::getName | ( | ) | [inline] |
Definition at line 153 of file interactive_marker_control.h.
int rviz::InteractiveMarkerControl::getOrientationMode | ( | ) | [inline] |
Definition at line 168 of file interactive_marker_control.h.
InteractiveMarker* rviz::InteractiveMarkerControl::getParent | ( | ) | [inline] |
Definition at line 148 of file interactive_marker_control.h.
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 529 of file interactive_marker_control.cpp.
Definition at line 350 of file interactive_marker_control.cpp.
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.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.
event | A struct holding certain event data (see description above). |
cursor_pos | The world-relative position of the 3D cursor. |
cursor_rot | The world-relative orientation of the 3D cursor. |
control_name | The name of the child InteractiveMarkerControl calling this function. |
Definition at line 1039 of file interactive_marker_control.cpp.
void rviz::InteractiveMarkerControl::handleMouseEvent | ( | ViewportMouseEvent & | event | ) | [virtual] |
Implements rviz::InteractiveObject.
Definition at line 1180 of file interactive_marker_control.cpp.
void rviz::InteractiveMarkerControl::handleMouseMovement | ( | ViewportMouseEvent & | event | ) | [protected] |
Definition at line 1378 of file interactive_marker_control.cpp.
void rviz::InteractiveMarkerControl::handleMouseWheelMovement | ( | ViewportMouseEvent & | event | ) | [protected] |
Definition at line 1431 of file interactive_marker_control.cpp.
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 391 of file interactive_marker_control.cpp.
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 1456 of file interactive_marker_control.cpp.
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 1445 of file interactive_marker_control.cpp.
bool rviz::InteractiveMarkerControl::isInteractive | ( | ) | [inline, virtual] |
Implements rviz::InteractiveObject.
Definition at line 128 of file interactive_marker_control.h.
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 93 of file interactive_marker_control.cpp.
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 914 of file interactive_marker_control.cpp.
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 724 of file interactive_marker_control.cpp.
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 770 of file interactive_marker_control.cpp.
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 636 of file interactive_marker_control.cpp.
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 655 of file interactive_marker_control.cpp.
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 781 of file interactive_marker_control.cpp.
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 847 of file interactive_marker_control.cpp.
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 969 of file interactive_marker_control.cpp.
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 618 of file interactive_marker_control.cpp.
void rviz::InteractiveMarkerControl::moveZAxisRelative | ( | const ViewportMouseEvent & | event | ) | [protected] |
Move the pose along the mouse ray, based on relative mouse movement.
Definition at line 582 of file interactive_marker_control.cpp.
void rviz::InteractiveMarkerControl::moveZAxisWheel | ( | const ViewportMouseEvent & | event | ) | [protected] |
Move the pose along the mouse ray, based on mouse wheel movement.
Definition at line 603 of file interactive_marker_control.cpp.
void rviz::InteractiveMarkerControl::preFindVisibleObjects | ( | Ogre::SceneManager * | source, |
Ogre::SceneManager::IlluminationRenderStage | irs, | ||
Ogre::Viewport * | v | ||
) | [protected, virtual] |
Definition at line 317 of file interactive_marker_control.cpp.
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 195 of file interactive_marker_control.cpp.
void rviz::InteractiveMarkerControl::recordDraggingInPlaceEvent | ( | ViewportMouseEvent & | event | ) | [protected] |
Definition at line 1017 of file interactive_marker_control.cpp.
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 445 of file interactive_marker_control.cpp.
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 468 of file interactive_marker_control.cpp.
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 941 of file interactive_marker_control.cpp.
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 541 of file interactive_marker_control.cpp.
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 561 of file interactive_marker_control.cpp.
void rviz::InteractiveMarkerControl::setHighlight | ( | const ControlHighlight & | hl | ) |
Definition at line 996 of file interactive_marker_control.cpp.
void rviz::InteractiveMarkerControl::setHighlight | ( | float | a | ) | [protected] |
Definition at line 1002 of file interactive_marker_control.cpp.
void rviz::InteractiveMarkerControl::setShowVisualAids | ( | bool | show | ) | [inline] |
If true, will show some geometric helpers while dragging.
Definition at line 173 of file interactive_marker_control.h.
void rviz::InteractiveMarkerControl::setVisible | ( | bool | visible | ) |
Definition at line 355 of file interactive_marker_control.cpp.
void rviz::InteractiveMarkerControl::stopDragging | ( | bool | force = false | ) | [protected] |
Definition at line 1023 of file interactive_marker_control.cpp.
Definition at line 368 of file interactive_marker_control.cpp.
void rviz::InteractiveMarkerControl::updateControlOrientationForViewFacing | ( | Ogre::Viewport * | v | ) | [protected] |
Definition at line 324 of file interactive_marker_control.cpp.
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.
screen_pos | the resultant screen position, in pixels. |
Project a world position onto the viewport to find screen coordinates in pixels.
screen_pos | the resultant screen position, in pixels. |
Definition at line 674 of file interactive_marker_control.cpp.
bool rviz::InteractiveMarkerControl::always_visible_ [protected] |
Definition at line 346 of file interactive_marker_control.h.
Definition at line 314 of file interactive_marker_control.h.
DisplayContext* rviz::InteractiveMarkerControl::context_ [protected] |
Definition at line 312 of file interactive_marker_control.h.
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 326 of file interactive_marker_control.h.
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 415 of file interactive_marker_control.h.
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 344 of file interactive_marker_control.h.
QCursor rviz::InteractiveMarkerControl::cursor_ [protected] |
Definition at line 440 of file interactive_marker_control.h.
QString rviz::InteractiveMarkerControl::description_ [protected] |
Definition at line 348 of file interactive_marker_control.h.
Ogre::Viewport* rviz::InteractiveMarkerControl::drag_viewport_ [protected] |
Definition at line 308 of file interactive_marker_control.h.
Definition at line 310 of file interactive_marker_control.h.
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 380 of file interactive_marker_control.h.
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 376 of file interactive_marker_control.h.
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 432 of file interactive_marker_control.h.
bool rviz::InteractiveMarkerControl::has_focus_ [protected] |
Definition at line 434 of file interactive_marker_control.h.
std::set<Ogre::Pass*> rviz::InteractiveMarkerControl::highlight_passes_ [protected] |
Definition at line 357 of file interactive_marker_control.h.
bool rviz::InteractiveMarkerControl::independent_marker_orientation_ [protected] |
Definition at line 338 of file interactive_marker_control.h.
bool rviz::InteractiveMarkerControl::interaction_enabled_ [protected] |
Definition at line 435 of file interactive_marker_control.h.
int rviz::InteractiveMarkerControl::interaction_mode_ [protected] |
Definition at line 332 of file interactive_marker_control.h.
boost::shared_ptr<Line> rviz::InteractiveMarkerControl::line_ [protected] |
Definition at line 445 of file interactive_marker_control.h.
std::vector< MarkerBasePtr > rviz::InteractiveMarkerControl::markers_ [protected] |
Definition at line 353 of file interactive_marker_control.h.
Ogre::SceneNode* rviz::InteractiveMarkerControl::markers_node_ [protected] |
Definition at line 329 of file interactive_marker_control.h.
Qt::KeyboardModifiers rviz::InteractiveMarkerControl::modifiers_at_drag_begin_ [protected] |
The modifier state when drag begins.
Definition at line 391 of file interactive_marker_control.h.
bool rviz::InteractiveMarkerControl::mouse_down_ [protected] |
Definition at line 443 of file interactive_marker_control.h.
bool rviz::InteractiveMarkerControl::mouse_dragging_ [protected] |
Definition at line 307 of file interactive_marker_control.h.
Ogre::Ray rviz::InteractiveMarkerControl::mouse_ray_at_drag_begin_ [protected] |
Definition at line 398 of file interactive_marker_control.h.
int rviz::InteractiveMarkerControl::mouse_relative_to_absolute_x_ [protected] |
offset of the absolute mouse position from the relative mouse position
Definition at line 404 of file interactive_marker_control.h.
int rviz::InteractiveMarkerControl::mouse_relative_to_absolute_y_ [protected] |
Definition at line 405 of file interactive_marker_control.h.
int rviz::InteractiveMarkerControl::mouse_x_at_drag_begin_ [protected] |
position of mouse when drag begins.
Definition at line 394 of file interactive_marker_control.h.
int rviz::InteractiveMarkerControl::mouse_y_at_drag_begin_ [protected] |
Definition at line 395 of file interactive_marker_control.h.
double rviz::InteractiveMarkerControl::mouse_z_scale_ [protected] |
Definition at line 401 of file interactive_marker_control.h.
std::string rviz::InteractiveMarkerControl::name_ [protected] |
Definition at line 350 of file interactive_marker_control.h.
int rviz::InteractiveMarkerControl::orientation_mode_ [protected] |
Definition at line 333 of file interactive_marker_control.h.
InteractiveMarker* rviz::InteractiveMarkerControl::parent_ [protected] |
Definition at line 355 of file interactive_marker_control.h.
Ogre::Quaternion rviz::InteractiveMarkerControl::parent_orientation_at_mouse_down_ [protected] |
The orientation of the parent when the mouse button is pressed.
Definition at line 419 of file interactive_marker_control.h.
Ogre::Vector3 rviz::InteractiveMarkerControl::parent_position_at_mouse_down_ [protected] |
The position of the parent when the mouse button is pressed.
Definition at line 411 of file interactive_marker_control.h.
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 384 of file interactive_marker_control.h.
Ogre::Vector3 rviz::InteractiveMarkerControl::parent_to_grab_position_ [protected] |
position of grab relative to parent in world coordinates.
Definition at line 408 of file interactive_marker_control.h.
std::vector< PointsMarkerPtr > rviz::InteractiveMarkerControl::points_markers_ [protected] |
Definition at line 363 of file interactive_marker_control.h.
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 318 of file interactive_marker_control.h.
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 367 of file interactive_marker_control.h.
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 372 of file interactive_marker_control.h.
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 424 of file interactive_marker_control.h.
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 428 of file interactive_marker_control.h.
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 388 of file interactive_marker_control.h.
bool rviz::InteractiveMarkerControl::show_visual_aids_ [protected] |
Definition at line 447 of file interactive_marker_control.h.
QString rviz::InteractiveMarkerControl::status_msg_ [protected] |
Definition at line 441 of file interactive_marker_control.h.
bool rviz::InteractiveMarkerControl::view_facing_ [protected] |
Definition at line 438 of file interactive_marker_control.h.
bool rviz::InteractiveMarkerControl::visible_ [protected] |
Definition at line 437 of file interactive_marker_control.h.