|
def | __init__ (self, base_link, tip_link, timeout=0.005, epsilon=1e-5, solve_type="Speed", urdf_string=None) |
|
def | get_ik (self, qinit, x, y, z, rx, ry, rz, rw, bx=1e-5, by=1e-5, bz=1e-5, brx=1e-3, bry=1e-3, brz=1e-3) |
|
def | get_joint_limits (self) |
|
def | set_joint_limits (self, lower_bounds, upper_bounds) |
|
Definition at line 10 of file trac_ik.py.
def trac_ik_python.trac_ik.IK.__init__ |
( |
|
self, |
|
|
|
base_link, |
|
|
|
tip_link, |
|
|
|
timeout = 0.005 , |
|
|
|
epsilon = 1e-5 , |
|
|
|
solve_type = "Speed" , |
|
|
|
urdf_string = None |
|
) |
| |
Create a TRAC_IK instance and keep track of it.
:param str base_link: Starting link of the chain.
:param str tip_link: Last link of the chain.
:param float timeout: Timeout in seconds for the IK calls.
:param float epsilon: Error epsilon.
:param solve_type str: Type of solver, can be:
Speed (default), Distance, Manipulation1, Manipulation2
:param urdf_string str: Optional arg, if not given URDF is taken from
the param server at /robot_description.
Definition at line 13 of file trac_ik.py.
def trac_ik_python.trac_ik.IK.get_ik |
( |
|
self, |
|
|
|
qinit, |
|
|
|
x, |
|
|
|
y, |
|
|
|
z, |
|
|
|
rx, |
|
|
|
ry, |
|
|
|
rz, |
|
|
|
rw, |
|
|
|
bx = 1e-5 , |
|
|
|
by = 1e-5 , |
|
|
|
bz = 1e-5 , |
|
|
|
brx = 1e-3 , |
|
|
|
bry = 1e-3 , |
|
|
|
brz = 1e-3 |
|
) |
| |
Do the IK call.
:param list of float qinit: Initial status of the joints as seed.
:param float x: X coordinates in base_frame.
:param float y: Y coordinates in base_frame.
:param float z: Z coordinates in base_frame.
:param float rx: X quaternion coordinate.
:param float ry: Y quaternion coordinate.
:param float rz: Z quaternion coordinate.
:param float rw: W quaternion coordinate.
:param float bx: X allowed bound.
:param float by: Y allowed bound.
:param float bz: Z allowed bound.
:param float brx: rotation over X allowed bound.
:param float bry: rotation over Y allowed bound.
:param float brz: rotation over Z allowed bound.
:return: joint values or None if no solution found.
:rtype: tuple of float.
Definition at line 49 of file trac_ik.py.
def trac_ik_python.trac_ik.IK.get_joint_limits |
( |
|
self | ) |
|
Return lower bound limits and upper bound limits for all the joints
in the order of the joint names.
Definition at line 84 of file trac_ik.py.
def trac_ik_python.trac_ik.IK.set_joint_limits |
( |
|
self, |
|
|
|
lower_bounds, |
|
|
|
upper_bounds |
|
) |
| |
Set joint limits for all the joints.
:arg list lower_bounds: List of float of the lower bound limits for
all joints.
:arg list upper_bounds: List of float of the upper bound limits for
all joints.
Definition at line 93 of file trac_ik.py.
trac_ik_python.trac_ik.IK._epsilon |
|
private |
trac_ik_python.trac_ik.IK._ik_solver |
|
private |
trac_ik_python.trac_ik.IK._solve_type |
|
private |
trac_ik_python.trac_ik.IK._timeout |
|
private |
trac_ik_python.trac_ik.IK._urdf_string |
|
private |
trac_ik_python.trac_ik.IK.base_link |
trac_ik_python.trac_ik.IK.joint_names |
trac_ik_python.trac_ik.IK.link_names |
trac_ik_python.trac_ik.IK.number_of_joints |
trac_ik_python.trac_ik.IK.tip_link |
The documentation for this class was generated from the following file: