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
64 Ogre::SceneNode* reference_node,
66 : mouse_dragging_(false)
67 , drag_viewport_(nullptr)
69 , reference_node_(reference_node)
70 , control_frame_node_(reference_node_->createChildSceneNode())
71 , markers_node_(reference_node_->createChildSceneNode())
74 , grab_point_in_reference_frame_(0, 0, 0)
75 , interaction_enabled_(false)
79 , line_(new
Line(context->getSceneManager(), control_frame_node_))
80 , show_visual_aids_(false)
82 line_->setVisible(
false);
87 for (
const auto& marker_msg_const : message.markers)
95 PointsMarkerPtr points_marker = boost::dynamic_pointer_cast<PointsMarker>(marker);
101 visualization_msgs::MarkerPtr marker_msg(
new visualization_msgs::Marker(marker_msg_const));
103 if (marker_msg->header.frame_id.empty())
109 marker->setMessage(marker_msg);
113 marker->setMessage(marker_msg);
116 marker->setPosition(
markers_node_->convertWorldToLocalPosition(marker->getPosition()));
117 marker->setOrientation(
markers_node_->convertWorldToLocalOrientation(marker->getOrientation()));
119 marker->setInteractiveObject(shared_from_this());
140 name_ = message.name;
141 description_ = QString::fromStdString(message.description);
147 message.orientation.y, message.orientation.z);
150 bool new_view_facingness =
151 (message.orientation_mode == visualization_msgs::InteractiveMarkerControl::VIEW_FACING);
154 if (new_view_facingness)
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:
230 "<b>Left-Click:</b> Move X/Y. <b>Shift + Left-Click / Left-Click + Wheel:</b> Move Z. ";
232 case visualization_msgs::InteractiveMarkerControl::ROTATE_3D:
234 status_msg_ +=
"<b>Left-Click:</b> Rotate around X/Y. <b>Shift-Left-Click:</b> Rotate around Z. ";
236 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D:
238 status_msg_ +=
"<b>Left-Click:</b> Move X/Y. <b>Shift + Left-Click / Left-Click + Wheel:</b> Move "
239 "Z. <b>Ctrl + Left-Click:</b> Rotate around X/Y. <b>Ctrl + Shift + Left-Click:</b> "
246 status_msg_ +=
"<b>Right-Click:</b> Show context menu.";
253 if (
orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
265 Ogre::SceneManager::IlluminationRenderStage ,
273 Ogre::Quaternion x_view_facing_rotation =
278 Ogre::Quaternion align_yz_rotation = z_axis_2.getRotationTo(v->getCamera()->getDerivedUp());
281 Ogre::Quaternion rotate_around_x = Ogre::Quaternion(
rotation_, v->getCamera()->getDerivedDirection());
283 Ogre::Quaternion rotation =
reference_node_->convertWorldToLocalOrientation(
284 rotate_around_x * align_yz_rotation * x_view_facing_rotation);
340 Ogre::Quaternion int_marker_orientation)
347 case visualization_msgs::InteractiveMarkerControl::INHERIT:
352 case visualization_msgs::InteractiveMarkerControl::FIXED:
359 case visualization_msgs::InteractiveMarkerControl::VIEW_FACING:
376 const Ogre::Vector3& line_dir,
377 const Ogre::Vector3& test_point)
388 double factor = (test_point - line_start).dotProduct(line_dir) / line_dir.dotProduct(line_dir);
389 Ogre::Vector3 closest_point = line_start + line_dir * factor;
390 return closest_point;
395 Ogre::Vector3 intersection_3d;
396 Ogre::Vector2 intersection_2d;
408 intersection_3d, intersection_2d, ray_t))
426 Ogre::Vector3 center_to_cursor = cursor_in_reference_frame - rotation_center;
427 Ogre::Vector3 center_to_cursor_radial =
428 center_to_cursor - center_to_cursor.dotProduct(rotation_axis) * rotation_axis;
430 Ogre::Quaternion orientation_change_since_mouse_down =
431 grab_rel_center.getRotationTo(center_to_cursor_radial, rotation_axis);
435 orientation_change_since_mouse_down.ToAngleAxis(rot, axis);
441 Ogre::Radian rotation_since_mouse_down = rot * axis.dotProduct(rotation_axis);
451 float width =
event.viewport->getActualWidth() - 1;
452 float height =
event.viewport->getActualHeight() - 1;
454 Ogre::Ray mouse_ray =
455 event.viewport->getCamera()->getCameraToViewportRay((x + .5) / width, (y + .5) / height);
458 mouse_ray.setOrigin(
reference_node_->convertWorldToLocalPosition(mouse_ray.getOrigin()));
459 mouse_ray.setDirection(
reference_node_->convertWorldToLocalOrientation(Ogre::Quaternion::IDENTITY) *
460 mouse_ray.getDirection());
481 if (dx == 0 && dy == 0)
497 static const double MOUSE_SCALE = 2 * 3.14 / 300;
498 Ogre::Radian rx(dx * MOUSE_SCALE);
499 Ogre::Radian ry(dy * MOUSE_SCALE);
501 Ogre::Quaternion up_rot(rx, event.
viewport->getCamera()->getRealUp());
502 Ogre::Quaternion right_rot(ry, event.
viewport->getCamera()->getRealRight());
513 if (std::abs(dy) > std::abs(dx))
518 static const double MOUSE_SCALE = 2 * 3.14 / 300;
519 Ogre::Radian rx(dx * MOUSE_SCALE);
521 Ogre::Quaternion rot(rx, event.
viewport->getCamera()->getRealDirection());
532 if (std::abs(dx) > std::abs(dy))
548 static const double WHEEL_TO_PIXEL_SCALE = (1.0 / 8.0) * (2.0 / 15.0);
550 double distance =
event.wheel_delta * WHEEL_TO_PIXEL_SCALE;
564 std::pair<bool, Ogre::Real> intersection = mouse_ray.intersects(plane);
565 if (!intersection.first)
567 Ogre::Vector3 mouse_position_on_plane = mouse_ray.getPoint(intersection.second);
582 Ogre::Vector3 intersection_3d;
583 Ogre::Vector2 intersection_2d;
604 Ogre::Vector3 displacement_on_plane =
605 displacement - displacement.dotProduct(plane_normal) * plane_normal;
615 const Ogre::Viewport* viewport,
616 Ogre::Vector2& screen_pos)
618 Ogre::Vector3 world_pos =
reference_node_->convertLocalToWorldPosition(pos_rel_reference);
620 const Ogre::Camera* cam = viewport->getCamera();
621 Ogre::Vector3 homogeneous_screen_position =
622 cam->getProjectionMatrix() * (cam->getViewMatrix() * world_pos);
624 double half_width = viewport->getActualWidth() / 2.0;
625 double half_height = viewport->getActualHeight() / 2.0;
627 screen_pos.x = half_width + (half_width * homogeneous_screen_position.x) - .5;
628 screen_pos.y = half_height + (half_height * -homogeneous_screen_position.y) - .5;
635 const Ogre::Ray& mouse_ray,
636 Ogre::Vector3& closest_point)
644 Ogre::Vector3 v13 = target_ray.getOrigin() - mouse_ray.getOrigin();
645 Ogre::Vector3 v43 = mouse_ray.getDirection();
646 Ogre::Vector3 v21 = target_ray.getDirection();
647 double d1343 = v13.dotProduct(v43);
648 double d4321 = v43.dotProduct(v21);
649 double d1321 = v13.dotProduct(v21);
650 double d4343 = v43.dotProduct(v43);
651 double d2121 = v21.dotProduct(v21);
653 double denom = d2121 * d4343 - d4321 * d4321;
654 if (fabs(denom) <= Ogre::Matrix3::EPSILON)
658 double numer = d1343 * d4321 - d1321 * d4343;
660 double mua = numer / denom;
661 closest_point = target_ray.getPoint(mua);
668 Ogre::Ray control_ray;
673 Ogre::Vector2 control_ray_screen_start, control_ray_screen_end;
677 Ogre::Vector2 mouse_point(event.
x, event.
y);
688 Ogre::Vector2 control_ray_screen_dir = control_ray_screen_end - control_ray_screen_start;
689 double denominator = control_ray_screen_dir.dotProduct(control_ray_screen_dir);
690 if (fabs(denominator) >
691 Ogre::Matrix3::EPSILON)
694 (mouse_point - control_ray_screen_start).dotProduct(control_ray_screen_dir) / denominator;
696 Ogre::Vector2 closest_screen_point = control_ray_screen_start + control_ray_screen_dir * factor;
699 Ogre::Ray new_mouse_ray =
703 Ogre::Vector3 closest_point;
715 Ogre::Vector3 control_unit_direction =
717 Ogre::Vector3 displacement_along_axis =
719 .dotProduct(control_unit_direction) *
720 control_unit_direction;
734 Ogre::Vector3 new_drag_rel_ref;
735 Ogre::Vector2 intersection_2d;
744 Ogre::Matrix4 control_rel_ref;
745 control_rel_ref.makeTransform(
control_frame_node_->getPosition(), 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()),
806 Ogre::Matrix4 control_rel_ref;
807 control_rel_ref.makeTransform(
control_frame_node_->getPosition(), Ogre::Vector3::UNIT_SCALE,
817 Ogre::Vector3 new_drag_rel_ref = cursor_position_in_reference_frame;
821 Ogre::Vector3 perpendicular_offset =
822 (new_drag_rel_ref - prev_drag_rel_ref).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()),
860 const Ogre::Quaternion& cursor_orientation_in_reference_frame)
872 Ogre::Vector3 world_to_cursor_in_world_frame =
873 reference_node_->convertLocalToWorldPosition(cursor_position_in_reference_frame);
874 Ogre::Quaternion rotation_world_to_cursor =
875 reference_node_->convertLocalToWorldOrientation(cursor_orientation_in_reference_frame);
880 Ogre::Vector3 world_to_cursor_in_cursor_frame =
881 rotation_world_to_cursor.Inverse() * world_to_cursor_in_world_frame;
882 Ogre::Vector3 world_to_marker_in_world_frame =
883 rotation_world_to_cursor *
885 Ogre::Vector3 marker_position_in_reference_frame =
886 reference_node_->convertWorldToLocalPosition(world_to_marker_in_world_frame);
894 const Ogre::Quaternion& cursor_orientation_in_reference_frame)
908 Ogre::Quaternion rotation_world_to_cursor =
909 reference_node_->convertLocalToWorldOrientation(cursor_orientation_in_reference_frame);
921 Ogre::Quaternion marker_orientation_in_reference_frame =
922 reference_node_->convertWorldToLocalOrientation(rotation_world_to_cursor *
930 const Ogre::Quaternion& cursor_orientation_in_reference_frame)
942 Ogre::Vector3 world_to_cursor_in_world_frame =
943 reference_node_->convertLocalToWorldPosition(cursor_position_in_reference_frame);
944 Ogre::Quaternion rotation_world_to_cursor =
945 reference_node_->convertLocalToWorldOrientation(cursor_orientation_in_reference_frame);
950 Ogre::Vector3 world_to_cursor_in_cursor_frame =
951 rotation_world_to_cursor.Inverse() * world_to_cursor_in_world_frame;
952 Ogre::Vector3 world_to_marker_in_world_frame =
953 rotation_world_to_cursor *
955 Ogre::Vector3 marker_position_in_reference_frame =
956 reference_node_->convertWorldToLocalPosition(world_to_marker_in_world_frame);
957 Ogre::Quaternion marker_orientation_in_reference_frame =
958 reference_node_->convertWorldToLocalOrientation(rotation_world_to_cursor *
961 parent_->
setPose(marker_position_in_reference_frame, marker_orientation_in_reference_frame,
name_);
976 std::set<Ogre::Pass*>::iterator it;
979 (*it)->setAmbient(a, a, a);
982 std::vector<PointsMarkerPtr>::iterator pm_it;
985 (*pm_it)->setHighlightColor(a, a, a);
1003 line_->setVisible(
false);
1012 const Ogre::Vector3& cursor_3D_pos,
1013 const Ogre::Quaternion& cursor_3D_orientation)
1018 case visualization_msgs::InteractiveMarkerControl::BUTTON:
1021 Ogre::Vector3 point_rel_world = cursor_3D_pos;
1022 bool got_3D_point =
true;
1024 visualization_msgs::InteractiveMarkerFeedback feedback;
1025 feedback.event_type = visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK;
1026 feedback.control_name =
name_;
1032 case visualization_msgs::InteractiveMarkerControl::MENU:
1036 Ogre::Vector3 three_d_point = cursor_3D_pos;
1037 bool valid_point =
true;
1039 QCursor::setPos(event.
panel->mapToGlobal(QPoint(mouse_pos.x, mouse_pos.y)));
1044 case visualization_msgs::InteractiveMarkerControl::MOVE_AXIS:
1045 case visualization_msgs::InteractiveMarkerControl::MOVE_PLANE:
1046 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE:
1047 case visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS:
1048 case visualization_msgs::InteractiveMarkerControl::MOVE_3D:
1049 case visualization_msgs::InteractiveMarkerControl::ROTATE_3D:
1050 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D:
1059 reference_node_->convertWorldToLocalOrientation(cursor_3D_orientation);
1062 cursor_3D_orientation.Inverse() *
1065 cursor_3D_orientation.Inverse() *
1071 if (
orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
1085 Ogre::Matrix4 reference_rel_control_frame;
1087 Ogre::Vector3::UNIT_SCALE,
1114 if (event.
type == QEvent::MouseMove && event.
left())
1116 Ogre::Vector3 cursor_position_in_reference_frame =
1118 Ogre::Quaternion cursor_orientation_in_reference_frame =
1119 reference_node_->convertWorldToLocalOrientation(cursor_3D_orientation);
1123 case visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS:
1124 rotate(cursor_position_in_reference_frame);
1127 case visualization_msgs::InteractiveMarkerControl::MOVE_AXIS:
1128 moveAxis(cursor_position_in_reference_frame);
1131 case visualization_msgs::InteractiveMarkerControl::MOVE_PLANE:
1132 movePlane(cursor_position_in_reference_frame);
1135 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE:
1136 moveRotate(cursor_position_in_reference_frame,
true);
1139 case visualization_msgs::InteractiveMarkerControl::MOVE_3D:
1140 move3D(cursor_position_in_reference_frame, cursor_orientation_in_reference_frame);
1143 case visualization_msgs::InteractiveMarkerControl::ROTATE_3D:
1144 rotate3D(cursor_position_in_reference_frame, cursor_orientation_in_reference_frame);
1147 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D:
1148 moveRotate3D(cursor_position_in_reference_frame, cursor_orientation_in_reference_frame);
1166 if (event.
type == QEvent::FocusIn)
1169 std::set<Ogre::Pass*>::iterator it;
1173 else if (event.
type == QEvent::FocusOut)
1181 mouse_down_ =
event.left() ||
event.middle() ||
event.right();
1186 case visualization_msgs::InteractiveMarkerControl::BUTTON:
1189 Ogre::Vector3 point_rel_world;
1193 visualization_msgs::InteractiveMarkerFeedback feedback;
1194 feedback.event_type = visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK;
1195 feedback.control_name =
name_;
1201 case visualization_msgs::InteractiveMarkerControl::MENU:
1204 Ogre::Vector3 point_rel_world;
1211 case visualization_msgs::InteractiveMarkerControl::MOVE_AXIS:
1212 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE:
1213 case visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS:
1217 visualization_msgs::InteractiveMarkerControl::VIEW_FACING);
1220 case visualization_msgs::InteractiveMarkerControl::MOVE_PLANE:
1225 case visualization_msgs::InteractiveMarkerControl::MOVE_3D:
1226 case visualization_msgs::InteractiveMarkerControl::ROTATE_3D:
1227 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D:
1234 else if (event.
left() &&
1272 line_->setVisible(line_visible);
1279 Ogre::Vector3 grab_point_in_world_frame;
1281 grab_point_in_world_frame))
1292 reference_node_->convertWorldToLocalPosition(grab_point_in_world_frame);
1297 QPoint absolute_mouse = QCursor::pos();
1313 Ogre::Vector3 rotation_center_rel_ref =
1315 Ogre::Matrix4 reference_rel_control_frame;
1317 Ogre::Vector3::UNIT_SCALE,
1324 static const double DEFAULT_MOUSE_Z_SCALE = 0.001;
1330 Ogre::Vector3 intersection_3d;
1331 Ogre::Vector3 intersection_3d_10;
1332 Ogre::Vector2 intersection_2d;
1354 bool do_rotation =
false;
1357 case visualization_msgs::InteractiveMarkerControl::MOVE_AXIS:
1361 case visualization_msgs::InteractiveMarkerControl::MOVE_PLANE:
1365 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE:
1369 case visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS:
1373 case visualization_msgs::InteractiveMarkerControl::ROTATE_3D:
1376 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D:
1380 case visualization_msgs::InteractiveMarkerControl::MOVE_3D:
1406 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D:
1407 case visualization_msgs::InteractiveMarkerControl::MOVE_3D:
1417 Ogre::Vector3& intersection_3d,
1418 Ogre::Vector2& intersection_2d,
1427 const Ogre::Vector3& point_on_plane,
1428 const Ogre::Quaternion& plane_orientation,
1429 Ogre::Vector3& intersection_3d,
1430 Ogre::Vector2& intersection_2d,
1437 Ogre::Plane plane(normal, point_on_plane);
1439 Ogre::Vector2 origin_2d(point_on_plane.dotProduct(axis_1), point_on_plane.dotProduct(axis_2));
1441 std::pair<bool, Ogre::Real> intersection = mouse_ray.intersects(plane);
1442 if (intersection.first)
1444 intersection_3d = mouse_ray.getPoint(intersection.second);
1446 Ogre::Vector2(intersection_3d.dotProduct(axis_1), intersection_3d.dotProduct(axis_2));
1447 intersection_2d -= origin_2d;
1449 ray_t = intersection.second;
1459 S_MaterialPtr::iterator it;
1461 for (it = materials.begin(); it != materials.end(); it++)
1463 Ogre::MaterialPtr material = *it;
1464 Ogre::Pass* original_pass = material->getTechnique(0)->getPass(0);
1465 Ogre::Pass* pass = material->getTechnique(0)->createPass();
1467 pass->setSceneBlending(Ogre::SBT_ADD);
1468 pass->setDepthWriteEnabled(
false);
1469 pass->setDepthCheckEnabled(
true);
1470 pass->setLightingEnabled(
true);
1471 pass->setAmbient(0, 0, 0);
1472 pass->setDiffuse(0, 0, 0, 0);
1473 pass->setSpecular(0, 0, 0, 0);
1474 pass->setCullingMode(original_pass->getCullingMode());