30 #ifndef INTERACTIVE_MARKER_CONTROL_H_ 31 #define INTERACTIVE_MARKER_CONTROL_H_ 35 #include <boost/shared_ptr.hpp> 36 #include <boost/enable_shared_from_this.hpp> 39 #include <OgreVector3.h> 40 #include <OgreQuaternion.h> 41 #include <OgreSceneManager.h> 46 #include <visualization_msgs/InteractiveMarkerControl.h> 61 class InteractiveMarker;
70 public boost::enable_shared_from_this<InteractiveMarkerControl>
81 Ogre::SceneNode *reference_node,
88 void processMessage(
const visualization_msgs::InteractiveMarkerControl &message );
91 virtual void enableInteraction(
bool enable);
121 virtual void handle3DCursorEvent(
ViewportMouseEvent event,
const Ogre::Vector3& cursor_3D_pos,
const Ogre::Quaternion& cursor_3D_orientation);
128 void interactiveMarkerPoseChanged( Ogre::Vector3 int_marker_position, Ogre::Quaternion int_marker_orientation );
130 bool isInteractive() {
return interaction_mode_ != visualization_msgs::InteractiveMarkerControl::NONE; }
135 void setVisible(
bool visible );
142 ACTIVE_HIGHLIGHT = 5};
155 const std::string&
getName() {
return name_; }
180 virtual void preFindVisibleObjects(Ogre::SceneManager *source, Ogre::SceneManager::IlluminationRenderStage irs, Ogre::Viewport *v);
182 void updateControlOrientationForViewFacing( Ogre::Viewport* v );
212 void rotate( Ogre::Ray &mouse_ray );
215 void rotate(
const Ogre::Vector3& cursor_position_in_reference_frame);
219 void moveRotate( Ogre::Ray &mouse_ray );
222 void moveRotate(
const Ogre::Vector3& cursor_position_in_reference_frame,
bool lock_axis =
true);
226 void movePlane( Ogre::Ray &mouse_ray );
229 void movePlane(
const Ogre::Vector3& cursor_position_in_reference_frame );
236 void moveAxis(
const Ogre::Vector3& cursor_position_in_reference_frame );
239 void move3D(
const Ogre::Vector3& cursor_position_in_reference_frame,
240 const Ogre::Quaternion &cursor_orientation_in_reference_frame );
243 void rotate3D(
const Ogre::Vector3& cursor_position_in_reference_frame,
244 const Ogre::Quaternion &cursor_orientation_in_reference_frame );
247 void moveRotate3D(
const Ogre::Vector3& cursor_position_in_reference_frame,
248 const Ogre::Quaternion& cursor_orientation_in_reference_frame );
251 bool intersectYzPlane(
const Ogre::Ray& mouse_ray,
252 Ogre::Vector3& intersection_3d,
253 Ogre::Vector2& intersection_2d,
257 bool intersectSomeYzPlane(
const Ogre::Ray& mouse_ray,
258 const Ogre::Vector3& point_in_plane,
259 const Ogre::Quaternion& plane_orientation,
260 Ogre::Vector3& intersection_3d,
261 Ogre::Vector2& intersection_2d,
267 bool findClosestPoint(
const Ogre::Ray& target_ray,
268 const Ogre::Ray& mouse_ray,
269 Ogre::Vector3& closest_point );
273 void worldToScreen(
const Ogre::Vector3& pos_rel_reference,
274 const Ogre::Viewport* viewport,
275 Ogre::Vector2& screen_pos );
281 void setHighlight(
float a );
298 Ogre::Vector3 closestPointOnLineToPoint(
const Ogre::Vector3& line_start,
299 const Ogre::Vector3& line_dir,
300 const Ogre::Vector3& test_point );
303 void makeMarkers(
const visualization_msgs::InteractiveMarkerControl &message );
305 void stopDragging(
bool force =
false );
307 virtual const QCursor&
getCursor()
const {
return cursor_; }
Ogre::Vector3 parent_to_cursor_in_cursor_frame_at_grab_
Ogre::SceneNode * markers_node_
ViewportMouseEvent dragging_in_place_event_
Ogre::Viewport * drag_viewport_
Ogre::Vector3 parent_to_grab_position_
DisplayContext * context_
std::set< Ogre::Pass * > highlight_passes_
InteractiveMarker * parent_
void setShowVisualAids(bool show)
If true, will show some geometric helpers while dragging.
int mouse_relative_to_absolute_x_
Ogre::Quaternion rotation_cursor_to_parent_at_grab_
TFSIMD_FORCE_INLINE const tfScalar & y() const
Ogre::Quaternion control_frame_orientation_at_mouse_down_
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
std::vector< PointsMarkerPtr > points_markers_
Abstract base class of things in the scene which handle mouse events.
Pure-virtual base class for objects which give Display subclasses context in which to work...
Ogre::Ray mouse_ray_at_drag_begin_
Ogre::Vector3 grab_point_in_reference_frame_
Qt::KeyboardModifiers modifiers_at_drag_begin_
Ogre::SceneNode * reference_node_
int mouse_y_at_drag_begin_
Ogre::Quaternion control_orientation_
Ogre::Vector3 parent_position_at_mouse_down_
boost::shared_ptr< MarkerBase > MarkerBasePtr
TFSIMD_FORCE_INLINE const tfScalar & x() const
const QString & getDescription()
Ogre::Vector3 rotation_center_rel_control_
const std::string & getName()
InteractiveMarker * getParent()
Ogre::SceneNode * control_frame_node_
std::vector< MarkerBasePtr > markers_
virtual const QCursor & getCursor() const
int mouse_x_at_drag_begin_
bool interaction_enabled_
int mouse_relative_to_absolute_y_
Ogre::Quaternion grab_orientation_in_reference_frame_
TFSIMD_FORCE_INLINE Vector3 rotate(const Vector3 &wAxis, const tfScalar angle) const
CollObjectHandle coll_object_handle_
Ogre::Radian rotation_at_mouse_down_
std::set< Ogre::MaterialPtr > S_MaterialPtr
bool independent_marker_orientation_
Ogre::Vector3 grab_point_rel_control_
boost::shared_ptr< Line > line_
Ogre::Quaternion parent_orientation_at_mouse_down_
Ogre::Vector3 rotation_axis_
uint32_t CollObjectHandle
boost::shared_ptr< PointsMarker > PointsMarkerPtr