30 #include <OgreViewport.h> 31 #include <OgreCamera.h> 32 #include <OgreSceneNode.h> 33 #include <OgreSceneManager.h> 35 #include <OgreMaterial.h> 36 #include <OgreEntity.h> 37 #include <OgreSubEntity.h> 38 #include <OgreSharedPtr.h> 39 #include <OgreTechnique.h> 57 #define NO_HIGHLIGHT_VALUE 0.0 58 #define ACTIVE_HIGHLIGHT_VALUE 0.5 59 #define HOVER_HIGHLIGHT_VALUE 0.3 65 Ogre::SceneNode *reference_node,
67 : mouse_dragging_(false)
68 , drag_viewport_(
NULL )
70 , reference_node_(reference_node)
71 , control_frame_node_(reference_node_->createChildSceneNode())
72 , markers_node_(reference_node_->createChildSceneNode())
75 , grab_point_in_reference_frame_(0,0,0)
76 , interaction_enabled_(false)
78 , view_facing_( false )
80 , show_visual_aids_(false)
81 , line_(new
Line(context->getSceneManager(),control_frame_node_))
83 line_->setVisible(
false);
88 for (
unsigned i = 0; i < message.markers.size(); i++)
93 ROS_ERROR(
"Unknown marker type: %d", message.markers[i].type );
101 visualization_msgs::MarkerPtr marker_msg(
new visualization_msgs::Marker(message.markers[ i ]) );
103 if ( marker_msg->header.frame_id.empty() )
109 marker->setMessage( marker_msg );
113 marker->setMessage( marker_msg );
117 marker->setPosition(
markers_node_->convertWorldToLocalPosition( marker->getPosition() ) );
118 marker->setOrientation(
markers_node_->convertWorldToLocalOrientation( marker->getOrientation() ) );
120 marker->setInteractiveObject( shared_from_this() );
141 name_ = message.name;
142 description_ = QString::fromStdString( message.description );
148 message.orientation.x, message.orientation.y, message.orientation.z);
151 bool new_view_facingness = (message.orientation_mode == visualization_msgs::InteractiveMarkerControl::VIEW_FACING);
154 if( new_view_facingness )
178 if (
orientation_mode_ == visualization_msgs::InteractiveMarkerControl::INHERIT )
194 line_->setPoints( control_dir, -1*control_dir );
195 line_->setVisible(
false);
200 case visualization_msgs::InteractiveMarkerControl::NONE:
203 case visualization_msgs::InteractiveMarkerControl::MENU:
207 case visualization_msgs::InteractiveMarkerControl::BUTTON:
211 case visualization_msgs::InteractiveMarkerControl::MOVE_AXIS:
215 case visualization_msgs::InteractiveMarkerControl::MOVE_PLANE:
219 case visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS:
223 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE:
225 status_msg_ +=
"<b>Left-Click:</b> Move / Rotate. ";
227 case visualization_msgs::InteractiveMarkerControl::MOVE_3D:
229 status_msg_ +=
"<b>Left-Click:</b> Move X/Y. <b>Shift + Left-Click / Left-Click + Wheel:</b> Move Z. ";
231 case visualization_msgs::InteractiveMarkerControl::ROTATE_3D:
233 status_msg_ +=
"<b>Left-Click:</b> Rotate around X/Y. <b>Shift-Left-Click:</b> Rotate around Z. ";
235 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D:
237 status_msg_ +=
"<b>Left-Click:</b> Move X/Y. <b>Shift + Left-Click / Left-Click + Wheel:</b> Move Z. <b>Ctrl + Left-Click:</b> Rotate around X/Y. <b>Ctrl + Shift + Left-Click:</b> Rotate around Z. ";
243 status_msg_ +=
"<b>Right-Click:</b> Show context menu.";
250 if(
orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
262 Ogre::SceneManager *source,
263 Ogre::SceneManager::IlluminationRenderStage irs, Ogre::Viewport *v )
270 Ogre::Quaternion x_view_facing_rotation =
275 Ogre::Quaternion align_yz_rotation = z_axis_2.getRotationTo(v->getCamera()->getDerivedUp());
278 Ogre::Quaternion rotate_around_x = Ogre::Quaternion(
rotation_, v->getCamera()->getDerivedDirection());
280 Ogre::Quaternion rotation =
reference_node_->convertWorldToLocalOrientation(
281 rotate_around_x * align_yz_rotation * x_view_facing_rotation );
336 Ogre::Vector3 int_marker_position, Ogre::Quaternion int_marker_orientation )
343 case visualization_msgs::InteractiveMarkerControl::INHERIT:
348 case visualization_msgs::InteractiveMarkerControl::FIXED:
355 case visualization_msgs::InteractiveMarkerControl::VIEW_FACING:
372 const Ogre::Vector3& line_dir,
373 const Ogre::Vector3& test_point )
384 double factor = ( test_point - line_start ).dotProduct( line_dir ) / line_dir.dotProduct( line_dir );
385 Ogre::Vector3 closest_point = line_start + line_dir * factor;
386 return closest_point;
391 Ogre::Vector3 intersection_3d;
392 Ogre::Vector2 intersection_2d;
405 intersection_3d, intersection_2d, ray_t ))
424 Ogre::Vector3 center_to_cursor = cursor_in_reference_frame - rotation_center;
425 Ogre::Vector3 center_to_cursor_radial = center_to_cursor - center_to_cursor.dotProduct(rotation_axis)*rotation_axis;
427 Ogre::Quaternion orientation_change_since_mouse_down =
428 grab_rel_center.getRotationTo( center_to_cursor_radial, rotation_axis );
432 orientation_change_since_mouse_down.ToAngleAxis( rot, axis );
438 Ogre::Radian rotation_since_mouse_down = rot * axis.dotProduct( rotation_axis );
448 float width =
event.viewport->getActualWidth() - 1;
449 float height =
event.viewport->getActualHeight() - 1;
451 Ogre::Ray mouse_ray =
event.viewport->getCamera()->getCameraToViewportRay( (x + .5) / width,
455 mouse_ray.setOrigin(
reference_node_->convertWorldToLocalPosition( mouse_ray.getOrigin() ) );
456 mouse_ray.setDirection(
reference_node_->convertWorldToLocalOrientation( Ogre::Quaternion::IDENTITY ) * mouse_ray.getDirection() );
477 if (dx == 0 && dy == 0)
493 static const double MOUSE_SCALE = 2 * 3.14 / 300;
494 Ogre::Radian rx(dx * MOUSE_SCALE);
495 Ogre::Radian ry(dy * MOUSE_SCALE);
497 Ogre::Quaternion up_rot(rx, event.
viewport->getCamera()->getRealUp());
498 Ogre::Quaternion right_rot(ry, event.
viewport->getCamera()->getRealRight());
511 if (std::abs(dy) > std::abs(dx))
516 static const double MOUSE_SCALE = 2 * 3.14 / 300;
517 Ogre::Radian rx(dx * MOUSE_SCALE);
519 Ogre::Quaternion rot(rx, event.
viewport->getCamera()->getRealDirection());
532 if (std::abs(dx) > std::abs(dy))
550 static const double WHEEL_TO_PIXEL_SCALE = (1.0/8.0) * (2.0/15.0);
552 double distance =
event.wheel_delta * WHEEL_TO_PIXEL_SCALE;
565 Ogre::Plane plane( event.
viewport->getCamera()->getRealDirection(),
569 std::pair<bool, Ogre::Real> intersection = mouse_ray.intersects(plane);
570 if (!intersection.first)
572 Ogre::Vector3 mouse_position_on_plane = mouse_ray.getPoint(intersection.second);
582 if(
orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
588 Ogre::Vector3 intersection_3d;
589 Ogre::Vector2 intersection_2d;
593 intersection_3d, intersection_2d, ray_t ))
601 if(
orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
609 Ogre::Vector3 displacement_on_plane = displacement - displacement.dotProduct(plane_normal) * plane_normal;
619 const Ogre::Viewport* viewport,
620 Ogre::Vector2& screen_pos )
622 Ogre::Vector3 world_pos =
reference_node_->convertLocalToWorldPosition( pos_rel_reference );
624 const Ogre::Camera* cam = viewport->getCamera();
625 Ogre::Vector3 homogeneous_screen_position = cam->getProjectionMatrix() * (cam->getViewMatrix() * world_pos);
627 double half_width = viewport->getActualWidth() / 2.0;
628 double half_height = viewport->getActualHeight() / 2.0;
630 screen_pos.x = half_width + (half_width * homogeneous_screen_position.x) - .5;
631 screen_pos.y = half_height + (half_height * -homogeneous_screen_position.y) - .5;
638 const Ogre::Ray& mouse_ray,
639 Ogre::Vector3& closest_point )
647 Ogre::Vector3 v13 = target_ray.getOrigin() - mouse_ray.getOrigin();
648 Ogre::Vector3 v43 = mouse_ray.getDirection();
649 Ogre::Vector3 v21 = target_ray.getDirection();
650 double d1343 = v13.dotProduct( v43 );
651 double d4321 = v43.dotProduct( v21 );
652 double d1321 = v13.dotProduct( v21 );
653 double d4343 = v43.dotProduct( v43 );
654 double d2121 = v21.dotProduct( v21 );
656 double denom = d2121 * d4343 - d4321 * d4321;
657 if( fabs( denom ) <= Ogre::Matrix3::EPSILON )
661 double numer = d1343 * d4321 - d1321 * d4343;
663 double mua = numer / denom;
664 closest_point = target_ray.getPoint( mua );
671 Ogre::Ray control_ray;
676 Ogre::Vector2 control_ray_screen_start, control_ray_screen_end;
677 worldToScreen( control_ray.getOrigin(),
event.viewport, control_ray_screen_start );
678 worldToScreen( control_ray.getPoint( 1 ),
event.viewport, control_ray_screen_end );
680 Ogre::Vector2 mouse_point( event.
x, event.
y );
691 Ogre::Vector2 control_ray_screen_dir = control_ray_screen_end - control_ray_screen_start;
692 double denominator = control_ray_screen_dir.dotProduct( control_ray_screen_dir );
693 if( fabs( denominator ) > Ogre::Matrix3::EPSILON )
696 ( mouse_point - control_ray_screen_start ).dotProduct( control_ray_screen_dir ) / denominator;
698 Ogre::Vector2 closest_screen_point = control_ray_screen_start + control_ray_screen_dir * factor;
704 Ogre::Vector3 closest_point;
717 Ogre::Vector3 displacement_along_axis = (cursor_position_in_reference_frame -
grab_point_in_reference_frame_).dotProduct(control_unit_direction) * control_unit_direction;
727 if(
orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
733 Ogre::Vector3 new_drag_rel_ref;
734 Ogre::Vector2 intersection_2d;
743 Ogre::Matrix4 control_rel_ref;
745 Ogre::Vector3::UNIT_SCALE,
757 new_drag_rel_ref, intersection_2d, ray_t ))
766 Ogre::Vector3 prev_rel_center = prev_drag_rel_ref - rotation_center;
767 Ogre::Vector3 new_rel_center = new_drag_rel_ref - rotation_center;
768 if( new_rel_center.length() > Ogre::Matrix3::EPSILON )
770 Ogre::Quaternion rotation_change = prev_rel_center.getRotationTo( new_rel_center,
rotation_axis_ );
773 rotation_change.ToAngleAxis( rot, axis );
779 Ogre::Radian angle_change = rot * axis.dotProduct(
rotation_axis_ );
786 parent_->
translate( new_rel_center * (1.0 - prev_rel_center.length() / new_rel_center.length()),
name_ );
793 if(
orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
805 Ogre::Matrix4 control_rel_ref;
807 Ogre::Vector3::UNIT_SCALE,
817 Ogre::Vector3 new_drag_rel_ref = cursor_position_in_reference_frame;
821 Ogre::Vector3 perpendicular_offset = (new_drag_rel_ref - prev_drag_rel_ref)
822 .dotProduct(plane_normal)*plane_normal;
823 new_drag_rel_ref -= perpendicular_offset;
834 Ogre::Vector3 prev_rel_center = prev_drag_rel_ref - rotation_center;
835 Ogre::Vector3 new_rel_center = new_drag_rel_ref - rotation_center;
836 if( new_rel_center.length() > Ogre::Matrix3::EPSILON )
838 Ogre::Quaternion rotation_change = prev_rel_center.getRotationTo( new_rel_center,
rotation_axis_ );
841 rotation_change.ToAngleAxis( rot, axis );
847 Ogre::Radian angle_change = rot * axis.dotProduct(
rotation_axis_ );
854 parent_->
translate( new_rel_center * (1.0 - prev_rel_center.length() / new_rel_center.length()),
name_ );
859 const Ogre::Quaternion& cursor_orientation_in_reference_frame )
861 if(
orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
871 Ogre::Vector3 world_to_cursor_in_world_frame =
reference_node_->convertLocalToWorldPosition(cursor_position_in_reference_frame);
872 Ogre::Quaternion rotation_world_to_cursor =
reference_node_->convertLocalToWorldOrientation(cursor_orientation_in_reference_frame);
876 Ogre::Vector3 world_to_cursor_in_cursor_frame = rotation_world_to_cursor.Inverse()*world_to_cursor_in_world_frame;
878 Ogre::Vector3 marker_position_in_reference_frame =
reference_node_->convertWorldToLocalPosition(world_to_marker_in_world_frame);
886 const Ogre::Quaternion& cursor_orientation_in_reference_frame )
888 if(
orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
898 Ogre::Vector3 world_to_cursor_in_world_frame =
reference_node_->convertLocalToWorldPosition(cursor_position_in_reference_frame);
899 Ogre::Quaternion rotation_world_to_cursor =
reference_node_->convertLocalToWorldOrientation(cursor_orientation_in_reference_frame);
903 Ogre::Vector3 world_to_cursor_in_cursor_frame = rotation_world_to_cursor.Inverse()*world_to_cursor_in_world_frame;
905 Ogre::Vector3 marker_position_in_reference_frame =
reference_node_->convertWorldToLocalPosition(world_to_marker_in_world_frame);
909 marker_orientation_in_reference_frame,
name_ );
914 const Ogre::Quaternion& cursor_orientation_in_reference_frame )
916 if(
orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
926 Ogre::Vector3 world_to_cursor_in_world_frame =
reference_node_->convertLocalToWorldPosition(cursor_position_in_reference_frame);
927 Ogre::Quaternion rotation_world_to_cursor =
reference_node_->convertLocalToWorldOrientation(cursor_orientation_in_reference_frame);
931 Ogre::Vector3 world_to_cursor_in_cursor_frame = rotation_world_to_cursor.Inverse()*world_to_cursor_in_world_frame;
933 Ogre::Vector3 marker_position_in_reference_frame =
reference_node_->convertWorldToLocalPosition(world_to_marker_in_world_frame);
937 marker_orientation_in_reference_frame,
name_ );
948 std::set<Ogre::Pass*>::iterator it;
951 (*it)->setAmbient(a,a,a);
954 std::vector<PointsMarkerPtr>::iterator pm_it;
957 (*pm_it)->setHighlightColor( a, a, a );
975 line_->setVisible(
false);
984 const Ogre::Vector3& cursor_3D_pos,
985 const Ogre::Quaternion& cursor_3D_orientation)
990 case visualization_msgs::InteractiveMarkerControl::BUTTON:
993 Ogre::Vector3 point_rel_world = cursor_3D_pos;
994 bool got_3D_point =
true;
996 visualization_msgs::InteractiveMarkerFeedback feedback;
997 feedback.event_type = visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK;
998 feedback.control_name =
name_;
1004 case visualization_msgs::InteractiveMarkerControl::MENU:
1008 Ogre::Vector3 three_d_point = cursor_3D_pos;
1009 bool valid_point =
true;
1011 QCursor::setPos(event.
panel->mapToGlobal(QPoint(mouse_pos.x, mouse_pos.y)));
1016 case visualization_msgs::InteractiveMarkerControl::MOVE_AXIS:
1017 case visualization_msgs::InteractiveMarkerControl::MOVE_PLANE:
1018 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE:
1019 case visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS:
1020 case visualization_msgs::InteractiveMarkerControl::MOVE_3D:
1021 case visualization_msgs::InteractiveMarkerControl::ROTATE_3D:
1022 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D:
1038 if(
orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
1053 Ogre::Matrix4 reference_rel_control_frame;
1055 Ogre::Vector3::UNIT_SCALE,
1075 else if( event.
leftUp() )
1082 if( event.
type == QEvent::MouseMove && event.
left())
1084 Ogre::Vector3 cursor_position_in_reference_frame =
reference_node_->convertWorldToLocalPosition( cursor_3D_pos );
1085 Ogre::Quaternion cursor_orientation_in_reference_frame =
reference_node_->convertWorldToLocalOrientation( cursor_3D_orientation );
1089 case visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS:
1090 rotate( cursor_position_in_reference_frame );
1093 case visualization_msgs::InteractiveMarkerControl::MOVE_AXIS:
1094 moveAxis( cursor_position_in_reference_frame );
1097 case visualization_msgs::InteractiveMarkerControl::MOVE_PLANE:
1098 movePlane( cursor_position_in_reference_frame );
1101 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE:
1102 moveRotate( cursor_position_in_reference_frame,
true );
1105 case visualization_msgs::InteractiveMarkerControl::MOVE_3D:
1106 move3D( cursor_position_in_reference_frame, cursor_orientation_in_reference_frame );
1109 case visualization_msgs::InteractiveMarkerControl::ROTATE_3D:
1110 rotate3D( cursor_position_in_reference_frame, cursor_orientation_in_reference_frame );
1113 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D:
1114 moveRotate3D( cursor_position_in_reference_frame, cursor_orientation_in_reference_frame );
1132 if( event.
type == QEvent::FocusIn )
1135 std::set<Ogre::Pass*>::iterator it;
1139 else if( event.
type == QEvent::FocusOut )
1147 mouse_down_ =
event.left() ||
event.middle() ||
event.right();
1152 case visualization_msgs::InteractiveMarkerControl::BUTTON:
1155 Ogre::Vector3 point_rel_world;
1158 visualization_msgs::InteractiveMarkerFeedback feedback;
1159 feedback.event_type = visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK;
1160 feedback.control_name =
name_;
1166 case visualization_msgs::InteractiveMarkerControl::MENU:
1169 Ogre::Vector3 point_rel_world;
1175 case visualization_msgs::InteractiveMarkerControl::MOVE_AXIS:
1176 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE:
1177 case visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS:
1181 orientation_mode_ != visualization_msgs::InteractiveMarkerControl::VIEW_FACING);
1184 case visualization_msgs::InteractiveMarkerControl::MOVE_PLANE:
1189 case visualization_msgs::InteractiveMarkerControl::MOVE_3D:
1190 case visualization_msgs::InteractiveMarkerControl::ROTATE_3D:
1191 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D:
1198 else if ( event.
left() &&
1227 else if( event.
leftUp() )
1236 line_->setVisible(line_visible);
1243 Ogre::Vector3 grab_point_in_world_frame;
1259 QPoint absolute_mouse = QCursor::pos();
1264 if(
orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
1279 Ogre::Matrix4 reference_rel_control_frame;
1281 Ogre::Vector3::UNIT_SCALE,
1288 static const double DEFAULT_MOUSE_Z_SCALE = 0.001;
1294 Ogre::Vector3 intersection_3d;
1295 Ogre::Vector3 intersection_3d_10;
1296 Ogre::Vector2 intersection_2d;
1300 grab_point_in_reference_frame_,
1307 grab_point_in_reference_frame_,
1325 bool do_rotation =
false;
1328 case visualization_msgs::InteractiveMarkerControl::MOVE_AXIS:
1332 case visualization_msgs::InteractiveMarkerControl::MOVE_PLANE:
1336 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE:
1340 case visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS:
1344 case visualization_msgs::InteractiveMarkerControl::ROTATE_3D:
1347 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D:
1351 case visualization_msgs::InteractiveMarkerControl::MOVE_3D:
1377 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D:
1378 case visualization_msgs::InteractiveMarkerControl::MOVE_3D:
1388 Ogre::Vector3& intersection_3d,
1389 Ogre::Vector2& intersection_2d,
1395 intersection_3d, intersection_2d, ray_t );
1399 const Ogre::Vector3& point_on_plane,
1400 const Ogre::Quaternion& plane_orientation,
1401 Ogre::Vector3& intersection_3d,
1402 Ogre::Vector2& intersection_2d,
1409 Ogre::Plane plane(normal, point_on_plane);
1411 Ogre::Vector2 origin_2d(point_on_plane.dotProduct(axis_1), point_on_plane.dotProduct(axis_2));
1413 std::pair<bool, Ogre::Real> intersection = mouse_ray.intersects(plane);
1414 if (intersection.first)
1416 intersection_3d = mouse_ray.getPoint(intersection.second);
1417 intersection_2d = Ogre::Vector2(intersection_3d.dotProduct(axis_1), intersection_3d.dotProduct(axis_2));
1418 intersection_2d -= origin_2d;
1420 ray_t = intersection.second;
1430 S_MaterialPtr::iterator it;
1432 for (it = materials.begin(); it != materials.end(); it++)
1434 Ogre::MaterialPtr material = *it;
1435 Ogre::Pass *original_pass = material->getTechnique(0)->getPass(0);
1436 Ogre::Pass *pass = material->getTechnique(0)->createPass();
1438 pass->setSceneBlending(Ogre::SBT_ADD);
1439 pass->setDepthWriteEnabled(
false);
1440 pass->setDepthCheckEnabled(
true);
1441 pass->setLightingEnabled(
true);
1442 pass->setAmbient(0, 0, 0);
1443 pass->setDiffuse(0, 0, 0, 0);
1444 pass->setSpecular(0, 0, 0, 0);
1445 pass->setCullingMode(original_pass->getCullingMode());
virtual void setStatus(const QString &message)=0
Ogre::Vector3 parent_to_cursor_in_cursor_frame_at_grab_
void translate(Ogre::Vector3 delta_position, const std::string &control_name)
virtual void handleMouseEvent(ViewportMouseEvent &event)
Ogre::SceneNode * markers_node_
const Ogre::Quaternion & getOrientation()
ViewportMouseEvent dragging_in_place_event_
Ogre::Viewport * viewport
Ogre::Viewport * drag_viewport_
QCursor makeIconCursor(QString url, bool fill_cache)
void rotate(Ogre::Quaternion delta_orientation, const std::string &control_name)
void movePlane(Ogre::Ray &mouse_ray)
void handleMouseWheelMovement(ViewportMouseEvent &event)
void interactiveMarkerPoseChanged(Ogre::Vector3 int_marker_position, Ogre::Quaternion int_marker_orientation)
void beginMouseMovement(ViewportMouseEvent &event, bool line_visible)
void updateControlOrientationForViewFacing(Ogre::Viewport *v)
DisplayContext * context_
virtual ~InteractiveMarkerControl()
std::set< Ogre::Pass * > highlight_passes_
InteractiveMarker * parent_
void addHighlightPass(S_MaterialPtr materials)
take all the materials, add a highlight pass and store a pointer to the pass for later use ...
void move3D(const Ogre::Vector3 &cursor_position_in_reference_frame, const Ogre::Quaternion &cursor_orientation_in_reference_frame)
bool intersectYzPlane(const Ogre::Ray &mouse_ray, Ogre::Vector3 &intersection_3d, Ogre::Vector2 &intersection_2d, float &ray_t)
compute intersection between mouse ray and y-z plane given in local coordinates
void moveViewPlane(Ogre::Ray &mouse_ray, const ViewportMouseEvent &event)
int mouse_relative_to_absolute_x_
virtual void handle3DCursorEvent(ViewportMouseEvent event, const Ogre::Vector3 &cursor_3D_pos, const Ogre::Quaternion &cursor_3D_orientation)
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
#define NO_HIGHLIGHT_VALUE
void moveRotate(Ogre::Ray &mouse_ray)
#define HOVER_HIGHLIGHT_VALUE
Ogre::Quaternion rotation_cursor_to_parent_at_grab_
InteractiveMarkerControl(DisplayContext *context, Ogre::SceneNode *reference_node, InteractiveMarker *parent)
Constructor.
virtual void preFindVisibleObjects(Ogre::SceneManager *source, Ogre::SceneManager::IlluminationRenderStage irs, Ogre::Viewport *v)
Ogre::Quaternion control_frame_orientation_at_mouse_down_
void makeMarkers(const visualization_msgs::InteractiveMarkerControl &message)
Create marker objects from the message and add them to the internal marker arrays.
Ogre::Vector3 closestPointOnLineToPoint(const Ogre::Vector3 &line_start, const Ogre::Vector3 &line_dir, const Ogre::Vector3 &test_point)
std::vector< PointsMarkerPtr > points_markers_
MarkerBase * createMarker(int marker_type, MarkerDisplay *owner, DisplayContext *context, Ogre::SceneNode *parent_node)
void stopDragging(bool force=false)
const Ogre::Vector3 & getPosition()
Ogre::Vector2 project3DPointToViewportXY(const Ogre::Viewport *view, const Ogre::Vector3 &pos)
Given a viewport and a 3D position in world coordinates, project that point into the view plane...
void publishFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback, bool mouse_point_valid=false, const Ogre::Vector3 &mouse_point_rel_world=Ogre::Vector3(0, 0, 0))
Pure-virtual base class for objects which give Display subclasses context in which to work...
const std::string & getName()
void rotate(Ogre::Ray &mouse_ray)
Ogre::Ray mouse_ray_at_drag_begin_
void recordDraggingInPlaceEvent(ViewportMouseEvent &event)
bool handle3DCursorEvent(ViewportMouseEvent &event, const Ogre::Vector3 &cursor_pos, const Ogre::Quaternion &cursor_rot, const std::string &control_name)
Ogre::Vector3 grab_point_in_reference_frame_
Ogre::Ray getMouseRayInReferenceFrame(const ViewportMouseEvent &event, int x, int y)
Qt::KeyboardModifiers modifiers_at_drag_begin_
Ogre::SceneNode * reference_node_
void beginRelativeMouseMotion(const ViewportMouseEvent &event)
void setHighlight(const ControlHighlight &hl)
int mouse_y_at_drag_begin_
Ogre::Quaternion control_orientation_
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
QCursor getDefaultCursor(bool fill_cache)
void moveRotate3D(const Ogre::Vector3 &cursor_position_in_reference_frame, const Ogre::Quaternion &cursor_orientation_in_reference_frame)
virtual SelectionManager * getSelectionManager() const =0
Return a pointer to the SelectionManager.
Ogre::Vector3 parent_position_at_mouse_down_
void showMenu(ViewportMouseEvent &event, const std::string &control_name, const Ogre::Vector3 &three_d_point, bool valid_point)
void rotate3D(const Ogre::Vector3 &cursor_position_in_reference_frame, const Ogre::Quaternion &cursor_orientation_in_reference_frame)
void processMessage(const visualization_msgs::InteractiveMarkerControl &message)
Set up or update the contents of this control to match the specification in the message.
bool findClosestPoint(const Ogre::Ray &target_ray, const Ogre::Ray &mouse_ray, Ogre::Vector3 &closest_point)
Ogre::Vector3 rotation_center_rel_control_
const std::string & getFixedFrame()
Return the current fixed frame name.
bool getRelativeMouseMotion(const ViewportMouseEvent &event, int &dx, int &dy)
void moveZAxisWheel(const ViewportMouseEvent &event)
Ogre::SceneNode * control_frame_node_
void setVisible(bool visible)
std::vector< MarkerBasePtr > markers_
void worldToScreen(const Ogre::Vector3 &pos_rel_reference, const Ogre::Viewport *viewport, Ogre::Vector2 &screen_pos)
virtual Ogre::SceneManager * getSceneManager() const =0
Returns the Ogre::SceneManager used for the main RenderPanel.
virtual void enableInteraction(bool enable)
int mouse_x_at_drag_begin_
#define ACTIVE_HIGHLIGHT_VALUE
bool intersectSomeYzPlane(const Ogre::Ray &mouse_ray, const Ogre::Vector3 &point_in_plane, const Ogre::Quaternion &plane_orientation, Ogre::Vector3 &intersection_3d, Ogre::Vector2 &intersection_2d, float &ray_t)
compute intersection between mouse ray and a y-z plane.
bool interaction_enabled_
int mouse_relative_to_absolute_y_
Ogre::Quaternion grab_orientation_in_reference_frame_
void moveZAxisRelative(const ViewportMouseEvent &event)
void setPose(Ogre::Vector3 position, Ogre::Quaternion orientation, const std::string &control_name)
void rotateXYRelative(const ViewportMouseEvent &event)
void handleMouseMovement(ViewportMouseEvent &event)
void moveAxis(const Ogre::Ray &mouse_ray, const ViewportMouseEvent &event)
Ogre::Radian rotation_at_mouse_down_
std::set< Ogre::MaterialPtr > S_MaterialPtr
bool getInteractionEnabled()
bool independent_marker_orientation_
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
Ogre::Vector3 grab_point_rel_control_
bool handleMouseEvent(ViewportMouseEvent &event, const std::string &control_name)
boost::shared_ptr< Line > line_
bool get3DPoint(Ogre::Viewport *viewport, const int x, const int y, Ogre::Vector3 &result_point)
Ogre::Quaternion parent_orientation_at_mouse_down_
Ogre::Vector3 rotation_axis_
void rotateZRelative(const ViewportMouseEvent &event)