3 from visualization_msgs.msg
import Marker, InteractiveMarker, InteractiveMarkerControl
4 from geometry_msgs.msg
import Pose, Point, Quaternion
6 import pyexotica
as exo
8 __all__ = [
'TargetMarker']
12 return Pose(Point(x = p[0], y = p[1], z = p[2]), Quaternion(x = 0., y = 0., z = 0., w = 1.))
14 return Pose(Point(x = p[0], y = p[1], z = p[2]), Quaternion(x = p[3], y = p[4], z = p[5], w = p[6]))
16 raise RuntimeError(
'Invalid transform!')
20 def __init__(self, pose=[0, 0, 0, 0, 0, 0, 1],
22 server_name=
'target_marker',
23 frame_id=
'exotica/world_frame',
24 marker_shape=Marker.ARROW,
25 marker_size=[0.2, 0.05, 0.05],
26 marker_color=[0.0, 0.5, 0.5, 1.0],
29 controls_translate=
True):
34 self.int_marker.header.frame_id = frame_id
35 self.int_marker.name = server_name
36 self.int_marker.description = description
40 kdl.Rotation.Quaternion(self.int_marker.pose.orientation.x, self.int_marker.pose.orientation.y, self.int_marker.pose.orientation.z, self.int_marker.pose.orientation.w),
41 kdl.Vector(self.int_marker.pose.position.x, self.int_marker.pose.position.y, self.int_marker.pose.position.z))
44 visual_marker = Marker()
45 visual_marker.type = marker_shape
46 if len(marker_size) != 3:
47 raise RuntimeError(
"Length of marker_size needs to be 3.")
48 visual_marker.scale.x = marker_size[0]
49 visual_marker.scale.y = marker_size[1]
50 visual_marker.scale.z = marker_size[2]
51 if len(marker_color) != 4:
52 raise RuntimeError(
"Length of marker_color needs to be 4.")
53 visual_marker.color.r = marker_color[0]
54 visual_marker.color.g = marker_color[1]
55 visual_marker.color.b = marker_color[2]
56 visual_marker.color.a = marker_color[3]
59 visual_control = InteractiveMarkerControl()
60 visual_control.always_visible =
True 61 visual_control.markers.append( visual_marker )
64 self.int_marker.controls.append( visual_control )
67 self.
addControl([1, 0, 0], InteractiveMarkerControl.ROTATE_AXIS)
68 self.
addControl([0, 1, 0], InteractiveMarkerControl.ROTATE_AXIS)
69 self.
addControl([0, 0, 1], InteractiveMarkerControl.ROTATE_AXIS)
70 if controls_translate:
71 self.
addControl([1, 0, 0], InteractiveMarkerControl.MOVE_AXIS)
72 self.
addControl([0, 1, 0], InteractiveMarkerControl.MOVE_AXIS)
73 self.
addControl([0, 0, 1], InteractiveMarkerControl.MOVE_AXIS)
75 for control
in controls:
76 self.int_marker.controls.append(control)
79 self.server.applyChanges()
82 control = InteractiveMarkerControl()
83 quat = exo.KDLFrame([0, 0, 0] + direction + [1]).get_quaternion()
84 control.orientation.x = quat[0]
85 control.orientation.y = quat[1]
86 control.orientation.z = quat[2]
87 control.orientation.w = quat[3]
88 control.interaction_mode = control_type
89 self.int_marker.controls.append(control)
93 kdl.Rotation.Quaternion(feedback.pose.orientation.x, feedback.pose.orientation.y, feedback.pose.orientation.z, feedback.pose.orientation.w),
94 kdl.Vector(feedback.pose.position.x, feedback.pose.position.y, feedback.pose.position.z))
95 self.
position_exo = exo.KDLFrame([feedback.pose.position.x, feedback.pose.position.y, feedback.pose.position.z,
96 feedback.pose.orientation.x, feedback.pose.orientation.y, feedback.pose.orientation.z, feedback.pose.orientation.w])
def __init__(self, pose=[0, description='Target', server_name='target_marker', frame_id='exotica/world_frame', marker_shape=Marker.ARROW, marker_size=[0.2, marker_color=[0.0, controls=[], controls_rotate=True, controls_translate=True)
def addControl(self, direction, control_type)
def process_feedback(self, feedback)