#include <cartesian_control.h>
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::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, 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::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 |
Definition at line 58 of file cartesian_control.h.
enum rviz_interaction_tools::CartesianControl::SideT [protected] |
Definition at line 117 of file cartesian_control.h.
Definition at line 64 of file cartesian_control.h.
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.
void rviz_interaction_tools::CartesianControl::addControls | ( | unsigned | axis | ) | [protected] |
Definition at line 86 of file cartesian_control.cpp.
rviz::Shape * rviz_interaction_tools::CartesianControl::addDragBox | ( | Ogre::Vector3 | axis | ) | [protected] |
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.
float rviz_interaction_tools::CartesianControl::getClosestIntersection | ( | Ogre::Ray | mouse_ray | ) |
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.
Ogre::Quaternion rviz_interaction_tools::CartesianControl::getControlsOrientation | ( | ) |
Definition at line 231 of file cartesian_control.cpp.
Ogre::Vector3 rviz_interaction_tools::CartesianControl::getControlsPosition | ( | ) |
Definition at line 226 of file cartesian_control.cpp.
Definition at line 89 of file cartesian_control.h.
Ogre::Quaternion rviz_interaction_tools::CartesianControl::getOrientation | ( | ) |
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.
Ogre::Vector3 rviz_interaction_tools::CartesianControl::getPosition | ( | ) |
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.
void rviz_interaction_tools::CartesianControl::mouseDown | ( | Ogre::Ray | mouse_ray | ) |
Definition at line 340 of file cartesian_control.cpp.
void rviz_interaction_tools::CartesianControl::mouseMove | ( | Ogre::Ray | mouse_ray | ) |
Definition at line 262 of file cartesian_control.cpp.
void rviz_interaction_tools::CartesianControl::mouseUp | ( | Ogre::Ray | mouse_ray | ) |
Definition at line 395 of file cartesian_control.cpp.
void rviz_interaction_tools::CartesianControl::setControlsOrientation | ( | Ogre::Quaternion | orientation | ) |
Definition at line 221 of file cartesian_control.cpp.
void rviz_interaction_tools::CartesianControl::setControlsPosition | ( | Ogre::Vector3 | position | ) |
Definition at line 216 of file cartesian_control.cpp.
void rviz_interaction_tools::CartesianControl::setFixedControlsOrientation | ( | bool | use | ) | [inline] |
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.
void rviz_interaction_tools::CartesianControl::setPosition | ( | Ogre::Vector3 | position | ) |
Definition at line 196 of file cartesian_control.cpp.
Definition at line 178 of file cartesian_control.cpp.
void rviz_interaction_tools::CartesianControl::update | ( | void | ) |
Definition at line 236 of file cartesian_control.cpp.
Ogre::SceneNode* rviz_interaction_tools::CartesianControl::controls_node_ [protected] |
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.
double rviz_interaction_tools::CartesianControl::last_angle_ [protected] |
Definition at line 175 of file cartesian_control.h.
int rviz_interaction_tools::CartesianControl::last_axis_ [protected] |
Definition at line 178 of file cartesian_control.h.
double rviz_interaction_tools::CartesianControl::last_drag_pos_ [protected] |
Definition at line 176 of file cartesian_control.h.
Definition at line 177 of file cartesian_control.h.
Ogre::SceneNode* rviz_interaction_tools::CartesianControl::main_node_ [protected] |
Definition at line 163 of file cartesian_control.h.
Definition at line 171 of file cartesian_control.h.
const float rviz_interaction_tools::CartesianControl::NO_INTERSECTION = 99999 [static] |
Definition at line 62 of file cartesian_control.h.
Ogre::Quaternion rviz_interaction_tools::CartesianControl::orientation_ [protected] |
Definition at line 181 of file cartesian_control.h.
Ogre::Vector3 rviz_interaction_tools::CartesianControl::position_ [protected] |
Definition at line 180 of file cartesian_control.h.
std::vector<rviz_interaction_tools::MeshObject*> rviz_interaction_tools::CartesianControl::ring_segments_ [protected] |
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.