ModelManipulator Class Reference

Manipulator tool for translating/rotating/scaling models and links. More...

#include <gui/Gui.hh>

Inherits SingletonT< ModelManipulator >.

Public Member Functions

void Clear ()
 Clear the model manipulator. More...
 
void Detach ()
 Detach the manipulator from an entity. More...
 
void Init ()
 Initialize the model manipulator. More...
 
void OnKeyPressEvent (const common::KeyEvent &_event)
 Process a key press event. More...
 
void OnKeyReleaseEvent (const common::KeyEvent &_event)
 Process a key release event. More...
 
void OnMouseMoveEvent (const common::MouseEvent &_event)
 Process an object translate mouse move event. More...
 
void OnMousePressEvent (const common::MouseEvent &_event)
 Process an object translate mouse press event. More...
 
void OnMouseReleaseEvent (const common::MouseEvent &_event)
 Process an object translate mouse release event. More...
 
void RotateEntity (rendering::VisualPtr &_vis, const ignition::math::Vector3d &_axis, const bool _local=false)
 Rotate entity. More...
 
void ScaleEntity (rendering::VisualPtr &_vis, const ignition::math::Vector3d &_axis, const bool _local=false)
 Scale entity. More...
 
void SetAttachedVisual (rendering::VisualPtr _vis)
 Set the visual to be manipulated by the model manipulator. More...
 
void SetManipulationMode (const std::string &_mode)
 Set the manipulation mode. More...
 
void TranslateEntity (rendering::VisualPtr &_vis, const ignition::math::Vector3d &_axis, const bool _local=false)
 Translate entity. More...
 

Static Public Member Functions

static ModelManipulatorInstance ()
 Get an instance of the singleton. More...
 
static ignition::math::Vector3d MouseMoveDistance (rendering::CameraPtr _camera, const ignition::math::Vector2i &_start, const ignition::math::Vector2i &_end, const ignition::math::Pose3d &_pose, const ignition::math::Vector3d &_axis, const bool _local)
 Helper function to get the distance moved by the mouse. More...
 
static ignition::math::Vector3d MousePositionOnPlane (rendering::CameraPtr _camera, const common::MouseEvent &_event)
 Helper function to get the 3D position of mouse on ground plane. More...
 
static ignition::math::Vector3d SnapPoint (const ignition::math::Vector3d &_point, const double _interval=1.0, const double _sensitivity=0.4)
 Snap a point at intervals of a fixed distance. More...
 

Detailed Description

Manipulator tool for translating/rotating/scaling models and links.

Member Function Documentation

void Clear ( )

Clear the model manipulator.

This explicity cleans up the internal state of the singleton and prepares it for exit.

void Detach ( )

Detach the manipulator from an entity.

void Init ( )

Initialize the model manipulator.

static ModelManipulator * Instance ( )
inlinestaticinherited

Get an instance of the singleton.

static ignition::math::Vector3d MouseMoveDistance ( rendering::CameraPtr  _camera,
const ignition::math::Vector2i &  _start,
const ignition::math::Vector2i &  _end,
const ignition::math::Pose3d &  _pose,
const ignition::math::Vector3d &  _axis,
const bool  _local 
)
static

Helper function to get the distance moved by the mouse.

Parameters
[in]_cameraPointer to user camera.
[in]_startStart point.
[in]_endEnd point.
[in]_posePose of origin.
[in]_axisMovement axis.
[in]_localTrue to get distance in local frame.
Returns
Mouse distance moved.
static ignition::math::Vector3d MousePositionOnPlane ( rendering::CameraPtr  _camera,
const common::MouseEvent _event 
)
static

Helper function to get the 3D position of mouse on ground plane.

param[in] _camera Pointer to user camera. param[in] _event Mouse event. return Point of mouse-plane intersection in world coordinates.

void OnKeyPressEvent ( const common::KeyEvent _event)

Process a key press event.

Parameters
[in]_eventKey event.
void OnKeyReleaseEvent ( const common::KeyEvent _event)

Process a key release event.

Parameters
[in]_eventKey event.
void OnMouseMoveEvent ( const common::MouseEvent _event)

Process an object translate mouse move event.

Parameters
[in]_eventMouse event.
void OnMousePressEvent ( const common::MouseEvent _event)

Process an object translate mouse press event.

Parameters
[in]_eventMouse event.
void OnMouseReleaseEvent ( const common::MouseEvent _event)

Process an object translate mouse release event.

Parameters
[in]_eventMouse event.
void RotateEntity ( rendering::VisualPtr _vis,
const ignition::math::Vector3d &  _axis,
const bool  _local = false 
)

Rotate entity.

Parameters
[in]_visVisual representing the entity.
[in]_axisAxis of rotation.
[in]_localTrue to apply rotation in local frame.
void ScaleEntity ( rendering::VisualPtr _vis,
const ignition::math::Vector3d &  _axis,
const bool  _local = false 
)

Scale entity.

Parameters
[in]_visVisual representing the entity.
[in]_axisScaling axis.
[in]_localTrue to apply scaling in local frame.
void SetAttachedVisual ( rendering::VisualPtr  _vis)

Set the visual to be manipulated by the model manipulator.

void SetManipulationMode ( const std::string &  _mode)

Set the manipulation mode.

Parameters
[in]_modeManipulation mode: translate, rotate, or scale.
static ignition::math::Vector3d SnapPoint ( const ignition::math::Vector3d &  _point,
const double  _interval = 1.0,
const double  _sensitivity = 0.4 
)
static

Snap a point at intervals of a fixed distance.

Currently used to give a snapping behavior when moving models with a mouse.

Parameters
[in]_pointInput point.
[in]_intervalFixed distance interval at which the point is snapped.
[in]_sensitivitySensitivity of point snapping, in terms of a percentage of the interval.
Returns
Snapped 3D point.
void TranslateEntity ( rendering::VisualPtr _vis,
const ignition::math::Vector3d &  _axis,
const bool  _local = false 
)

Translate entity.

Parameters
[in]_visVisual representing the entity.
[in]_axisAxis of translation.
[in]_localTrue to apply translation in local frame.

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