Skip to content

Commit ace04f0

Browse files
committed
removed homogenous points
1 parent 7cb3abc commit ace04f0

File tree

5 files changed

+361
-258
lines changed

5 files changed

+361
-258
lines changed

roboticstoolbox/models/URDF/Frankie.py

Lines changed: 27 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22

33
import numpy as np
44
from roboticstoolbox.robot.ERobot import ERobot
5+
from spatialmath import SE3
56

67

78
class Frankie(ERobot):
@@ -28,31 +29,43 @@ class Frankie(ERobot):
2829
.. codeauthor:: Jesse Haviland
2930
.. sectionauthor:: Peter Corke
3031
"""
32+
3133
def __init__(self):
3234

3335
links, name = self.URDF_read(
34-
"franka_description/robots/frankie_arm_hand.urdf.xacro")
36+
"franka_description/robots/frankie_arm_hand.urdf.xacro"
37+
)
3538

3639
super().__init__(
37-
links,
38-
name=name,
39-
manufacturer='Franka Emika',
40-
gripper_links=links[11]
40+
links, name=name, manufacturer="Franka Emika", gripper_links=links[11]
4141
)
4242

43-
self.qdlim = np.array([
44-
4.0, 4.0,
45-
2.1750, 2.1750, 2.1750, 2.1750, 2.6100, 2.6100, 2.6100,
46-
3.0, 3.0])
43+
self.grippers[0].tool = SE3(0, 0, 0.1034)
44+
45+
self.qdlim = np.array(
46+
[4.0, 4.0, 2.1750, 2.1750, 2.1750, 2.1750, 2.6100, 2.6100, 2.6100, 3.0, 3.0]
47+
)
4748

48-
self.addconfiguration("qz", np.array(
49-
[0, 0, 0, 0, 0, 0, 0, 0, 0]))
49+
self.addconfiguration("qz", np.array([0, 0, 0, 0, 0, 0, 0, 0, 0]))
5050

51-
self.addconfiguration("qr", np.array(
52-
[0, 0, 0, -0.3, 0, -2.2, 0, 2.0, np.pi/4]))
51+
self.addconfiguration(
52+
"qr", np.array([0, 0, 0, -0.3, 0, -2.2, 0, 2.0, np.pi / 4])
53+
)
5354

5455

55-
if __name__ == '__main__': # pragma nocover
56+
if __name__ == "__main__": # pragma nocover
5657

5758
robot = Frankie()
5859
print(robot)
60+
61+
for link in robot.links:
62+
print(link.name)
63+
print(link.isjoint)
64+
print(len(link.collision))
65+
66+
print()
67+
68+
for link in robot.grippers[0].links:
69+
print(link.name)
70+
print(link.isjoint)
71+
print(len(link.collision))

roboticstoolbox/robot/ERobot.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2029,7 +2029,7 @@ def link_collision_damper(
20292029
bin = None
20302030

20312031
def indiv_calculation(link, link_col, q):
2032-
d, wTlp, wTcp = link_col.closest_point(shape, di, homogenous=False)
2032+
d, wTlp, wTcp = link_col.closest_point(shape, di)
20332033

20342034
if d is not None:
20352035
lpTcp = -wTlp + wTcp

0 commit comments

Comments
 (0)