interactive_marker.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import rospy
4 import tf.transformations
5 import numpy as np
6 
7 from interactive_markers.interactive_marker_server import \
8  InteractiveMarkerServer, InteractiveMarkerFeedback
9 from visualization_msgs.msg import InteractiveMarker, \
10  InteractiveMarkerControl
11 from geometry_msgs.msg import PoseStamped
12 from franka_msgs.msg import FrankaState
13 
14 marker_pose = PoseStamped()
15 pose_pub = None
16 # [[min_x, max_x], [min_y, max_y], [min_z, max_z]]
17 position_limits = [[-0.6, 0.6], [-0.6, 0.6], [0.05, 0.9]]
18 
19 
20 def publisher_callback(msg, link_name):
21  marker_pose.header.frame_id = link_name
22  marker_pose.header.stamp = rospy.Time(0)
23  pose_pub.publish(marker_pose)
24 
25 
26 def process_feedback(feedback):
27  if feedback.event_type == InteractiveMarkerFeedback.POSE_UPDATE:
28  marker_pose.pose.position.x = max([min([feedback.pose.position.x,
29  position_limits[0][1]]),
30  position_limits[0][0]])
31  marker_pose.pose.position.y = max([min([feedback.pose.position.y,
32  position_limits[1][1]]),
33  position_limits[1][0]])
34  marker_pose.pose.position.z = max([min([feedback.pose.position.z,
35  position_limits[2][1]]),
36  position_limits[2][0]])
37  marker_pose.pose.orientation = feedback.pose.orientation
38  server.applyChanges()
39 
40 
42  msg = rospy.wait_for_message("franka_state_controller/franka_states",
43  FrankaState) # type: FrankaState
44 
45  initial_quaternion = \
46  tf.transformations.quaternion_from_matrix(
47  np.transpose(np.reshape(msg.O_T_EE,
48  (4, 4))))
49  initial_quaternion = initial_quaternion / \
50  np.linalg.norm(initial_quaternion)
51  marker_pose.pose.orientation.x = initial_quaternion[0]
52  marker_pose.pose.orientation.y = initial_quaternion[1]
53  marker_pose.pose.orientation.z = initial_quaternion[2]
54  marker_pose.pose.orientation.w = initial_quaternion[3]
55  marker_pose.pose.position.x = msg.O_T_EE[12]
56  marker_pose.pose.position.y = msg.O_T_EE[13]
57  marker_pose.pose.position.z = msg.O_T_EE[14]
58 
59 
60 if __name__ == "__main__":
61  rospy.init_node("equilibrium_pose_node")
62  listener = tf.TransformListener()
63  link_name = rospy.get_param("~link_name")
64 
66 
67  pose_pub = rospy.Publisher(
68  "equilibrium_pose", PoseStamped, queue_size=10)
69  server = InteractiveMarkerServer("equilibrium_pose_marker")
70  int_marker = InteractiveMarker()
71  int_marker.header.frame_id = link_name
72  int_marker.scale = 0.3
73  int_marker.name = "equilibrium_pose"
74  int_marker.description = ("Equilibrium Pose\nBE CAREFUL! "
75  "If you move the \nequilibrium "
76  "pose the robot will follow it\n"
77  "so be aware of potential collisions")
78  int_marker.pose = marker_pose.pose
79  # run pose publisher
80  rospy.Timer(rospy.Duration(0.005),
81  lambda msg: publisher_callback(msg, link_name))
82 
83  # insert a box
84  control = InteractiveMarkerControl()
85  control.orientation.w = 1
86  control.orientation.x = 1
87  control.orientation.y = 0
88  control.orientation.z = 0
89  control.name = "rotate_x"
90  control.interaction_mode = InteractiveMarkerControl.ROTATE_AXIS
91  int_marker.controls.append(control)
92 
93  control = InteractiveMarkerControl()
94  control.orientation.w = 1
95  control.orientation.x = 1
96  control.orientation.y = 0
97  control.orientation.z = 0
98  control.name = "move_x"
99  control.interaction_mode = InteractiveMarkerControl.MOVE_AXIS
100  int_marker.controls.append(control)
101  control = InteractiveMarkerControl()
102  control.orientation.w = 1
103  control.orientation.x = 0
104  control.orientation.y = 1
105  control.orientation.z = 0
106  control.name = "rotate_y"
107  control.interaction_mode = InteractiveMarkerControl.ROTATE_AXIS
108  int_marker.controls.append(control)
109  control = InteractiveMarkerControl()
110  control.orientation.w = 1
111  control.orientation.x = 0
112  control.orientation.y = 1
113  control.orientation.z = 0
114  control.name = "move_y"
115  control.interaction_mode = InteractiveMarkerControl.MOVE_AXIS
116  int_marker.controls.append(control)
117  control = InteractiveMarkerControl()
118  control.orientation.w = 1
119  control.orientation.x = 0
120  control.orientation.y = 0
121  control.orientation.z = 1
122  control.name = "rotate_z"
123  control.interaction_mode = InteractiveMarkerControl.ROTATE_AXIS
124  int_marker.controls.append(control)
125  control = InteractiveMarkerControl()
126  control.orientation.w = 1
127  control.orientation.x = 0
128  control.orientation.y = 0
129  control.orientation.z = 1
130  control.name = "move_z"
131  control.interaction_mode = InteractiveMarkerControl.MOVE_AXIS
132  int_marker.controls.append(control)
133  server.insert(int_marker, process_feedback)
134 
135  server.applyChanges()
136 
137  rospy.spin()
def publisher_callback(msg, link_name)
def process_feedback(feedback)


franka_example_controllers
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 03:06:01