00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifndef CARTESIAN_CONTROL_H_
00031 #define CARTESIAN_CONTROL_H_
00032
00033 #include "rviz/status_level.h"
00034 #include "rviz_interaction_tools/gripper.h"
00035
00036 #include "ogre_tools/shape.h"
00037 #include "rviz_interaction_tools/mesh_object.h"
00038
00039 #include <OGRE/OgreMaterial.h>
00040 #include <OGRE/OgreRay.h>
00041
00042 #include <string>
00043
00044 namespace rviz {
00045 class VisualizationManager;
00046 }
00047
00048 namespace Ogre {
00049 class SceneNode;
00050 }
00051
00052 namespace rviz_interaction_tools
00053 {
00054
00055
00056
00057
00058
00059 class CartesianControl
00060 {
00061 public:
00062
00063 static const float NO_INTERSECTION = 99999;
00064
00065 enum StatusT
00066 {
00067 HIDDEN,
00068 IDLE,
00069 ROTATING,
00070 DRAGGING
00071 };
00072
00073 CartesianControl( Ogre::SceneNode *scene_node, rviz::VisualizationManager *vis_manager );
00074
00075 virtual ~CartesianControl();
00076
00077
00078 void setPosition( Ogre::Vector3 position );
00079 void setOrientation( Ogre::Quaternion orientation );
00080
00081
00082 Ogre::Vector3 getPosition();
00083 Ogre::Quaternion getOrientation();
00084
00085
00086 void setControlsPosition( Ogre::Vector3 position );
00087 void setControlsOrientation( Ogre::Quaternion orientation );
00088
00089 void setFixedControlsOrientation( bool use ) { fixed_controls_orientation_ = use; }
00090 bool getFixedControlsOrientation() { return fixed_controls_orientation_; }
00091
00092
00093 Ogre::Vector3 getControlsPosition();
00094 Ogre::Quaternion getControlsOrientation( );
00095
00096
00097 geometry_msgs::PoseStamped getPose();
00098
00099 void show();
00100 void hide();
00101
00102 void update();
00103
00104 void mouseMove( Ogre::Ray mouse_ray );
00105 void mouseDown( Ogre::Ray mouse_ray );
00106 void mouseUp( Ogre::Ray mouse_ray );
00107
00108
00109 float getClosestIntersection( Ogre::Ray mouse_ray );
00110
00111 protected:
00112
00113 static const float HANDLE_RADIUS_OUTER = 0.13;
00114 static const float HANDLE_RADIUS_INNER = 0.10;
00115 static const float HANDLE_SIZE = 0.03;
00116 static const float HANDLE_ALPHA = 0.5;
00117
00118 enum SideT
00119 {
00120 POS,
00121 NEG
00122 };
00123
00124 void addControls( unsigned axis );
00125
00126 ogre_tools::Shape* addDragBox( Ogre::Vector3 axis );
00127
00128 void addRing(
00129 Ogre::Vector3 axis1, Ogre::Vector3 axis2,
00130 Ogre::MaterialPtr material, unsigned render_queue_group );
00131
00132
00133 void addRingSegment(
00134 Ogre::Vector3 axis1, Ogre::Vector3 axis2,
00135 Ogre::MaterialPtr material, unsigned render_queue_group,
00136 float a_min, float a_max );
00137
00138 bool intersectRing( Ogre::Ray mouse_ray, unsigned axis,
00139 Ogre::Vector3 &intersection_3d, Ogre::Vector2 &intersection_2d, float &ray_t,
00140 float inner_radius=HANDLE_RADIUS_INNER, float outer_radius=HANDLE_RADIUS_OUTER );
00141
00142 bool intersectPlane( Ogre::Ray mouse_ray, unsigned axis,
00143 Ogre::Vector3 &intersection_3d, Ogre::Vector2 &intersection_2d, float &ray_t );
00144
00145 bool getClosestRing( Ogre::Ray mouse_ray,
00146 Ogre::Vector3 &nearest_intersection_3d, Ogre::Vector2 &nearest_intersection_2d,
00147 float &nearest_t, unsigned &nearest_axis );
00148
00149 bool intersectBox( Ogre::Ray mouse_ray, unsigned axis, SideT side,
00150 Ogre::Vector3 &intersection_3d, float &intersection_1d, float &ray_t );
00151
00152 bool getClosestBox( Ogre::Ray mouse_ray,
00153 Ogre::Vector3 &nearest_intersection_3d, float &nearest_intersection_1d,
00154 float &nearest_t, unsigned &nearest_axis, SideT &nearest_side );
00155
00156 Ogre::Vector3 getAxis( unsigned axis );
00157
00158 bool getClosestPosition( Ogre::Ray mouse_ray, unsigned axis, float &pos );
00159
00160 rviz::VisualizationManager *vis_manager_;
00161
00162 bool fixed_controls_orientation_;
00163
00164 Ogre::SceneNode *main_node_;
00165 Ogre::SceneNode *controls_node_;
00166
00167
00168 std::map< unsigned, std::map<SideT, ogre_tools::Shape*> > drag_boxes_;
00169
00170 std::vector<rviz_interaction_tools::MeshObject*> ring_segments_;
00171
00172 ogre_tools::Shape* marker_;
00173
00174 StatusT status_;
00175
00176 double last_angle_;
00177 double last_drag_pos_;
00178 SideT last_drag_side_;
00179 int last_axis_;
00180
00181 Ogre::Vector3 position_;
00182 Ogre::Quaternion orientation_;
00183 };
00184
00185 }
00186
00187 #endif