interface_interactive_marker.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import rospy
00004 
00005 from frame_editor.objects import *
00006 from frame_editor.commands import *
00007 from frame_editor.interface import Interface
00008 
00009 from frame_editor.constructors_geometry import *
00010 from frame_editor.constructors_std import *
00011 
00012 from geometry_msgs.msg import Pose
00013 
00014 from interactive_markers.interactive_marker_server import *
00015 from visualization_msgs.msg import InteractiveMarkerControl, Marker
00016 
00017 
00018 class FrameEditor_InteractiveMarker(Interface):
00019 
00020     def __init__(self, frame_editor):
00021         self.editor = frame_editor
00022         self.editor.observers.append(self)
00023 
00024         self.server = InteractiveMarkerServer("frame_editor_interactive")
00025 
00026         self.set_marker_settings(["x", "y", "z", "a", "b", "c"])
00027 
00028         self.old_frame = None
00029 
00030 
00031     def update(self, editor, level, elements):
00032 
00033         if level & 2:
00034             ## Check for change
00035             if self.editor.active_frame is not self.old_frame:
00036                 self.make_interactive(self.editor.active_frame)
00037 
00038         if level & 4:
00039             if self.editor.active_frame is not None:
00040                 self.int_marker.name = self.editor.active_frame.name
00041                 self.int_marker.header.frame_id = self.editor.active_frame.parent
00042                 self.int_marker.pose = self.editor.active_frame.pose
00043                 self.server.insert(self.int_marker, self.callback_marker)
00044                 self.server.applyChanges()
00045 
00046 
00047     def make_interactive(self, frame):
00048 
00049         ## Stop currently active frame
00050         if self.old_frame is not None:
00051             self.server.erase(self.old_frame.name)
00052             self.server.applyChanges()
00053 
00054         self.old_frame = frame
00055 
00056         if frame is not None:
00057             self.set_marker_settings(["x", "y", "z", "a", "b", "c"], frame)
00058 
00059             self.int_marker.name = frame.name
00060             self.int_marker.header.frame_id = frame.parent
00061             self.int_marker.pose = frame.pose
00062 
00063             self.server.insert(self.int_marker, self.callback_marker)
00064             self.server.applyChanges()
00065 
00066 
00067     def callback_marker(self, feedback):
00068         self.editor.command(Command_SetPose(self.editor, self.editor.active_frame, FromPoint(feedback.pose.position), FromQuaternion(feedback.pose.orientation)))
00069 
00070 
00071     def set_marker_settings(self, arrows, frame=None, scale=0.25):
00072         '''arrows is a list with any number of the following strings: ["x", "y", "z", "a", "b", "c"].'''
00073 
00074         if frame:
00075             style = frame.style
00076         else:
00077             style = "none"
00078 
00079         ## Marker
00080         int_marker = InteractiveMarker()
00081         int_marker.header.frame_id = ""
00082         int_marker.name = ""
00083         int_marker.description = "Frame Editor"
00084         int_marker.pose = Pose()
00085         int_marker.scale = scale
00086 
00087         if "x" in arrows:
00088             control = InteractiveMarkerControl()
00089             control.name = "move_x"
00090             control.orientation = NewQuaternion(1, 0, 0, 1)
00091             control.interaction_mode = InteractiveMarkerControl.MOVE_AXIS
00092             int_marker.controls.append(control);
00093 
00094         if "y" in arrows:
00095             control = InteractiveMarkerControl()
00096             control.name = "move_y"
00097             control.orientation = NewQuaternion(0, 1, 0, 1)
00098             control.interaction_mode = InteractiveMarkerControl.MOVE_AXIS
00099             int_marker.controls.append(control);
00100 
00101         if "z" in arrows:
00102             control = InteractiveMarkerControl()
00103             control.name = "move_z"
00104             control.orientation = NewQuaternion(0, 0, 1, 1)
00105             control.interaction_mode = InteractiveMarkerControl.MOVE_AXIS
00106             int_marker.controls.append(control);
00107 
00108         if "a" in arrows:
00109             control = InteractiveMarkerControl()
00110             control.name = "rotate_x"
00111             control.orientation = NewQuaternion(1, 0, 0, 1)
00112             control.interaction_mode = InteractiveMarkerControl.ROTATE_AXIS
00113             int_marker.controls.append(control);
00114 
00115         if "b" in arrows:
00116             control = InteractiveMarkerControl()
00117             control.name = "rotate_y"
00118             control.orientation = NewQuaternion(0, 1, 0, 1)
00119             control.interaction_mode = InteractiveMarkerControl.ROTATE_AXIS
00120             int_marker.controls.append(control);
00121 
00122 
00123         if "c" in arrows:
00124             control = InteractiveMarkerControl()
00125             control.name = "rotate_z"
00126             control.orientation = NewQuaternion(0, 0, 1, 1)
00127             control.interaction_mode = InteractiveMarkerControl.ROTATE_AXIS
00128             int_marker.controls.append(control);
00129 
00130 
00131         ## Style ##
00132         ##
00133         #style_marker = Marker()
00134         #style_marker.scale = NewVector3(0.75*scale, 0.75*scale, 0.75*scale)
00135         #style_marker.color = NewColor(0.0, 0.5, 0.5, 0.75)
00136 
00137         #if style != "none":
00138         #    style_marker = frame.marker
00139 
00140         #style_control = InteractiveMarkerControl()
00141         #style_control.always_visible = True
00142         #style_control.markers.append(style_marker)
00143 
00144         #if style != "none":
00145         #    int_marker.controls.append(style_control)
00146 
00147 
00148         self.int_marker = int_marker
00149 
00150 # eof


frame_editor
Author(s): ipa-frn
autogenerated on Sat Jun 8 2019 20:21:35