pybotics.robot module

Robot module.

class pybotics.robot.Robot(kinematic_chain: pybotics.kinematic_chain.KinematicChain, tool: pybotics.tool.Tool = NOTHING, world_frame: numpy.ndarray[Any, numpy.dtype[numpy.float64]] = NOTHING, random_state: numpy.random.mtrand.RandomState = NOTHING, home_position: numpy.ndarray[Any, numpy.dtype[numpy.float64]] = NOTHING, joints: numpy.ndarray[Any, numpy.dtype[numpy.float64]] = NOTHING, joint_limits: numpy.ndarray[Any, numpy.dtype[numpy.float64]] = NOTHING)[source]

Bases: collections.abc.Sized, typing.Generic

Robot manipulator class.

clamp_joints(q: numpy.ndarray[Any, numpy.dtype[numpy.float64]]) → numpy.ndarray[Any, numpy.dtype[numpy.float64]][source]

Limit joints to joint limits.

compute_joint_torques(wrench: numpy.ndarray[Any, numpy.dtype[numpy.float64]], q: Optional[numpy.ndarray[Any, numpy.dtype[numpy.float64]]] = None) → numpy.ndarray[Any, numpy.dtype[numpy.float64]][source]

Calculate the joint torques due to external flange force.

Method from: 5.9 STATIC FORCES IN MANIPULATORS Craig, John J. Introduction to robotics: mechanics and control. Vol. 3. Upper Saddle River: Pearson Prentice Hall, 2005. :param wrench: :param q: :return:

fk(q: Optional[numpy.ndarray[Any, numpy.dtype[numpy.float64]]] = None) → numpy.ndarray[Any, numpy.dtype[numpy.float64]][source]

Compute the forward kinematics of a given position.

Uses the current position if None is given. :param q: :return: 4x4 transform matrix of the FK pose

classmethod from_parameters(parameters: numpy.ndarray[Any, numpy.dtype[numpy.float64]]) → pybotics.robot.Robot[source]

Construct Robot from Kinematic Chain parameters.

ik(pose: numpy.ndarray[Any, numpy.dtype[numpy.float64]], q: Optional[numpy.ndarray[Any, numpy.dtype[numpy.float64]]] = None) → Optional[numpy.ndarray[Any, numpy.dtype[numpy.float64]]][source]

Solve the inverse kinematics.

jacobian_flange(q: Optional[numpy.ndarray[Any, numpy.dtype[numpy.float64]]] = None) → numpy.ndarray[Any, numpy.dtype[numpy.float64]][source]

Calculate the Jacobian wrt the flange frame.

jacobian_world(q: Optional[numpy.ndarray[Any, numpy.dtype[numpy.float64]]] = None) → numpy.ndarray[Any, numpy.dtype[numpy.float64]][source]

Calculate the Jacobian wrt the world frame.

joint_limits

Limits of the robot position (e.g., joint limits).

Returns:limits with shape (2,num_dof) where first row is upper limits
joints

Get the robot configuration (e.g., joint positions for serial robot).

Returns:robot position
ndof

Get the number of degrees of freedom.

Returns:number of degrees of freedom
random_joints(in_place: bool = False) → Optional[numpy.ndarray[Any, numpy.dtype[numpy.float64]]][source]

Generate random joints within limits.

to_json() → str[source]

Encode robot model as JSON.