Skip to content

Commit 3b33832

Browse files
felixvdAbishalini
authored andcommitted
Add Python2 compatibility (moveit#618)
1 parent 875c93e commit 3b33832

File tree

1 file changed

+4
-3
lines changed

1 file changed

+4
-3
lines changed

doc/move_group_python_interface/scripts/move_group_python_interface_tutorial.py

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -51,12 +51,13 @@
5151
import moveit_commander
5252
import moveit_msgs.msg
5353
import geometry_msgs.msg
54-
from math import pi, dist, fabs, cos
5554
try:
56-
from math import tau
55+
from math import pi, tau, dist, fabs, cos
5756
except: # For Python 2 compatibility
58-
from math import pi
57+
from math import pi, fabs, cos, sqrt
5958
tau = 2.0*pi
59+
def dist(p, q):
60+
return sqrt(sum((p_i - q_i)**2.0 for p_i, q_i in zip(p,q)))
6061
from std_msgs.msg import String
6162
from moveit_commander.conversions import pose_to_list
6263
## END_SUB_TUTORIAL

0 commit comments

Comments
 (0)