rviz_interaction_tools::CartesianControl Class Reference

#include <cartesian_control.h>

List of all members.

Public Types

enum  StatusT { HIDDEN, IDLE, ROTATING, DRAGGING }

Public Member Functions

 CartesianControl (Ogre::SceneNode *scene_node, rviz::VisualizationManager *vis_manager)
float getClosestIntersection (Ogre::Ray mouse_ray)
Ogre::Quaternion getControlsOrientation ()
Ogre::Vector3 getControlsPosition ()
bool getFixedControlsOrientation ()
Ogre::Quaternion getOrientation ()
geometry_msgs::PoseStamped getPose ()
Ogre::Vector3 getPosition ()
void hide ()
void mouseDown (Ogre::Ray mouse_ray)
void mouseMove (Ogre::Ray mouse_ray)
void mouseUp (Ogre::Ray mouse_ray)
void setControlsOrientation (Ogre::Quaternion orientation)
void setControlsPosition (Ogre::Vector3 position)
void setFixedControlsOrientation (bool use)
void setOrientation (Ogre::Quaternion orientation)
void setPosition (Ogre::Vector3 position)
void show ()
void update ()
virtual ~CartesianControl ()

Static Public Attributes

static const float NO_INTERSECTION = 99999

Protected Types

enum  SideT { POS, NEG }

Protected Member Functions

void addControls (unsigned axis)
ogre_tools::Shape * addDragBox (Ogre::Vector3 axis)
void addRing (Ogre::Vector3 axis1, Ogre::Vector3 axis2, Ogre::MaterialPtr material, unsigned render_queue_group)
void addRingSegment (Ogre::Vector3 axis1, Ogre::Vector3 axis2, Ogre::MaterialPtr material, unsigned render_queue_group, float a_min, float a_max)
Ogre::Vector3 getAxis (unsigned axis)
bool getClosestBox (Ogre::Ray mouse_ray, Ogre::Vector3 &nearest_intersection_3d, float &nearest_intersection_1d, float &nearest_t, unsigned &nearest_axis, SideT &nearest_side)
bool getClosestPosition (Ogre::Ray mouse_ray, unsigned axis, float &pos)
bool getClosestRing (Ogre::Ray mouse_ray, Ogre::Vector3 &nearest_intersection_3d, Ogre::Vector2 &nearest_intersection_2d, float &nearest_t, unsigned &nearest_axis)
bool intersectBox (Ogre::Ray mouse_ray, unsigned axis, SideT side, Ogre::Vector3 &intersection_3d, float &intersection_1d, float &ray_t)
bool intersectPlane (Ogre::Ray mouse_ray, unsigned axis, Ogre::Vector3 &intersection_3d, Ogre::Vector2 &intersection_2d, float &ray_t)
bool intersectRing (Ogre::Ray mouse_ray, unsigned axis, Ogre::Vector3 &intersection_3d, Ogre::Vector2 &intersection_2d, float &ray_t, float inner_radius=HANDLE_RADIUS_INNER, float outer_radius=HANDLE_RADIUS_OUTER)

Protected Attributes

Ogre::SceneNode * controls_node_
std::map< unsigned, std::map
< SideT, ogre_tools::Shape * > > 
drag_boxes_
bool fixed_controls_orientation_
double last_angle_
int last_axis_
double last_drag_pos_
SideT last_drag_side_
Ogre::SceneNode * main_node_
ogre_tools::Shape * marker_
Ogre::Quaternion orientation_
Ogre::Vector3 position_
std::vector
< rviz_interaction_tools::MeshObject * > 
ring_segments_
StatusT status_
rviz::VisualizationManager * vis_manager_

Static Protected Attributes

static const float HANDLE_ALPHA = 0.5
static const float HANDLE_RADIUS_INNER = 0.10
static const float HANDLE_RADIUS_OUTER = 0.13
static const float HANDLE_SIZE = 0.03

Detailed Description

Definition at line 59 of file cartesian_control.h.


Member Enumeration Documentation

Enumerator:
POS 
NEG 

Definition at line 118 of file cartesian_control.h.

Enumerator:
HIDDEN 
IDLE 
ROTATING 
DRAGGING 

Definition at line 65 of file cartesian_control.h.


Constructor & Destructor Documentation

rviz_interaction_tools::CartesianControl::CartesianControl ( Ogre::SceneNode *  scene_node,
rviz::VisualizationManager *  vis_manager 
)

Definition at line 51 of file cartesian_control.cpp.

rviz_interaction_tools::CartesianControl::~CartesianControl (  )  [virtual]

Definition at line 71 of file cartesian_control.cpp.


Member Function Documentation

void rviz_interaction_tools::CartesianControl::addControls ( unsigned  axis  )  [protected]

Definition at line 83 of file cartesian_control.cpp.

ogre_tools::Shape * rviz_interaction_tools::CartesianControl::addDragBox ( Ogre::Vector3  axis  )  [protected]

Definition at line 102 of file cartesian_control.cpp.

void rviz_interaction_tools::CartesianControl::addRing ( Ogre::Vector3  axis1,
Ogre::Vector3  axis2,
Ogre::MaterialPtr  material,
unsigned  render_queue_group 
) [protected]

Definition at line 123 of file cartesian_control.cpp.

void rviz_interaction_tools::CartesianControl::addRingSegment ( Ogre::Vector3  axis1,
Ogre::Vector3  axis2,
Ogre::MaterialPtr  material,
unsigned  render_queue_group,
float  a_min,
float  a_max 
) [protected]

Definition at line 134 of file cartesian_control.cpp.

Ogre::Vector3 rviz_interaction_tools::CartesianControl::getAxis ( unsigned  axis  )  [protected]

Definition at line 546 of file cartesian_control.cpp.

bool rviz_interaction_tools::CartesianControl::getClosestBox ( Ogre::Ray  mouse_ray,
Ogre::Vector3 &  nearest_intersection_3d,
float &  nearest_intersection_1d,
float &  nearest_t,
unsigned &  nearest_axis,
SideT nearest_side 
) [protected]

Definition at line 478 of file cartesian_control.cpp.

float rviz_interaction_tools::CartesianControl::getClosestIntersection ( Ogre::Ray  mouse_ray  ) 

Definition at line 237 of file cartesian_control.cpp.

bool rviz_interaction_tools::CartesianControl::getClosestPosition ( Ogre::Ray  mouse_ray,
unsigned  axis,
float &  pos 
) [protected]

Definition at line 564 of file cartesian_control.cpp.

bool rviz_interaction_tools::CartesianControl::getClosestRing ( Ogre::Ray  mouse_ray,
Ogre::Vector3 &  nearest_intersection_3d,
Ogre::Vector2 &  nearest_intersection_2d,
float &  nearest_t,
unsigned &  nearest_axis 
) [protected]

Definition at line 410 of file cartesian_control.cpp.

Ogre::Quaternion rviz_interaction_tools::CartesianControl::getControlsOrientation (  ) 

Definition at line 228 of file cartesian_control.cpp.

Ogre::Vector3 rviz_interaction_tools::CartesianControl::getControlsPosition (  ) 

Definition at line 223 of file cartesian_control.cpp.

bool rviz_interaction_tools::CartesianControl::getFixedControlsOrientation (  )  [inline]

Definition at line 90 of file cartesian_control.h.

Ogre::Quaternion rviz_interaction_tools::CartesianControl::getOrientation (  ) 

Definition at line 208 of file cartesian_control.cpp.

geometry_msgs::PoseStamped rviz_interaction_tools::CartesianControl::getPose (  ) 

Definition at line 585 of file cartesian_control.cpp.

Ogre::Vector3 rviz_interaction_tools::CartesianControl::getPosition (  ) 

Definition at line 203 of file cartesian_control.cpp.

void rviz_interaction_tools::CartesianControl::hide (  ) 

Definition at line 181 of file cartesian_control.cpp.

bool rviz_interaction_tools::CartesianControl::intersectBox ( Ogre::Ray  mouse_ray,
unsigned  axis,
SideT  side,
Ogre::Vector3 &  intersection_3d,
float &  intersection_1d,
float &  ray_t 
) [protected]

Definition at line 510 of file cartesian_control.cpp.

bool rviz_interaction_tools::CartesianControl::intersectPlane ( Ogre::Ray  mouse_ray,
unsigned  axis,
Ogre::Vector3 &  intersection_3d,
Ogre::Vector2 &  intersection_2d,
float &  ray_t 
) [protected]

Definition at line 447 of file cartesian_control.cpp.

bool rviz_interaction_tools::CartesianControl::intersectRing ( Ogre::Ray  mouse_ray,
unsigned  axis,
Ogre::Vector3 &  intersection_3d,
Ogre::Vector2 &  intersection_2d,
float &  ray_t,
float  inner_radius = HANDLE_RADIUS_INNER,
float  outer_radius = HANDLE_RADIUS_OUTER 
) [protected]

Definition at line 437 of file cartesian_control.cpp.

void rviz_interaction_tools::CartesianControl::mouseDown ( Ogre::Ray  mouse_ray  ) 

Definition at line 337 of file cartesian_control.cpp.

void rviz_interaction_tools::CartesianControl::mouseMove ( Ogre::Ray  mouse_ray  ) 

Definition at line 259 of file cartesian_control.cpp.

void rviz_interaction_tools::CartesianControl::mouseUp ( Ogre::Ray  mouse_ray  ) 

Definition at line 392 of file cartesian_control.cpp.

void rviz_interaction_tools::CartesianControl::setControlsOrientation ( Ogre::Quaternion  orientation  ) 

Definition at line 218 of file cartesian_control.cpp.

void rviz_interaction_tools::CartesianControl::setControlsPosition ( Ogre::Vector3  position  ) 

Definition at line 213 of file cartesian_control.cpp.

void rviz_interaction_tools::CartesianControl::setFixedControlsOrientation ( bool  use  )  [inline]

Definition at line 89 of file cartesian_control.h.

void rviz_interaction_tools::CartesianControl::setOrientation ( Ogre::Quaternion  orientation  ) 

Definition at line 198 of file cartesian_control.cpp.

void rviz_interaction_tools::CartesianControl::setPosition ( Ogre::Vector3  position  ) 

Definition at line 193 of file cartesian_control.cpp.

void rviz_interaction_tools::CartesianControl::show (  ) 

Definition at line 175 of file cartesian_control.cpp.

void rviz_interaction_tools::CartesianControl::update (  ) 

Definition at line 233 of file cartesian_control.cpp.


Member Data Documentation

Definition at line 165 of file cartesian_control.h.

std::map< unsigned, std::map<SideT, ogre_tools::Shape*> > rviz_interaction_tools::CartesianControl::drag_boxes_ [protected]

Definition at line 168 of file cartesian_control.h.

Definition at line 162 of file cartesian_control.h.

const float rviz_interaction_tools::CartesianControl::HANDLE_ALPHA = 0.5 [static, protected]

Definition at line 116 of file cartesian_control.h.

const float rviz_interaction_tools::CartesianControl::HANDLE_RADIUS_INNER = 0.10 [static, protected]

Definition at line 114 of file cartesian_control.h.

const float rviz_interaction_tools::CartesianControl::HANDLE_RADIUS_OUTER = 0.13 [static, protected]

Definition at line 113 of file cartesian_control.h.

const float rviz_interaction_tools::CartesianControl::HANDLE_SIZE = 0.03 [static, protected]

Definition at line 115 of file cartesian_control.h.

Definition at line 176 of file cartesian_control.h.

Definition at line 179 of file cartesian_control.h.

Definition at line 177 of file cartesian_control.h.

Definition at line 178 of file cartesian_control.h.

Definition at line 164 of file cartesian_control.h.

ogre_tools::Shape* rviz_interaction_tools::CartesianControl::marker_ [protected]

Definition at line 172 of file cartesian_control.h.

Definition at line 63 of file cartesian_control.h.

Definition at line 182 of file cartesian_control.h.

Definition at line 181 of file cartesian_control.h.

Definition at line 170 of file cartesian_control.h.

Definition at line 174 of file cartesian_control.h.

rviz::VisualizationManager* rviz_interaction_tools::CartesianControl::vis_manager_ [protected]

Definition at line 160 of file cartesian_control.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


rviz_interaction_tools
Author(s): David Gossow
autogenerated on Fri Jan 11 09:34:12 2013