Go to the documentation of this file.
30 #ifndef INTERACTIVE_MARKER_CONTROL_H_
31 #define INTERACTIVE_MARKER_CONTROL_H_
34 #include <boost/shared_ptr.hpp>
35 #include <boost/enable_shared_from_this.hpp>
39 #include <OgreQuaternion.h>
40 #include <OgreSceneManager.h>
45 #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);
122 const Ogre::Vector3& cursor_3D_pos,
123 const Ogre::Quaternion& cursor_3D_orientation);
131 Ogre::Quaternion int_marker_orientation);
207 Ogre::SceneManager::IlluminationRenderStage irs,
208 Ogre::Viewport* v)
override;
240 void rotate(Ogre::Ray& mouse_ray);
243 void rotate(
const Ogre::Vector3& cursor_position_in_reference_frame);
251 void moveRotate(
const Ogre::Vector3& cursor_position_in_reference_frame,
bool lock_axis =
true);
258 void movePlane(
const Ogre::Vector3& cursor_position_in_reference_frame);
265 void moveAxis(
const Ogre::Vector3& cursor_position_in_reference_frame);
268 void move3D(
const Ogre::Vector3& cursor_position_in_reference_frame,
269 const Ogre::Quaternion& cursor_orientation_in_reference_frame);
272 void rotate3D(
const Ogre::Vector3& cursor_position_in_reference_frame,
273 const Ogre::Quaternion& cursor_orientation_in_reference_frame);
276 void moveRotate3D(
const Ogre::Vector3& cursor_position_in_reference_frame,
277 const Ogre::Quaternion& cursor_orientation_in_reference_frame);
281 Ogre::Vector3& intersection_3d,
282 Ogre::Vector2& intersection_2d,
287 const Ogre::Vector3& point_in_plane,
288 const Ogre::Quaternion& plane_orientation,
289 Ogre::Vector3& intersection_3d,
290 Ogre::Vector2& intersection_2d,
297 const Ogre::Ray& mouse_ray,
298 Ogre::Vector3& closest_point);
303 const Ogre::Viewport* viewport,
304 Ogre::Vector2& screen_pos);
328 const Ogre::Vector3& line_dir,
329 const Ogre::Vector3& test_point);
332 void makeMarkers(
const visualization_msgs::InteractiveMarkerControl& message);
const QString & getDescription()
void moveRotate(Ogre::Ray &mouse_ray)
void worldToScreen(const Ogre::Vector3 &pos_rel_reference, const Ogre::Viewport *viewport, Ogre::Vector2 &screen_pos)
std::set< Ogre::MaterialPtr > S_MaterialPtr
std::set< Ogre::Pass * > highlight_passes_
Ogre::Vector3 parent_to_cursor_in_cursor_frame_at_grab_
Ogre::Quaternion parent_orientation_at_mouse_down_
InteractiveMarker * getParent()
CollObjectHandle coll_object_handle_
boost::shared_ptr< MarkerBase > MarkerBasePtr
Ogre::SceneNode * reference_node_
Ogre::SceneNode * markers_node_
void setShowVisualAids(bool show)
If true, will show some geometric helpers while dragging.
void move3D(const Ogre::Vector3 &cursor_position_in_reference_frame, const Ogre::Quaternion &cursor_orientation_in_reference_frame)
void moveViewPlane(Ogre::Ray &mouse_ray, const ViewportMouseEvent &event)
boost::shared_ptr< Line > line_
void beginRelativeMouseMotion(const ViewportMouseEvent &event)
ViewportMouseEvent dragging_in_place_event_
void moveZAxisWheel(const ViewportMouseEvent &event)
bool getRelativeMouseMotion(const ViewportMouseEvent &event, int &dx, int &dy)
std::vector< MarkerBasePtr > markers_
void rotateXYRelative(const ViewportMouseEvent &event)
std::vector< PointsMarkerPtr > points_markers_
InteractiveMarker * parent_
void handleMouseWheelMovement(ViewportMouseEvent &event)
Ogre::Vector3 grab_point_in_reference_frame_
Qt::KeyboardModifiers modifiers_at_drag_begin_
Ogre::Vector3 rotation_center_rel_control_
uint32_t CollObjectHandle
void enableInteraction(bool enable) override
void addHighlightPass(const S_MaterialPtr &materials)
take all the materials, add a highlight pass and store a pointer to the pass for later use
Ogre::Ray mouse_ray_at_drag_begin_
void rotate3D(const Ogre::Vector3 &cursor_position_in_reference_frame, const Ogre::Quaternion &cursor_orientation_in_reference_frame)
void recordDraggingInPlaceEvent(ViewportMouseEvent &event)
void moveAxis(const Ogre::Ray &mouse_ray, const ViewportMouseEvent &event)
void beginMouseMovement(ViewportMouseEvent &event, bool line_visible)
bool findClosestPoint(const Ogre::Ray &target_ray, const Ogre::Ray &mouse_ray, Ogre::Vector3 &closest_point)
void movePlane(Ogre::Ray &mouse_ray)
void makeMarkers(const visualization_msgs::InteractiveMarkerControl &message)
Create marker objects from the message and add them to the internal marker arrays.
Ogre::Vector3 rotation_axis_
void interactiveMarkerPoseChanged(Ogre::Vector3 int_marker_position, Ogre::Quaternion int_marker_orientation)
InteractiveMarkerControl(DisplayContext *context, Ogre::SceneNode *reference_node, InteractiveMarker *parent)
Constructor.
Ogre::Ray getMouseRayInReferenceFrame(const ViewportMouseEvent &event, int x, int y)
Abstract base class of things in the scene which handle mouse events.
int mouse_y_at_drag_begin_
Ogre::Quaternion control_orientation_
void handleMouseMovement(ViewportMouseEvent &event)
const std::string & getName()
Ogre::Quaternion rotation_cursor_to_parent_at_grab_
Pure-virtual base class for objects which give Display subclasses context in which to work.
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
Ogre::Vector3 parent_position_at_mouse_down_
void moveRotate3D(const Ogre::Vector3 &cursor_position_in_reference_frame, const Ogre::Quaternion &cursor_orientation_in_reference_frame)
void rotateZRelative(const ViewportMouseEvent &event)
Ogre::Quaternion grab_orientation_in_reference_frame_
Ogre::Radian rotation_at_mouse_down_
bool interaction_enabled_
void processMessage(const visualization_msgs::InteractiveMarkerControl &message)
Set up or update the contents of this control to match the specification in the message.
bool isInteractive() override
void setHighlight(const ControlHighlight &hl)
Ogre::Vector3 closestPointOnLineToPoint(const Ogre::Vector3 &line_start, const Ogre::Vector3 &line_dir, const Ogre::Vector3 &test_point)
int mouse_x_at_drag_begin_
void preFindVisibleObjects(Ogre::SceneManager *source, Ogre::SceneManager::IlluminationRenderStage irs, Ogre::Viewport *v) override
~InteractiveMarkerControl() override
void stopDragging(bool force=false)
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 independent_marker_orientation_
Ogre::Quaternion control_frame_orientation_at_mouse_down_
void rotate(Ogre::Ray &mouse_ray)
virtual void handle3DCursorEvent(ViewportMouseEvent event, const Ogre::Vector3 &cursor_3D_pos, const Ogre::Quaternion &cursor_3D_orientation)
boost::shared_ptr< PointsMarker > PointsMarkerPtr
Ogre::Viewport * drag_viewport_
void setVisible(bool visible)
int mouse_relative_to_absolute_x_
Ogre::Vector3 parent_to_grab_position_
void handleMouseEvent(ViewportMouseEvent &event) override
Ogre::Vector3 grab_point_rel_control_
DisplayContext * context_
Ogre::SceneNode * control_frame_node_
void moveZAxisRelative(const ViewportMouseEvent &event)
int mouse_relative_to_absolute_y_
void updateControlOrientationForViewFacing(Ogre::Viewport *v)
const QCursor & getCursor() const override
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:09