Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes
rviz::InteractiveMarkerControl Class Reference

#include <interactive_marker_control.h>

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

List of all members.

Public Member Functions

virtual void enableInteraction (bool enable)
virtual void handleMouseEvent (ViewportMouseEvent &event)
void hideVisible ()
 InteractiveMarkerControl (VisualizationManager *vis_manager, 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 restoreVisible ()
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
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)
void handleMouseMovement (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 moveAxis (const Ogre::Ray &mouse_ray, const ViewportMouseEvent &event)
void movePlane (Ogre::Ray &mouse_ray)
void moveRotate (Ogre::Ray &mouse_ray)
virtual void preFindVisibleObjects (Ogre::SceneManager *source, Ogre::SceneManager::IlluminationRenderStage irs, Ogre::Viewport *v)
void recordDraggingInPlaceEvent (ViewportMouseEvent &event)
void rotate (Ogre::Ray &mouse_ray)
void setHighlight (float a)
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_
Ogre::SceneNode * control_frame_node_
Ogre::Quaternion control_frame_orientation_at_mouse_down_
Ogre::Quaternion control_orientation_
std::string description_
Ogre::Viewport * drag_viewport_
bool dragging_
ViewportMouseEvent dragging_in_place_event_
Ogre::Vector2 grab_pixel_
Ogre::Vector3 grab_point_
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_
std::vector< MarkerBasePtrmarkers_
Ogre::SceneNode * markers_node_
std::string name_
int orientation_mode_
InteractiveMarkerparent_
Ogre::Quaternion parent_orientation_at_mouse_down_
Ogre::Vector3 parent_position_at_mouse_down_
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_
bool saved_visibility_state_
bool view_facing_
VisualizationManagervis_manager_
bool visible_

Detailed Description

A single control element of an InteractiveMarker.

Definition at line 62 of file interactive_marker_control.h.


Member Typedef Documentation

typedef boost::shared_ptr<MarkerBase> rviz::InteractiveMarkerControl::MarkerBasePtr [protected]

Definition at line 223 of file interactive_marker_control.h.

typedef boost::shared_ptr<PointsMarker> rviz::InteractiveMarkerControl::PointsMarkerPtr [protected]

Definition at line 233 of file interactive_marker_control.h.


Constructor & Destructor Documentation

rviz::InteractiveMarkerControl::InteractiveMarkerControl ( VisualizationManager vis_manager,
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 62 of file interactive_marker_control.cpp.

Definition at line 158 of file interactive_marker_control.cpp.


Member Function Documentation

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

Definition at line 818 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 347 of file interactive_marker_control.cpp.

Implements rviz::InteractiveObject.

Definition at line 301 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.

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 447 of file interactive_marker_control.cpp.

Implements rviz::InteractiveObject.

Definition at line 616 of file interactive_marker_control.cpp.

Definition at line 734 of file interactive_marker_control.cpp.

Definition at line 269 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 311 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 788 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 777 of file interactive_marker_control.cpp.

Implements rviz::InteractiveObject.

Definition at line 97 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 80 of file interactive_marker_control.cpp.

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

Definition at line 478 of file interactive_marker_control.cpp.

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

Translate, following the mouse movement.

Definition at line 407 of file interactive_marker_control.cpp.

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

Rotate and translate to follow the mouse movement. mouse_ray is relative to the reference frame.

Definition at line 529 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 236 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 169 of file interactive_marker_control.cpp.

Definition at line 610 of file interactive_marker_control.cpp.

Definition at line 275 of file interactive_marker_control.cpp.

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

Rotate the pose, following the mouse movement. mouse_ray is relative to the reference frame.

Definition at line 365 of file interactive_marker_control.cpp.

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

Definition at line 595 of file interactive_marker_control.cpp.

Definition at line 280 of file interactive_marker_control.cpp.

Definition at line 293 of file interactive_marker_control.cpp.

Definition at line 243 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.

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 428 of file interactive_marker_control.cpp.


Member Data Documentation

Definition at line 217 of file interactive_marker_control.h.

Definition at line 185 of file interactive_marker_control.h.

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 197 of file interactive_marker_control.h.

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

Definition at line 256 of file interactive_marker_control.h.

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 215 of file interactive_marker_control.h.

Definition at line 219 of file interactive_marker_control.h.

Definition at line 179 of file interactive_marker_control.h.

Definition at line 178 of file interactive_marker_control.h.

Definition at line 181 of file interactive_marker_control.h.

Definition at line 250 of file interactive_marker_control.h.

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

Definition at line 247 of file interactive_marker_control.h.

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

Definition at line 273 of file interactive_marker_control.h.

Definition at line 275 of file interactive_marker_control.h.

Definition at line 228 of file interactive_marker_control.h.

Definition at line 209 of file interactive_marker_control.h.

Definition at line 276 of file interactive_marker_control.h.

Definition at line 203 of file interactive_marker_control.h.

Definition at line 224 of file interactive_marker_control.h.

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

Definition at line 200 of file interactive_marker_control.h.

std::string rviz::InteractiveMarkerControl::name_ [protected]

Definition at line 221 of file interactive_marker_control.h.

Definition at line 204 of file interactive_marker_control.h.

Definition at line 226 of file interactive_marker_control.h.

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

Definition at line 260 of file interactive_marker_control.h.

Definition at line 252 of file interactive_marker_control.h.

Definition at line 234 of file interactive_marker_control.h.

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

Definition at line 189 of file interactive_marker_control.h.

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

Definition at line 238 of file interactive_marker_control.h.

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 243 of file interactive_marker_control.h.

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 265 of file interactive_marker_control.h.

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

Definition at line 269 of file interactive_marker_control.h.

Definition at line 279 of file interactive_marker_control.h.

Definition at line 280 of file interactive_marker_control.h.

Definition at line 183 of file interactive_marker_control.h.

Definition at line 278 of file interactive_marker_control.h.


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


rviz
Author(s): Dave Hershberger, Josh Faust
autogenerated on Mon Jan 6 2014 11:54:33