Skip to content

Al5D Support #287

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 4 commits into from
Apr 7, 2022
Merged
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
118 changes: 118 additions & 0 deletions roboticstoolbox/models/DH/AL5D.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,118 @@
"""
@author: Tassos Natsakis
"""

import numpy as np
from roboticstoolbox import DHRobot, RevoluteMDH
from spatialmath import SE3

class AL5D(DHRobot):
"""
Class that models a Lynxmotion AL5D manipulator

:param symbolic: use symbolic constants
:type symbolic: bool

``AL5D()`` is an object which models a Lynxmotion AL5D robot and
describes its kinematic and dynamic characteristics using modified DH
conventions.

.. runblock:: pycon

>>> import roboticstoolbox as rtb
>>> robot = rtb.models.DH.AL5D()
>>> print(robot)

Defined joint configurations are:

- qz, zero joint angle configuration

.. note::
- SI units are used.

:References:

- 'Reference of the robot <http://www.lynxmotion.com/c-130-al5d.aspx>'_

.. codeauthor:: Tassos Natsakis
""" # noqa

def __init__(self, symbolic=False):

if symbolic:
import spatialmath.base.symbolic as sym
zero = sym.zero()
pi = sym.pi()
else:
from math import pi
zero = 0.0

# robot length values (metres)
a = [0, 0.002, 0.14679, 0.17751]
d = [-0.06858, 0, 0, 0]

alpha = [pi, pi/2, pi, pi]
offset = [pi/2, pi, -0.0427, -0.0427-pi/2]

# mass data as measured
mass = [0.187, 0.044, 0.207, 0.081]

# center of mass as calculated through CAD model
center_of_mass = [
[0.01724, -0.00389, 0.00468],
[0.07084, 0.00000, 0.00190],
[0.05615, -0.00251, -0.00080],
[0.04318, 0.00735, -0.00523],
]

# moments of inertia are practically zero
moments_of_inertia = [
[0, 0, 0, 0, 0, 0],
[0, 0, 0, 0, 0, 0],
[0, 0, 0, 0, 0, 0],
[0, 0, 0, 0, 0, 0]
]

joint_limits = [
[-pi/2, pi/2],
[-pi/2, pi/2],
[-pi,2, pi/2],
[-pi/2, pi/2],
]

links = []

for j in range(4):
link = RevoluteMDH(
d=d[j],
a=a[j],
alpha=alpha[j],
offset=offset[j],
r=center_of_mass[j],
I=moments_of_inertia[j],
G=1,
B=0,
Tc=[0,0],
qlim=joint_limits[j]
)
links.append(link)

tool=SE3(0.07719,0,0)

super().__init__(
links,
name="AL5D",
manufacturer="Lynxmotion",
keywords=('dynamics', 'symbolic'),
symbolic=symbolic,
tool=tool
)

# zero angles
self.addconfiguration("home", np.array([pi/2, pi/2, pi/2, pi/2]))

if __name__ == '__main__': # pragma nocover

al5d = AL5D(symbolic=False)
print(al5d)
print(al5d.dyntable())
2 changes: 2 additions & 0 deletions roboticstoolbox/models/DH/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
from roboticstoolbox.models.DH.TwoLink import TwoLink
from roboticstoolbox.models.DH.Hyper3d import Hyper3d
from roboticstoolbox.models.DH.P8 import P8
from roboticstoolbox.models.DH.AL5D import AL5D


__all__ = [
Expand All @@ -47,4 +48,5 @@
'Baxter',
'TwoLink',
'P8',
'AL5D',
]
53 changes: 53 additions & 0 deletions roboticstoolbox/models/URDF/AL5D.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
#!/usr/bin/env python

import numpy as np
from roboticstoolbox.robot.ERobot import ERobot
from math import pi

class AL5D(ERobot):
"""
Class that imports a AL5D URDF model

``AL5D()`` is a class which imports a Lynxmotion AL5D robot definition
from a URDF file. The model describes its kinematic and graphical
characteristics.

.. runblock:: pycon

>>> import roboticstoolbox as rtb
>>> robot = rtb.models.URDF.AL5D()
>>> print(robot)

Defined joint configurations are:

- qz, zero joint angle configuration, 'L' shaped configuration
- up, robot poiting upwards

.. codeauthor:: Tassos Natsakis
"""

def __init__(self):

links, name, urdf_string, urdf_filepath = self.URDF_read(
"al5d_description/urdf/al5d_robot.urdf"
)

super().__init__(
links,
name=name,
urdf_string=urdf_string,
urdf_filepath=urdf_filepath,
)

self.manufacturer = "Lynxmotion"

# zero angles, upper arm pointing up, lower arm straight ahead
self.addconfiguration("qz", np.array([0, 0, 0, 0]))

# reference pose robot pointing upwards
self.addconfiguration("up", np.array([0.0000, 0.0000, 1.5707, 0.0000]))

if __name__ == "__main__": # pragma nocover

robot = AL5D()
print(robot)
2 changes: 2 additions & 0 deletions roboticstoolbox/models/URDF/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
from roboticstoolbox.models.URDF.LBR import LBR
from roboticstoolbox.models.URDF.KinovaGen3 import KinovaGen3
from roboticstoolbox.models.URDF.YuMi import YuMi
from roboticstoolbox.models.URDF.AL5D import AL5D

__all__ = [
"Panda",
Expand All @@ -42,4 +43,5 @@
"LBR",
"KinovaGen3",
"YuMi",
"AL5D",
]
Binary file added rtb-data/rtbdata/meshes/Lynxmotion/AL5D/base.stl
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file added rtb-data/rtbdata/meshes/Lynxmotion/AL5D/link4.stl
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
115 changes: 115 additions & 0 deletions rtb-data/rtbdata/xacro/al5d_description/urdf/al5d_robot.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,115 @@
<?xml version="1.0" ?>
<robot name="AL5D" xmlns:xacro="http://www.ros.org/wiki/xacro">
<material name="gray">
<color rgba="0.8 0.8 0.8 0.9"/>
</material>
<material name="black">
<color rgba="0.3 0.3 0.3 0.9"/>
</material>

<link name="base">
<visual>
<geometry>
<mesh filename="package://al5d_description/meshes/base.stl" scale="0.001 0.001 0.001"/>
</geometry>
<origin rpy="0 0 0"/>
<material name="black"/>
</visual>
<inertial>
<mass value="0.092"/>
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
</link>

<link name="link1">
<visual>
<geometry>
<mesh filename="package://al5d_description/meshes/link1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="black"/>
</visual>
<inertial>
<mass value="0.187"/>
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
</link>

<link name="link2">
<visual>
<geometry>
<mesh filename="package://al5d_description/meshes/link2.stl" scale="0.001 0.001 0.001"/>
</geometry>
<origin xyz="0 0 0"/>
<material name="gray"/>
</visual>
<inertial>
<mass value="0.044"/>
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
</link>

<link name="link3">
<visual>
<geometry>
<mesh filename="package://al5d_description/meshes/link3.stl" scale="0.001 0.001 0.001"/>
</geometry>
<origin rpy="0 0 -0.0427" xyz="0 0 0"/>
<material name="gray"/>
</visual>
<inertial>
<mass value="0.207"/>
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
</link>

<link name="link4">
<visual>
<geometry>
<mesh filename="package://al5d_description/meshes/link4.stl" scale="0.001 0.001 0.001"/>
</geometry>
<origin rpy="0 0 1.528096327" xyz="0 0 0"/>
<material name="black"/>
</visual>
<inertial>
<mass value="0.081"/>
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
</link>

<joint name="j1" type="revolute">
<parent link="base"/>
<child link="link1"/>
<origin rpy="0 3.141592653 0" xyz="0 0 0.06858"/>
<axis xyz="0 0 1"/>
<!-- This is descibed in child frame -->
<limit effort="1000.0" lower="-1.570796325" upper="1.570796325" velocity="0"/>
</joint>

<joint name="j2" type="revolute">
<parent link="link1"/>
<child link="link2"/>
<origin rpy="0 1.570796325 -1.570796325" xyz="0.002 0 0"/>
<axis xyz="0 0 1"/>
<!-- This is descibed in child frame -->
<limit effort="1000.0" lower="-1.570796325" upper="1.570796325" velocity="0"/>
</joint>

<joint name="j3" type="revolute">
<parent link="link2"/>
<child link="link3"/>
<origin rpy="0 3.141592653 1.570796325" xyz="0.14679 0 0"/>
<axis xyz="0 0 1"/>
<!-- This is descibed in child frame -->
<limit effort="1000.0" lower="-1.570796325" upper="1.570796325" velocity="0"/>
</joint>

<joint name="j4" type="revolute">
<parent link="link3"/>
<child link="link4"/>
<origin rpy="3.141592653 0 1.570796325" xyz="0.17751 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="1000.0" lower="-1.570796325" upper="1.570796325" velocity="0"/>
</joint>
</robot>