skrobot.interfaces._pybullet.PybulletRobotInterface¶
- class skrobot.interfaces._pybullet.PybulletRobotInterface(robot, urdf_path=None, use_fixed_base=False, connect=1, *args, **kwargs)[source]¶
Pybullet Interface Class
- Parameters:
robot (skrobot.model.RobotModel) – robot model
urdf_path (None or str) – urdf path. If this value is None, get urdf_path from robot.urdf_path.
use_fixed_base (bool) – If this value is True, robot in pybullet simulator will be fixed.
connect (int) – pybullet’s connection mode. If you have already connected to pybullet physics server, specify the server id. The default value is 1 (pybullet.GUI).
Examples
>>> from skrobot.models import PR2 >>> from skrobot.interfaces import PybulletRobotInterface >>> robot_model = PR2() >>> interface = PybulletRobotInterface(robot_model)
If you have already connected to pybullet physics server
>>> import pybullet >>> client_id = pybullet.connect(pybullet.GUI) >>> robot_model = PR2() >>> interface = PybulletRobotInterface(robot_model, connect=client_id)
Methods
- T()[source]¶
Return 4x4 homogeneous transformation matrix.
- Returns:
matrix – homogeneous transformation matrix shape of (4, 4)
- Return type:
Examples
>>> from numpy import pi >>> from skrobot.coordinates import make_coords >>> c = make_coords() >>> c.T() array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]]) >>> c.translate([0.1, 0.2, 0.3]) >>> c.rotate(pi / 2.0, 'y') array([[ 2.22044605e-16, 0.00000000e+00, 1.00000000e+00, 1.00000000e-01], [ 0.00000000e+00, 1.00000000e+00, 0.00000000e+00, 2.00000000e-01], [-1.00000000e+00, 0.00000000e+00, 2.22044605e-16, 3.00000000e-01], [ 0.00000000e+00, 0.00000000e+00, 0.00000000e+00, 1.00000000e+00]])
- angle_vector(angle_vector=None, realtime_simulation=None)[source]¶
Send a angle vector to pybullet’s phsyics engine.
- Parameters:
angle_vector (None or numpy.ndarray) – angle vector. If None, send self.robot.angle_vector()
realtime_simulation (None or bool) – If this value is True, send angle_vector by pybullet.setJointMotorControl2.
- Returns:
angle_vector – return sent angle vector.
- Return type:
- static available()[source]¶
Check Pybullet is available.
- Returns:
_available – If False, pybullet is not available.
- Return type:
- changed()[source]¶
Return False
This is used for CascadedCoords compatibility
- Returns:
False – always return False
- Return type:
- difference_position(coords, translation_axis=True)[source]¶
Return differences in positoin of given coords.
- Parameters:
coords (skrobot.coordinates.Coordinates) – given coordinates
translation_axis (str or bool or None (optional)) – we can take ‘x’, ‘y’, ‘z’, ‘xy’, ‘yz’, ‘zx’, ‘xx’, ‘yy’, ‘zz’, True or False(None).
- Returns:
dif_pos – difference position of self coordinates and coords considering translation_axis.
- Return type:
Examples
>>> from skrobot.coordinates import Coordinates >>> from skrobot.coordinates import transform_coords >>> from numpy import pi >>> c1 = Coordinates().translate([0.1, 0.2, 0.3]).rotate( ... pi / 3.0, 'x') >>> c2 = Coordinates().translate([0.3, -0.3, 0.1]).rotate( ... pi / 2.0, 'y') >>> c1.difference_position(c2) array([ 0.2 , -0.42320508, 0.3330127 ]) >>> c1 = Coordinates().translate([0.1, 0.2, 0.3]).rotate(0, 'x') >>> c2 = Coordinates().translate([0.3, -0.3, 0.1]).rotate( ... pi / 3.0, 'x') >>> c1.difference_position(c2) array([ 0.2, -0.5, -0.2])
- difference_rotation(coords, rotation_axis=True)[source]¶
Return differences in rotation of given coords.
- Parameters:
coords (skrobot.coordinates.Coordinates) – given coordinates
rotation_axis (str or bool or None (optional)) – we can take ‘x’, ‘y’, ‘z’, ‘xx’, ‘yy’, ‘zz’, ‘xm’, ‘ym’, ‘zm’, ‘xy’, ‘yx’, ‘yz’, ‘zy’, ‘zx’, ‘xz’, True or False(None).
- Returns:
dif_rot – difference rotation of self coordinates and coords considering rotation_axis.
- Return type:
Examples
>>> from numpy import pi >>> from skrobot.coordinates import Coordinates >>> from skrobot.coordinates.math import rpy_matrix >>> coord1 = Coordinates() >>> coord2 = Coordinates(rot=rpy_matrix(pi / 2.0, pi / 3.0, pi / 5.0)) >>> coord1.difference_rotation(coord2) array([-0.32855112, 1.17434985, 1.05738936]) >>> coord1.difference_rotation(coord2, rotation_axis=False) array([0, 0, 0]) >>> coord1.difference_rotation(coord2, rotation_axis='x') array([0. , 1.36034952, 0.78539816]) >>> coord1.difference_rotation(coord2, rotation_axis='y') array([0.35398131, 0. , 0.97442695]) >>> coord1.difference_rotation(coord2, rotation_axis='z') array([-0.88435715, 0.74192175, 0. ])
Using mirror option [‘xm’, ‘ym’, ‘zm’], you can allow differences of mirror direction.
>>> coord1 = Coordinates() >>> coord2 = Coordinates().rotate(pi, 'x') >>> coord1.difference_rotation(coord2, 'xm') array([-2.99951957e-32, 0.00000000e+00, 0.00000000e+00]) >>> coord1 = Coordinates() >>> coord2 = Coordinates().rotate(pi / 2.0, 'x') >>> coord1.difference_rotation(coord2, 'xm') array([-1.57079633, 0. , 0. ])
- get_transform()[source]¶
Return Transform object
- Returns:
transform – corrensponding Transform to this coordinates
- Return type:
skrobot.coordinates.base.Transform
- inverse_transform_vector(vec)[source]¶
Transform vector in world coordinates to local coordinates
- Parameters:
vec (numpy.ndarray) – 3d vector. We can take batch of vector like (batch_size, 3)
- Returns:
transformed_point – transformed point
- Return type:
- inverse_transformation(dest=None)[source]¶
Return a invese transformation of this coordinate system.
Create a new coordinate with inverse transformation of this coordinate system.
\[\begin{split}\left( \begin{array}{ccc} R^{-1} & - R^{-1} p \\ 0 & 1 \end{array} \right)\end{split}\]- Parameters:
dest (None or skrobot.coordinates.Coordinates) – If dest is given, the result of transformation is in-placed to dest.
- Returns:
dest – result of inverse transformation.
- Return type:
- move_coords(target_coords, local_coords)[source]¶
Transform this coordinate so that local_coords to target_coords.
- Parameters:
target_coords (skrobot.coordinates.Coordinates) – target coords.
local_coords (skrobot.coordinates.Coordinates) – local coords to be aligned.
- Returns:
self.worldcoords() – world coordinates.
- Return type:
- orient_with_matrix(rotation_matrix, wrt='world')[source]¶
Force update this coordinate system’s rotation.
- Parameters:
rotation_matrix (numpy.ndarray) – 3x3 rotation matrix.
wrt (str or skrobot.coordinates.Coordinates) – reference coordinates.
- rotate(theta, axis=None, wrt='local')[source]¶
Rotate this robot by given theta and axis.
For more detail, please see docs of skrobot.coordinates.Coordinates.rotate. The difference between the rotate, this function internally call pybullet.resetBasePositionAndOrientation.
- Parameters:
theta (float) – radian
wrt (string or skrobot.coordinates.Coordinates) –
- rotate_vector(v)[source]¶
Rotate 3-dimensional vector using rotation of this coordinate
- Parameters:
v (numpy.ndarray) – vector shape of (3,)
- Returns:
np.matmul(self.rotation, v) – rotated vector
- Return type:
Examples
>>> from skrobot.coordinates import Coordinates >>> from numpy import pi >>> c = Coordinates().rotate(pi, 'z') >>> c.rotate_vector([1, 2, 3]) array([-1., -2., 3.])
- rotate_with_matrix(mat, wrt='local')[source]¶
Rotate this coordinate by given rotation matrix.
This is a subroutine of self.rotate function.
- Parameters:
mat (numpy.ndarray) – rotation matrix shape of (3, 3)
wrt (str or skrobot.coordinates.Coordinates) – with respect to.
- Returns:
self
- Return type:
- rpy_angle()[source]¶
Return a pair of rpy angles of this coordinates.
- Returns:
rpy_angle(self.rotation) – a pair of rpy angles. See also skrobot.coordinates.math.rpy_angle
- Return type:
Examples
>>> import numpy as np >>> from skrobot.coordinates import Coordinates >>> c = Coordinates().rotate(np.pi / 2.0, 'x').rotate(np.pi / 3.0, 'z') >>> r.rpy_angle() (array([ 3.84592537e-16, -1.04719755e+00, 1.57079633e+00]), array([ 3.14159265, -2.0943951 , -1.57079633]))
- transform(c, wrt='local')[source]¶
Transform this coordinate by coords based on wrt
For more detail, please see docs of skrobot.coordinates.Coordinates.transform. The difference between the transform, this function internally call pybullet.resetBasePositionAndOrientation.
- Parameters:
c (skrobot.coordinates.Coordinates) – coordinate
wrt (string or skrobot.coordinates.Coordinates) – If wrt is ‘local’ or self, multiply c from the right. If wrt is ‘world’ or ‘parent’ or self.parent, transform c with respect to worldcoord. If wrt is Coordinates, transform c with respect to c.
- transform_vector(v)[source]¶
“Return vector represented at world frame.
Vector v given in the local coords is converted to world representation.
- Parameters:
v (numpy.ndarray) – 3d vector. We can take batch of vector like (batch_size, 3)
- Returns:
transformed_point – transformed point
- Return type:
- translate(vec, wrt='local')[source]¶
Translate robot in simulator.
For more detail, please see docs of skrobot.coordinates.Coordinates.translate. The difference between the translate, this function internally call pybullet.resetBasePositionAndOrientation.
- Parameters:
vec (list or np.ndarray) – shape of (3,) translation vector. unit is [m] order.
wrt (string or Coordinates (optional)) – translate with respect to wrt.
- wait_interpolation(thresh=0.05, timeout=60.0)[source]¶
Wait robot movement.
This function usually called after self.angle_vector. Wait while the robot joints are moving or until time of timeout. This function called internally pybullet.stepSimulation().
- worldpos()[source]¶
Return translation of this coordinate
See also skrobot.coordinates.Coordinates.translation
- Returns:
self.translation – translation of this coordinate
- Return type:
- worldrot()[source]¶
Return rotation of this coordinate
See also skrobot.coordinates.Coordinates.rotation
- Returns:
self.rotation – rotation matrix of this coordinate
- Return type:
- __eq__(value, /)¶
Return self==value.
- __ne__(value, /)¶
Return self!=value.
- __lt__(value, /)¶
Return self<value.
- __le__(value, /)¶
Return self<=value.
- __gt__(value, /)¶
Return self>value.
- __ge__(value, /)¶
Return self>=value.
- __mul__(other_c)[source]¶
Return Transformed Coordinates.
Note that this function creates new Coordinates and does not change translation and rotation, unlike transform function.
- Parameters:
other_c (skrobot.coordinates.Coordinates) – input coordinates.
- Returns:
out – transformed coordinates multiplied other_c from the right. T = T_{self} T_{other_c}.
- Return type:
- __pow__(exponent)[source]¶
Return exponential homogeneous matrix.
If exponent equals -1, return inverse transformation of this coords.
- Parameters:
exponent (numbers.Number) – exponent value. If exponent equals -1, return inverse transformation of this coords. In current, support only -1 case.
- Returns:
out – output.
- Return type:
Attributes
- dimension¶
Return dimension of this coordinate
- Returns:
len(self.translation) – dimension of this coordinate
- Return type:
- dual_quaternion¶
Property of DualQuaternion
Return DualQuaternion representation of this coordinate.
- Returns:
DualQuaternion – DualQuaternion representation of this coordinate
- Return type:
- pose¶
Getter of Pose in pybullet phsyics simulator.
Wrapper of pybullet.getBasePositionAndOrientation.
- Returns:
pose – pose of this robot in the phsyics simulator.
- Return type:
- quaternion¶
Property of quaternion
- Returns:
q – [w, x, y, z] quaternion
- Return type:
Examples
>>> from numpy import pi >>> from skrobot.coordinates import make_coords >>> c = make_coords() >>> c.quaternion array([1., 0., 0., 0.]) >>> c.rotate(pi / 3, 'y').rotate(pi / 5, 'z') >>> c.quaternion array([0.8236391 , 0.1545085 , 0.47552826, 0.26761657])
- rotation¶
Return rotation matrix of this coordinates.
- Returns:
self._rotation – 3x3 rotation matrix
- Return type:
Examples
>>> import numpy as np >>> from skrobot.coordinates import Coordinates >>> c = Coordinates() >>> c.rotation array([[1., 0., 0.], [0., 1., 0.], [0., 0., 1.]]) >>> c.rotate(np.pi / 2.0, 'y') >>> c.rotation array([[ 2.22044605e-16, 0.00000000e+00, 1.00000000e+00], [ 0.00000000e+00, 1.00000000e+00, 0.00000000e+00], [-1.00000000e+00, 0.00000000e+00, 2.22044605e-16]])
- translation¶
Return translation of this coordinates.
- Returns:
self._translation – vector shape of (3, ). unit is [m]
- Return type:
Examples
>>> from skrobot.coordinates import Coordinates >>> c = Coordinates() >>> c.translation array([0., 0., 0.]) >>> c.translate([0.1, 0.2, 0.3]) >>> c.translation array([0.1, 0.2, 0.3])
- x_axis¶
Return x axis vector of this coordinates.
- Returns:
axis – x axis.
- Return type:
- y_axis¶
Return y axis vector of this coordinates.
- Returns:
axis – y axis.
- Return type:
- z_axis¶
Return z axis vector of this coordinates.
- Returns:
axis – z axis.
- Return type: