Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 5 additions & 4 deletions roboticstoolbox/models/URDF/UR10.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,14 +29,15 @@ class UR10(ERobot):

def __init__(self):

args = super().urdf_to_ets_args(
elinks, name = super().urdf_to_ets_args(
"ur_description/urdf/ur10_joint_limited_robot.urdf.xacro"
)

super().__init__(
args[0],
name=args[1],
manufacturer='Universal Robotics'
elinks,
name=name,
manufacturer='Universal Robotics',
gripper_links=elinks[7]
)

self.addconfiguration(
Expand Down
9 changes: 5 additions & 4 deletions roboticstoolbox/models/URDF/UR3.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,13 +28,14 @@ class UR3(ERobot):
"""
def __init__(self):

args = self.urdf_to_ets_args(
elinks, name = self.urdf_to_ets_args(
"ur_description/urdf/ur3_joint_limited_robot.urdf.xacro")

super().__init__(
args[0],
name=args[1],
manufacturer='Universal Robotics'
elinks,
name=name,
manufacturer='Universal Robotics',
gripper_links=elinks[7]
)

self.addconfiguration("qz", np.array([0, 0, 0, 0, 0, 0]))
Expand Down
9 changes: 5 additions & 4 deletions roboticstoolbox/models/URDF/UR5.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,13 +29,14 @@ class UR5(ERobot):

def __init__(self):

args = super().urdf_to_ets_args(
elinks, name = super().urdf_to_ets_args(
"ur_description/urdf/ur5_joint_limited_robot.urdf.xacro")

super().__init__(
args[0],
name=args[1],
manufacturer='Universal Robotics'
elinks,
name=name,
manufacturer='Universal Robotics',
gripper_links=elinks[7]
)

self.addconfiguration("qz", np.array([0, 0, 0, 0, 0, 0]))
Expand Down
6 changes: 6 additions & 0 deletions tests/test_models.py
Original file line number Diff line number Diff line change
Expand Up @@ -166,6 +166,12 @@ def test_ikine_a_puma(self):
nt.assert_array_almost_equal(sol0.q, qr0, decimal=4)
nt.assert_array_almost_equal(sol1.q, qr1, decimal=4)

def test_fkine_urdf(self):
for model_name in rp.models.URDF.__all__:
m = getattr(rp.models.URDF, model_name)
r = m()
r.fkine(r.q)

if __name__ == '__main__': # pragma nocover
unittest.main()
# pytest.main(['tests/test_SerialLink.py'])