Public Types | Public Member Functions | Static Public Attributes | Protected Types | Protected Member Functions | Protected Attributes | Static Protected Attributes
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)
rviz::ShapeaddDragBox (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, rviz::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_
rviz::Shapemarker_
Ogre::Quaternion orientation_
Ogre::Vector3 position_
std::vector
< rviz_interaction_tools::MeshObject * > 
ring_segments_
StatusT status_
rviz::VisualizationManagervis_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 58 of file cartesian_control.h.


Member Enumeration Documentation

Enumerator:
POS 
NEG 

Definition at line 117 of file cartesian_control.h.

Enumerator:
HIDDEN 
IDLE 
ROTATING 
DRAGGING 

Definition at line 64 of file cartesian_control.h.


Constructor & Destructor Documentation

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

Definition at line 54 of file cartesian_control.cpp.

Definition at line 74 of file cartesian_control.cpp.


Member Function Documentation

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

Definition at line 86 of file cartesian_control.cpp.

Definition at line 105 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 126 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 137 of file cartesian_control.cpp.

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

Definition at line 549 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 481 of file cartesian_control.cpp.

Definition at line 240 of file cartesian_control.cpp.

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

Definition at line 567 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 413 of file cartesian_control.cpp.

Definition at line 231 of file cartesian_control.cpp.

Definition at line 226 of file cartesian_control.cpp.

Definition at line 89 of file cartesian_control.h.

Definition at line 211 of file cartesian_control.cpp.

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

Definition at line 588 of file cartesian_control.cpp.

Definition at line 206 of file cartesian_control.cpp.

Definition at line 184 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 513 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 450 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 440 of file cartesian_control.cpp.

Definition at line 340 of file cartesian_control.cpp.

Definition at line 262 of file cartesian_control.cpp.

Definition at line 395 of file cartesian_control.cpp.

Definition at line 221 of file cartesian_control.cpp.

Definition at line 216 of file cartesian_control.cpp.

Definition at line 88 of file cartesian_control.h.

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

Definition at line 201 of file cartesian_control.cpp.

Definition at line 196 of file cartesian_control.cpp.

Definition at line 178 of file cartesian_control.cpp.

Definition at line 236 of file cartesian_control.cpp.


Member Data Documentation

Definition at line 164 of file cartesian_control.h.

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

Definition at line 167 of file cartesian_control.h.

Definition at line 161 of file cartesian_control.h.

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

Definition at line 115 of file cartesian_control.h.

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

Definition at line 113 of file cartesian_control.h.

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

Definition at line 112 of file cartesian_control.h.

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

Definition at line 114 of file cartesian_control.h.

Definition at line 175 of file cartesian_control.h.

Definition at line 178 of file cartesian_control.h.

Definition at line 176 of file cartesian_control.h.

Definition at line 177 of file cartesian_control.h.

Definition at line 163 of file cartesian_control.h.

Definition at line 171 of file cartesian_control.h.

Definition at line 62 of file cartesian_control.h.

Definition at line 181 of file cartesian_control.h.

Definition at line 180 of file cartesian_control.h.

Definition at line 169 of file cartesian_control.h.

Definition at line 173 of file cartesian_control.h.

Definition at line 159 of file cartesian_control.h.


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


rviz_interaction_tools
Author(s): David Gossow
autogenerated on Thu Jan 2 2014 11:37:58