Go to the documentation of this file.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 INTERACTIVE_MARKER_CONTROL_H_
00031 #define INTERACTIVE_MARKER_CONTROL_H_
00032
00033 #include <boost/shared_ptr.hpp>
00034 #include <boost/enable_shared_from_this.hpp>
00035
00036 #include <visualization_msgs/InteractiveMarkerControl.h>
00037
00038 #include "rviz/default_plugin/markers/marker_base.h"
00039 #include "rviz/selection/forwards.h"
00040 #include "rviz/viewport_mouse_event.h"
00041 #include "rviz/interactive_object.h"
00042
00043 #include <OGRE/OgreRay.h>
00044 #include <OGRE/OgreVector3.h>
00045 #include <OGRE/OgreQuaternion.h>
00046 #include <OGRE/OgreSceneManager.h>
00047
00048 namespace Ogre
00049 {
00050 class SceneNode;
00051 }
00052
00053 namespace rviz
00054 {
00055 class VisualizationManager;
00056 class InteractiveMarker;
00057 class PointsMarker;
00058
00062 class InteractiveMarkerControl: public Ogre::SceneManager::Listener,
00063 public InteractiveObject,
00064 public boost::enable_shared_from_this<InteractiveMarkerControl>
00065 {
00066 public:
00074 InteractiveMarkerControl(VisualizationManager* vis_manager,
00075 Ogre::SceneNode *reference_node,
00076 InteractiveMarker *parent );
00077
00078 virtual ~InteractiveMarkerControl();
00079
00082 void processMessage( const visualization_msgs::InteractiveMarkerControl &message );
00083
00084
00085 virtual void enableInteraction(bool enable);
00086
00087
00088 virtual void handleMouseEvent(ViewportMouseEvent& event);
00089
00095 void interactiveMarkerPoseChanged( Ogre::Vector3 int_marker_position, Ogre::Quaternion int_marker_orientation );
00096
00097 bool isInteractive() { return interaction_mode_ != visualization_msgs::InteractiveMarkerControl::NONE; }
00098
00099
00100 void update();
00101
00102 void setVisible( bool visible );
00103
00104 void hideVisible();
00105
00106 void restoreVisible();
00107
00108 protected:
00109
00110
00111 virtual void preFindVisibleObjects(Ogre::SceneManager *source, Ogre::SceneManager::IlluminationRenderStage irs, Ogre::Viewport *v);
00112
00113 void updateControlOrientationForViewFacing( Ogre::Viewport* v );
00114
00117 void rotate(Ogre::Ray &mouse_ray);
00118
00121 void moveRotate( Ogre::Ray &mouse_ray );
00122
00124 void movePlane(Ogre::Ray &mouse_ray);
00125
00126
00127 void moveAxis( const Ogre::Ray& mouse_ray, const ViewportMouseEvent& event );
00128
00130 bool intersectYzPlane( const Ogre::Ray& mouse_ray,
00131 Ogre::Vector3& intersection_3d,
00132 Ogre::Vector2& intersection_2d,
00133 float& ray_t );
00134
00136 bool intersectSomeYzPlane( const Ogre::Ray& mouse_ray,
00137 const Ogre::Vector3& point_in_plane,
00138 const Ogre::Quaternion& plane_orientation,
00139 Ogre::Vector3& intersection_3d,
00140 Ogre::Vector2& intersection_2d,
00141 float& ray_t );
00142
00146 bool findClosestPoint( const Ogre::Ray& target_ray,
00147 const Ogre::Ray& mouse_ray,
00148 Ogre::Vector3& closest_point );
00149
00152 void worldToScreen( const Ogre::Vector3& pos_rel_reference,
00153 const Ogre::Viewport* viewport,
00154 Ogre::Vector2& screen_pos );
00155
00157 void addHighlightPass( S_MaterialPtr materials );
00158
00159
00160 void setHighlight( float a );
00161
00162
00163
00164
00165 void recordDraggingInPlaceEvent( ViewportMouseEvent& event );
00166
00167
00168 void handleMouseMovement( ViewportMouseEvent& event );
00169
00170
00171 Ogre::Vector3 closestPointOnLineToPoint( const Ogre::Vector3& line_start,
00172 const Ogre::Vector3& line_dir,
00173 const Ogre::Vector3& test_point );
00174
00176 void makeMarkers( const visualization_msgs::InteractiveMarkerControl &message );
00177
00178 bool dragging_;
00179 Ogre::Viewport* drag_viewport_;
00180
00181 ViewportMouseEvent dragging_in_place_event_;
00182
00183 VisualizationManager* vis_manager_;
00184
00185 CollObjectHandle coll_object_handle_;
00186
00189 Ogre::SceneNode *reference_node_;
00190
00197 Ogre::SceneNode *control_frame_node_;
00198
00199
00200 Ogre::SceneNode *markers_node_;
00201
00202
00203 int interaction_mode_;
00204 int orientation_mode_;
00205
00206
00207
00208
00209 bool independent_marker_orientation_;
00210
00215 Ogre::Quaternion control_orientation_;
00216
00217 bool always_visible_;
00218
00219 std::string description_;
00220
00221 std::string name_;
00222
00223 typedef boost::shared_ptr<MarkerBase> MarkerBasePtr;
00224 std::vector< MarkerBasePtr > markers_;
00225
00226 InteractiveMarker *parent_;
00227
00228 std::set<Ogre::Pass*> highlight_passes_;
00229
00230
00231
00232
00233 typedef boost::shared_ptr<PointsMarker> PointsMarkerPtr;
00234 std::vector< PointsMarkerPtr > points_markers_;
00235
00238 Ogre::Radian rotation_;
00239
00243 Ogre::Radian rotation_at_mouse_down_;
00244
00247 Ogre::Vector3 grab_point_;
00248
00249
00250 Ogre::Vector2 grab_pixel_;
00251
00252 Ogre::Vector3 parent_position_at_mouse_down_;
00253
00256 Ogre::Quaternion control_frame_orientation_at_mouse_down_;
00257
00260 Ogre::Quaternion parent_orientation_at_mouse_down_;
00261
00265 Ogre::Vector3 rotation_axis_;
00266
00269 Ogre::Vector3 rotation_center_rel_control_;
00270
00273 Ogre::Vector3 grab_point_rel_control_;
00274
00275 bool has_focus_;
00276 bool interaction_enabled_;
00277
00278 bool visible_;
00279 bool saved_visibility_state_;
00280 bool view_facing_;
00281 };
00282
00283 }
00284
00285 #endif