multi_robots

Multi-robot system support.

This module defines a robot class that represents a multi robotic system with various configurations, transformations, and control mechanisms. It provides methods for controlling the robot’s movement, updating its state, handling the tool center point (TCP), managing sensors and grippers, as well as various kinematic and control strategies. The class includes support for joint and task space motion, force/torque sensor integration, and multiple motion control strategies, allowing for flexible and complex robot operations.

Key functionalities include: - Motion control in joint and task space (Cartesian, Object, Robot, World). - Force/torque sensor handling. - Gripper attachment and detachment. - Asynchronous and synchronous motion control. - Robot state and pose management. - Path planning with advanced kinematic computations. - Trajectory and null-space control.

robotblockset.multi_robots.join_robot(p1: ndarray, R1: ndarray, J1: ndarray, p2: ndarray, R2: ndarray, J2: ndarray) Tuple[ndarray, ndarray, ndarray][source]

Join two robot kinematic chains: base_1 -> EE_1 -> base_2 -> EE_2.

Parameters:
  • p1 (Vector3DType) – Position vector of robot 1 end-effector (shape: (3,)).

  • R1 (RotationMatrixType) – Rotation matrix of robot 1 end-effector (shape: (3, 3)).

  • J1 (JacobianType) – Jacobian matrix of robot 1 (shape: (6, n1)).

  • p2 (Vector3DType) – Position vector of robot 2 end-effector (shape: (3,)).

  • R2 (RotationMatrixType) – Rotation matrix of robot 2 end-effector (shape: (3, 3)).

  • J2 (JacobianType) – Jacobian matrix of robot 2 (shape: (6, n2)).

Returns:

  • x (Vector3DType) – Combined position vector (shape: (3,)).

  • R (RotationMatrixType) – Combined rotation matrix (shape: (3, 3)).

  • J (JacobianType) – Combined Jacobian matrix (shape: (6, n1 + n2)).

robotblockset.multi_robots.join_fixed_robot(p1: ndarray, R1: ndarray, p2: ndarray, R2: ndarray, J2: ndarray) Tuple[ndarray, ndarray, ndarray][source]

Join a fixed base with a robot: fixed base_1 -> fxed EE_1 -> base_2 -> EE_2.

Parameters:
  • p1 (Vector3DType) – Fixed robot position (shape: (3,)).

  • R1 (RotationMatrixType) – fixed robot orientation (shape: (3, 3)).

  • p2 (Vector3DType) – Position of robot 2 relative to its base (shape: (3,)).

  • R2 (RotationMatrixType) – Rotation matrix of robot 2 (shape: (3, 3)).

  • J2 (JacobianType) – Jacobian of robot 2 (shape: (6, n)).

Returns:

  • x (Vector3DType) – Combined position (shape: (3,)).

  • R (RotationMatrixType) – Combined orientation (shape: (3, 3)).

  • J (JacobianType) – Combined Jacobian (shape: (6, n)).

robotblockset.multi_robots.join_reverse_robot(p1: ndarray, R1: ndarray, J1: ndarray, p2: ndarray, R2: ndarray, J2: ndarray) Tuple[ndarray, ndarray, ndarray][source]

Join two robots with the structure: EE_1 -> base_1 -> base_2 -> EE_2.

Parameters:
  • p1 (Vector3DType) – Position vector of robot 1 end-effector (shape: (3,)).

  • R1 (RotationMatrixType) – Rotation matrix of robot 1 end-effector (shape: (3, 3)).

  • J1 (JacobianType) – Jacobian matrix of robot 1 (shape: (6, n1)).

  • p2 (Vector3DType) – Position vector of robot 2 end-effector (shape: (3,)).

  • R2 (RotationMatrixType) – Rotation matrix of robot 2 end-effector (shape: (3, 3)).

  • J2 (JacobianType) – Jacobian matrix of robot 2 (shape: (6, n2)).

Returns:

  • x (Vector3DType) – Combined position vector (shape: (3,)).

  • R (RotationMatrixType) – Combined orientation matrix (shape: (3, 3)).

  • J (JacobianType) – Combined Jacobian matrix (shape: (6, n1 + n2)).

robotblockset.multi_robots.join_robot_fixed(p1: ndarray, R1: ndarray, J1: ndarray, p2: ndarray, R2: ndarray) Tuple[ndarray, ndarray, ndarray][source]

Join a robot to a fixed structure: base_1 -> EE_1 > fixed base -> fixed EE.

Parameters:
  • p1 (Vector3DType) – Position of robot 1 end-effector (shape: (3,)).

  • R1 (RotationMatrixType) – Orientation matrix of robot 1 (shape: (3, 3)).

  • J1 (JacobianType) – Jacobian of robot 1 (shape: (6, n1)).

  • p2 (Vector3DType) – Fixed robot position (shape: (3,)).

  • R2 (RotationMatrixType) – Fixed robot rotation (shape: (3, 3)).

Returns:

  • x (Vector3DType) – Combined position (shape: (3,)).

  • R (RotationMatrixType) – Combined orientation (shape: (3, 3)).

  • J (JacobianType) – Combined Jacobian (shape: (6, n1)).

robotblockset.multi_robots.join_robot_reverse(p1: ndarray, R1: ndarray, J1: ndarray, p2: ndarray, R2: ndarray, J2: ndarray) Tuple[ndarray, ndarray, ndarray][source]

Join two robots in reverse: base_1 -> EE_1 -> EE_2 -> base_2.

Parameters:
  • p1 (Vector3DType) – Position vector of robot 1 end-effector (shape: (3,)).

  • R1 (RotationMatrixType) – Rotation matrix of robot 1 end-effector (shape: (3, 3)).

  • J1 (JacobianType) – Jacobian matrix of robot 1 (shape: (6, n1)).

  • p2 (Vector3DType) – Position vector of robot 2 end-effector (shape: (3,)).

  • R2 (RotationMatrixType) – Rotation matrix of robot 2 end-effector (shape: (3, 3)).

  • J2 (JacobianType) – Jacobian matrix of robot 2 (shape: (6, n2)).

Returns:

  • x (Vector3DType) – Combined position (shape: (3,)).

  • R (RotationMatrixType) – Combined orientation (shape: (3, 3)).

  • J (JacobianType) – Combined Jacobian (shape: (6, n1 + n2)).

robotblockset.multi_robots.robot_reverse(p1: ndarray, R1: ndarray, J1: ndarray) Tuple[ndarray, ndarray, ndarray][source]

Compute the reverse kinematics of a robot (from end-effector to base).

Parameters:
  • p1 (Vector3DType) – Position of the robot’s end-effector (shape: (3,)).

  • R1 (RotationMatrixType) – Rotation matrix of the robot’s end-effector (shape: (3, 3)).

  • J1 (JacobianType) – Jacobian matrix of the robot (shape: (6, n)).

Returns:

  • x (Vector3DType) – Reversed base position (shape: (3,)).

  • R (RotationMatrixType) – Reversed orientation matrix (shape: (3, 3)).

  • Jc (JacobianType) – Reversed Jacobian matrix (shape: (6, n)).

class robotblockset.multi_robots.multi_robots(robots: Tuple[robot, ...], robot_name: str | None = None, **kwargs: Any)[source]

Bases: robot

Represents a robot master class with various configurations, transformations, and control mechanisms.

Attributes:
  • Name (str) – Name of the robot.

  • tsamp (float) – Sampling rate for the robot.

  • TCP (np.ndarray) – Transformation matrix for the robot’s Tool Center Point (TCP).

  • TBase (np.ndarray) – Robot’s base pose transformation matrix (4, 4).

  • vBase (np.ndarray) – Robot’s base velocity twist (6,).

  • TObject (np.ndarray) – Transformation matrix for the object the robot manipulates.

  • TCPGripper (np.ndarray) – Transformation matrix for the robot’s gripper TCP.

  • Load (load_params) – Load associated with the robot.

  • Gripper (Optional[Any]) – Gripper object attached to the robot, if any.

  • FTSensor (Optional[Any]) – Force/Torque sensor attached to the robot, if any.

  • FTSensorFrame (np.ndarray) – Transformation matrix of the F/T sensor frame relative to the end-effector.

  • Platform (Optional[Any]) – Platform object to which the robot is attached.

  • User (Optional[Any]) – User-defined data or object.

  • Tag (Optional[Any]) – Tag associated with the robot.

Initializes combined robot system with default values and optional configurations.

Parameters:
  • robots (Tuple[robot, ...]) – Tuple[robot, …] Robots in the combined robot system.

  • robot_name (str, optional) – Name of the combined robot.

  • **kwargs (Any) – Additional keyword arguments for custom configuration or parameters.

__init__(robots: Tuple[robot, ...], robot_name: str | None = None, **kwargs: Any) None[source]

Initializes combined robot system with default values and optional configurations.

Parameters:
  • robots (Tuple[robot, ...]) – Tuple[robot, …] Robots in the combined robot system.

  • robot_name (str, optional) – Name of the combined robot.

  • **kwargs (Any) – Additional keyword arguments for custom configuration or parameters.

spatial(x: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...], shape: Tuple[int, ...] | None = None) ndarray[source]

Validates the shape of the input x and returns it in an appropriate format.

Parameters:

x (ArrayLike) – one of the following shapes: - (7,) : pose (position and quaternion) - (4, 4) : transformation matrix - (3,) : position vector - (4,) : quaternion - (3, 3) : rotation matrix - (6,) : twist (linear and angular velocity) - (3, 4) : homogeneous matrix without the last row (assumed to be 3x4)

Returns:

The input x in the validated shape, possibly modified if the shape was (3, 4).

Return type:

np.ndarray

Raises:

TypeError – If the input x does not have a valid shape.

InitObject() None[source]

Initializes the robot’s command and actual state with zeros, and sets default values for various attributes.

This method sets the initial values for joint positions, joint velocities, joint torques, end-effector pose, velocities, force/torque sensor data, control inputs, and other state variables.

Returns:

This method does not return any value. It modifies the internal state of the robot object.

Return type:

None

GetState() None[source]

Update and synchronize the internal state of the combined robot.

This method updates the joint positions, velocities, forces/torques, task space position and velocity, and the base pose of the dual robot system. It synchronizes the state of all robots and computes the combined state. The method handles the relative force computation and updates the base pose and velocity for the system.

The state synchronization occurs if the time since the last update exceeds a certain threshold, determined by the sampling rate (tsamp).

Attributes Updated: - Joint positions (self._actual.q) - Joint velocities (self._actual.qdot) - Joint torques (self._actual.trq) - Task space position (self._actual.x) - Task space velocity (self._actual.v) - Force/Torque sensor data (self._actual.FT)

Returns:

This method does not return any value. It modifies the internal state of the robot object.

Return type:

None

Notes

This method sets the following attributes: - _tt: The current time, can be retrieved using simtime(). - _last_update: The last update time, retrieved using simtime().

ResetCurrentTarget(do_move: bool = False, **kwargs: Any) int[source]

Resets the current target for the robot and optionally moves the robot to the actual configuration.

This method updates the robot’s commanded joint positions, velocities, torques, and end-effector pose to the current actual values. It also has an optional move functionality that commands the robot to move to the updated target.

Parameters:
  • do_move (bool, optional) – If True, the robot will move to the actual configuration after resetting the target. Default is False.

  • **kwargs (Any) – Additional keyword arguments passed to the GoTo_T method when do_move is True.

Returns:

A status code: - 0 if no movement is performed (i.e., do_move=False), - 88 if the movement was not executed due to active threads, - The result of the GoTo_q or GoTo_T function otherwise.

Return type:

int

Notes

This method modifies the _command and _actual states of the robot.

ResetTaskTarget() None[source]

Resets the task target for the robot based on the current commanded joint positions.

This method updates the robot’s commanded end-effector pose (_command.x) and velocity (_command.v) based on the robot’s current joint configuration.

Returns:

This method does not return any value but modifies the _command.x and _command.v attributes.

Return type:

None

isConnected() bool[source]

Checks if the robot is connected.

Returns:

True if the robot is connected, False otherwise.

Return type:

bool

isReady() bool[source]

Check if the robot is ready for operations.

This method checks the _connected attribute to determine if the robot is connected and operational.

Returns:

True if the robot is connected and ready for operations, otherwise False.

Return type:

bool

isActive() bool[source]

Check if the robot target is active.

Returns:

Indicating if the robot target is active.

Return type:

bool

inMotion() bool[source]

Check if the robot is in motion.

Returns:

True indicating the robot is excetuting motion command.

Return type:

bool

GetPose(out: str = None, task_space: str = None, kinematics: str = None, state: str = None, refresh: bool = None) ndarray[source]

Get the robot’s end-effector pose.

Parameters:
  • out (str, optional) – Output form for the pose. The default is “x” (“Pose”).

  • task_space (str, optional) – Task space frame to use. Options are “World”, “Object”, and “Robot”. The default is “World”.

  • kinematics (str, optional) – The kinematics to use. Options are “Robot” or “Calculated”. The default is “Robot”.

  • state (str, optional) – The state of the robot to use. Options are “Actual” or “Commanded”. The default is “Actual”.

  • refresh (bool, optional) – If True, the robot’s state is updated before retrieving the pose. Default is True.

Returns:

The end-effector pose in the specified form, shape varies depending on out value.

Return type:

np.ndarray

Raises:

ValueError – If the state, kinematics, or task_space options are invalid.

GetPos(out: str = 'p', task_space: str = None, kinematics: str = None, state: str = None) ndarray[source]

Get the robot’s end-effector position.

Parameters:
  • out (str, optional) – Output form for the position. The default is “p” (“Position”).

  • task_space (str, optional) – Task space frame to use. Options are “World”, “Object”, and “Robot”. The default is “World”.

  • kinematics (str, optional) – The kinematics to use. Options are “Robot” or “Calculated”. The default is “Robot”.

  • state (str, optional) – The state of the robot to use. Options are “Actual” or “Commanded”. The default is “Actual”.

Returns:

The end-effector position (3,).

Return type:

np.ndarray

Raises:

ValueError – If the out form is not “Position” or “p”.

GetOri(out: str = 'Q', task_space: str = None, kinematics: str = None, state: str = None) ndarray[source]

Get the robot’s end-effector orientation.

Parameters:
  • out (str, optional) – Output form for the orientation. Options are “Quaternion”, “Q”, “RotationMatrix”, “R”. The default is “Q” (“Quaternion”).

  • task_space (str, optional) – Task space frame to use. Options are “World”, “Object”, and “Robot”. The default is “World”.

  • kinematics (str, optional) – The kinematics to use. Options are “Robot” or “Calculated”. The default is “Robot”.

  • state (str, optional) – The state of the robot to use. Options are “Actual” or “Commanded”. The default is “Actual”.

Returns:

The end-effector orientation, either in quaternion (4,) or rotation matrix (3, 3) format.

Return type:

np.ndarray

Raises:

ValueError – If the out form is not “Quaternion”, “Q”, “RotationMatrix”, or “R”.

GetVel(out: str = None, task_space: str = None, kinematics: str = None, state: str = None, refresh: bool = None) ndarray[source]

Get robot end-effector velocity.

Parameters:
  • out (str, optional) – Output form for the velocity. Options are “Twist” (default), “Linear”, or “Angular”.

  • task_space (str, optional) – Task space frame for the velocity. Options are “World”, “Object”, or “Robot”. The default is “World”.

  • kinematics (str, optional) – The kinematics used for calculation. Options are “Robot” or “Calculated”. The default is “Robot”.

  • state (str, optional) – The state of the robot for the calculation. Options are “Actual” or “Commanded”. The default is “Actual”.

  • refresh (bool, optional) – If True, the robot’s state is updated before retrieving the velocity. Default is True.

Returns:

The end-effector velocity in the specified output form. The shape is either (6,) for the full twist or (3,) for linear or angular components.

Return type:

np.ndarray

Raises:

ValueError – If the out, task_space, or state values are not supported.

GetFT(out: str = None, source: str = None, task_space: str = None, kinematics: str = None, state: str = None, avg_time: int = 0, refresh: bool = None) ndarray[source]

Get force/torque sensor data for the robot.

Parameters:
  • out (str, optional) – Output form for the force/torque data. Options are “Wrench” (default), “Force”, or “Torque”.

  • source (str, optional) – Source of the force/torque data. Options are “External” or “Robot”. The default is “Robot”.

  • task_space (str, optional) – Task space frame for the force/torque data. Options are “World”, “Object”, “Robot”, or “Tool”. The default is “World”.

  • kinematics (str, optional) – The kinematics used for the calculation. Options are “Robot” or “Calculated”. The default is “Robot”.

  • state (str, optional) – The state of the robot for the calculation. Options are “Actual” or “Commanded”. The default is “Actual”.

  • avg_time (int, optional) – Average time for the external force/torque sensor, by default 0.

  • refresh (bool, optional) – If True, the robot’s state is updated before retrieving the force/torque data. Default is True.

Returns:

The force/torque data in the specified output form. The shape varies depending on the out option.

Return type:

np.ndarray

Raises:

ValueError – If the source, task_space, or out values are not supported.

GoTo_q(q: ndarray, qdot: ndarray, trq: ndarray, wait: float, **kwargs: Any) int[source]

Abstract method to command robots in combined to go to a specific joint configuration.

It has to be reimplemented in actual robot class!

This method sets the commanded joint positions (q), velocities (qdot), and torques (trq), then sends them to the robot and waits for the specified time (wait).

Parameters:
  • q (JointConfigurationType) – Desired joint positions (nj,).

  • qdot (JointVelocityType) – Desired joint velocities (nj,).

  • trq (JointTorqueType) – Desired joint torques (nj,).

  • wait (float) – Time to wait (in seconds) after commanding the robot to move.

Returns:

Status code (0 for success, non-zero for failure).

Return type:

int

GoTo_qtraj(q: ndarray, qdot: ndarray, qddot: ndarray, time: ndarray) int[source]

Command robots in combined system to follow a joint trajectory.

It is intended to control the robot to follow a trajectory specified by joint positions (q), velocities (qdot), and accelerations (qddot) over a specified time (time).

Parameters:
  • q (np.ndarray) – Desired joint positions for the trajectory (n, nr, nj), where n is the number of trajectory points.

  • qdot (np.ndarray) – Desired joint velocities for the trajectory (n, nr, nj), where n is the number of trajectory points.

  • qddot (np.ndarray) – Desired joint accelerations for the trajectory (n, nr, nj), where n is the number of trajectory points.

  • time (TimesType) – Time points for the trajectory (n,).

Returns:

Status code (0 for success, non-zero for failure).

Return type:

int

GoTo_T(x: ndarray, v: ndarray | None = None, FT: ndarray | None = None, wait: float | None = None, **kwargs: Any) int[source]

Move robots to the target pose and velocity in Cartesian space.

Parameters:
  • x (Union[Poses3DType, HomogeneousMatricesType]) – Target end-effector pose in Cartesian space. Can be in different forms (e.g., Pose, Transformation matrix).

  • v (Velocities3DType, optional) – Target end-effector velocity in Cartesian space. Default is a zero velocity vector (6,).

  • FT (np.ndarray, optional) – Target force/torque in Cartesian space. Default is a zero wrench array (nr, 6).

  • wait (float, optional) – The time to wait after the movement, by default the sample time (self.tsamp).

  • **kwargs (Any) – Additional keyword arguments passed to other methods, including task_space.

Returns:

The status of the move (0 for success, non-zero for error).

Return type:

int

Raises:

ValueError – If the provided task space is not supported.

Notes

The method first converts the input x, v, and FT based on the specified task space. The robot will be moved using either Cartesian control or a transformation control strategy.

GoTo_JT(x: ndarray, t: ndarray, wait: float | None = None, traj_samp_fac: float = None, max_iterations: int = 1000, pos_err: float | None = None, ori_err: float | None = None, task_space: str | None = None, task_DOF: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, null_space_task: str | None = None, task_cont_space: str | None = None, q_opt: ndarray | None = None, v_ns: ndarray | None = None, qdot_ns: ndarray | None = None, x_opt: ndarray | None = None, Kp: float | None = None, Kns: float | None = None, state: str = 'Commanded', **kwargs: Any) int[source]

Transforms Cartesian space trajectory to joiont space using inverse kinematics and then executes the trajectorj using GoTo_qtraj.

Parameters:
  • x (Union[Poses3DType, HomogeneousMatricesType]) – Target end-effector pose in Cartesian space (nr, 7) or (nr, 4, 4).

  • t (TimesType) – Time vector for trajectory (n,).

  • wait (float, optional) – The time to wait after movement, by default None (using self.tsamp).

  • traj_samp_fac (float, optional) – The factor for trajectory sampling, by default None (using self._default.TrajSampTimeFac).

  • max_iterations (int, optional) – Maximum iterations for inverse kinematics, by default 1000.

  • pos_err (float, optional) – Position error tolerance, by default None (using self._default.PosErr).

  • ori_err (float, optional) – Orientation error tolerance, by default None (using self._default.OriErr).

  • task_space (str, optional) – The task space for the motion, by default None (using self._default.TaskSpace).

  • task_DOF (ArrayLike, optional) – Task degrees of freedom, by default None (using self._default.TaskDOF).

  • null_space_task (str, optional) – The null space task for optimization, by default None (using self._default.NullSpaceTask).

  • task_cont_space (str, optional) – The task control space, by default None (using self._default.TaskContSpace).

  • q_opt (JointConfigurationType, optional) – Optimal joint configuration, by default None (using self.q_home).

  • v_ns (Velocity3DType, optional) – Velocity for null space, by default None (using zeros).

  • qdot_ns (JointVelocityType, optional) – Joint velocity for null space, by default None (using zeros).

  • x_opt (Poses3DType, optional) – Optimal end-effector pose, by default None (calculated using self.Kinmodel(q_opt)).

  • Kp (float, optional) – Position control gain, by default None (using self._default.Kp).

  • Kns (float, optional) – Null space gain, by default None (using self._default.Kns).

  • state (str, optional) – The robot state, by default “Commanded”.

  • **kwargs (Any) – Additional keyword arguments for customization.

Returns:

Status of the operation: 0 for success, non-zero for failure.

Return type:

int

Raises:

ValueError – If the task space or kinematics calculation is not supported.

Notes

The method uses inverse kinematics to plan the trajectory from Cartesian to joint space. Cartesian movement is converted to joint space via IKin and IKinPath methods. If Cartesian movement is not feasible, a warning message is raised.

GoTo_TC(x: ndarray, v: ndarray | None = None, FT: ndarray | None = None, timeout: float | None = None, pos_err: float | None = None, ori_err: float | None = None, task_space: str | None = None, task_DOF: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, null_space_task: str | None = None, task_cont_space: str = 'Robot', q_opt: ndarray | None = None, v_ns: ndarray | None = None, qdot_ns: ndarray | None = None, x_opt: ndarray | None = None, Kp: float | None = None, Kff: float | None = None, Kns: float | None = None, vel_fac: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, **kwargs: Any) int[source]

Kinematic controller for controlling bimanual robot in Cartesian space.

This function uses inverse kinematics to move the robot’s end-effector to a desired position while managing joint space motion through various null-space control strategies.

Parameters:
  • x (Union[Poses3DType, HomogeneousMatricesType]) – Combined target end-effector pose (…, 7), expressed in the specified task space.

  • v (Velocities3DType, optional) – Combined end-effector velocity (…, 6), by default None (zero velocity).

  • FT (np.ndarray, optional) – Combined end-effector Force/Torque (…, 6), by default None (zero force/torque).

  • timeout (float, optional) – Timeout for kinematic controller (by default 0).

  • pos_err (float, optional) – Position error tolerance, by default None (using self._default.PosErr).

  • ori_err (float, optional) – Orientation error tolerance, by default None (using self._default.OriErr).

  • task_space (str, optional) – The task space for motion, by default None (using self._default.TaskSpace).

  • task_DOF (ArrayLike, optional) – Task Degrees of Freedom, by default None (using self._default.TaskDOF).

  • null_space_task (str, optional) – Null-space task for optimization, by default None (using self._default.NullSpaceTask).

  • task_cont_space (str, optional) – Task control space, by default “Robot”.

  • q_opt (JointConfigurationType, optional) – Optimal joint configuration for null-space, by default None (using self.q_home).

  • v_ns (Velocity3DType, optional) – Null-space velocity, by default None (zero velocity).

  • qdot_ns (JointVelocityType, optional) – Joint velocity for null-space control, by default None (zero joint velocity).

  • x_opt (Poses3DType, optional) – Optimal end-effector pose, by default None (calculated from self.Kinmodel(q_opt)).

  • Kp (float, optional) – Proportional gain for position control, by default None (using self._default.Kp).

  • Kns (float, optional) – Null-space gain, by default None (using self._default.Kns).

  • vel_fac (ArrayLike, optional) – Velocity scaling factor for each joint, by default None.

  • **kwargs (Any) – Additional keyword arguments for flexibility.

Returns:

Status code (0 for success, non-zero for failure).

Return type:

int

Raises:

ValueError – If the task space or null-space task is not supported.

Notes

The method uses inverse kinematics to perform Cartesian motion to joint-space motion. Different null-space tasks can be applied for optimization such as manipulability, joint limits, etc.

CMoveFor(dx: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...], t: float | None = None, vel: float | None = None, vel_fac: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, traj: str | None = None, short: bool | None = None, wait: float | None = None, task_space: str | None = None, added_FT: ndarray | None = None, state: str = 'Commanded', asynchronous: bool = False, **kwargs: Any) int[source]

Move the robot in Cartesian space based on a displacement vector.

The robot moves its end-effector from the current position by a given displacement.

Parameters:
  • dx (ArrayLike) – Displacement in Cartesian space for position or rotation.

  • t (float, optional) – Time to complete the movement, by default None.

  • vel (float, optional) – Maximum velocity, by default None.

  • vel_fac (ArrayLike, optional) – Velocity scaling factor, by default None.

  • traj (str, optional) – Trajectory type, by default None.

  • short (bool, optional) – Whether to shorten the trajectory, by default None.

  • wait (float, optional) – Wait time after movement, by default None.

  • task_space (str, optional) – The task space for the movement, by default None.

  • added_FT (np.ndarray, optional) – Additional force/torque values, by default None.

  • state (str, optional) – The robot state (“Commanded” or “Actual”), by default “Commanded”.

  • asynchronous (bool, optional) – If True, executes the motion asynchronously, by default False.

  • **kwargs (Any) – Additional keyword arguments passed to internal methods.

Returns:

Status code of the move (0 if successful, non-zero if failed).

Return type:

int

CApproach(x: ndarray, dx: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...], t: float | None = None, vel: float | None = None, vel_fac: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, traj: str | None = None, short: bool | None = None, wait: float | None = None, task_space: str | None = None, added_FT: ndarray | None = None, state: str = 'Commanded', asynchronous: bool = False, **kwargs: Any) int[source]

Move the robot towards a target pose with an offset.

The robot moves to a position that is offset by a specified displacement from the given target pose.

Parameters:
  • x (Union[Poses3DType, HomogeneousMatricesType]) – The target Cartesian pose.

  • dx (ArrayLike) – The positional displacement to move towards.

  • t (float, optional) – Time to complete the movement, by default None.

  • vel (float, optional) – Maximum velocity, by default None.

  • vel_fac (ArrayLike, optional) – Velocity scaling factor, by default None.

  • traj (str, optional) – Trajectory type, by default None.

  • short (bool, optional) – Whether to shorten the trajectory, by default None.

  • wait (float, optional) – Wait time after movement, by default None.

  • task_space (str, optional) – The task space for the movement, by default None.

  • added_FT (np.ndarray, optional) – Additional force/torque values, by default None.

  • state (str, optional) – The robot state (“Commanded” or “Actual”), by default “Commanded”.

  • asynchronous (bool, optional) – If True, executes the motion asynchronously, by default False.

  • **kwargs (Any) – Additional keyword arguments passed to internal methods.

Returns:

Status code of the move (0 if successful, non-zero if failed).

Return type:

int

CRBFPath(*args: Any, **kwargs: Any) int[source]

Placeholder for RBF path motion in multi-robot systems.

Returns:

Status code indicating the method is not implemented.

Return type:

int

BaseToWorld(x: ndarray, typ: str = None, robot_num: int = None) ndarray[source]

Map from robot base frame to world frame.

Supported arguments: pose (7,), Homogenous matrix (4, 4), rotation matrix (3, 3), position (3,), twist (6,) and JacobianType (6, nj).

Parameters:
  • x (np.ndarray) – Argument to map. It can be one of the following shapes: - pose (7,) or (4, 4) - position (3,) - orientation (4,) or (3, 3) - velocity or force (6,) - JacobianType (6, nj)

  • typ (str, optional) – Transformation type, by default None. If “Wrench”, the transformation considers the force. If “Twist”, the transformation considers the velocity.

  • robot_num (int, optional) – Number of sub-robot, by default None.

Returns:

Mapped argument in the world frame.

Return type:

np.ndarray

Raises:

ValueError – If the parameter shape is not supported.

WorldToBase(x: ndarray, typ: str = None, robot_num: int = None) ndarray[source]

Map from world frame to robot base frame.

Supported arguments: pose (7,), Homogenous matrix (4, 4), rotation matrix (3, 3), position (3,), twist (6,) and JacobianType (6, nj).

Parameters:
  • x (np.ndarray) – Argument to map. It can be one of the following shapes: - pose (7,) or (4, 4) - position (3,) - orientation (4,) or (3, 3) - velocity or force (6,) - JacobianType (6, nj)

  • typ (str, optional) – Transformation type, by default None. If “Wrench”, the transformation considers the force. If “Twist”, the transformation considers the velocity.

  • robot_num (int, optional) – Number of sub-robot, by default None.

Returns:

Mapped argument in the robot base frame.

Return type:

np.ndarray

Raises:

ValueError – If the parameter shape is not supported.

ObjectToWorld(x: ndarray, typ: str = None, robot_num: int = None) ndarray[source]

Map from object frame to world frame.

Supported arguments: pose (7,), Homogenous matrix (4, 4), rotation matrix (3, 3), position (3,), twist (6,) and JacobianType (6, nj).

Parameters:
  • x (np.ndarray) – Argument to map. It can be one of the following shapes: - pose (7,) or (4, 4) - position (3,) - orientation (4,) or (3, 3) - velocity or force (6,) - JacobianType (6, nj)

  • typ (str, optional) – Transformation type, by default None. If “Wrench”, the transformation considers the force.

  • robot_num (int, optional) – Number of sub-robot, by default None.

Returns:

Mapped argument in the world frame.

Return type:

np.ndarray

Raises:

ValueError – If the parameter shape is not supported.

WorldToObject(x: ndarray, typ: str = None, robot_num: int = None) ndarray[source]

Map from world frame to object frame.

Supported arguments: pose (7,), Homogenous matrix (4, 4), rotation matrix (3, 3), position (3,), twist (6,) and JacobianType (6, nj).

Parameters:
  • x (np.ndarray) – Argument to map. It can be one of the following shapes: - pose (7,) or (4, 4) - position (3,) - orientation (4,) or (3, 3) - velocity or force (6,) - JacobianType (6, nj)

  • typ (str, optional) – Transformation type, by default None. If “Wrench”, the transformation considers the force.

  • robot_num (int, optional) – Number of sub-robot, by default None.

Returns:

Mapped argument in the object frame.

Return type:

np.ndarray

Raises:

ValueError – If the parameter shape is not supported.

DKinPath(path: ndarray, out: str = None) ndarray[source]

Compute direct kinematics for a path of joint positions.

Parameters:
  • path (np.ndarray) – Path in joint space - poses (n, nj).

  • out (str, optional) – Output format for the result, by default None (depends on robot settings).

Returns:

Task positions at target pose (n, 7) or (4, 4, n), depending on the output format.

Return type:

np.ndarray

IKin(x: ndarray, q0: ndarray, max_iterations: int = 1000, pos_err: float | None = None, ori_err: float | None = None, task_space: str | None = None, task_DOF: ndarray | None = None, null_space_task: str | None = None, task_cont_space: str = 'Robot', q_opt: ndarray | None = None, v_ns: ndarray | None = None, qdot_ns: ndarray | None = None, x_opt: ndarray | None = None, Kp: float | None = None, Kns: float | None = None, save_path: bool = False) ndarray[source]

Compute inverse kinematics to find joint positions that achieve a target Cartesian pose.

Parameters:
  • x (np.ndarray) – Target Cartesian pose (7,) or (4, 4).

  • q0 (np.ndarray) – Initial joint positions (nj,).

  • max_iterations (int, optional) – Maximum number of iterations for the inverse kinematics algorithm, by default 1000.

  • pos_err (float, optional) – Position error tolerance, by default None (uses default value).

  • ori_err (float, optional) – Orientation error tolerance, by default None (uses default value).

  • task_space (str, optional) – Task space in which to perform the inverse kinematics, by default “Robot”.

  • task_DOF (np.ndarray, optional) – Degrees of freedom of the task, by default None.

  • null_space_task (str, optional) – Type of null-space task, by default None.

  • task_cont_space (str, optional) – The space in which task continuity is considered, by default “Robot”.

  • q_opt (np.ndarray, optional) – Optimal joint positions for null space tasks, by default None.

  • v_ns (np.ndarray, optional) – Null-space velocity for task-space velocity, by default None.

  • qdot_ns (np.ndarray, optional) – Null-space joint velocities, by default None.

  • x_opt (np.ndarray, optional) – Optimal Cartesian pose for null-space tasks, by default None.

  • Kp (float, optional) – Proportional gain for the controller, by default None.

  • Kns (float, optional) – Gain for the null-space task, by default None.

  • save_path (bool, optional) – Whether to save the joint positions for the path, by default False.

Returns:

Joint positions at target pose (nj,).

Return type:

np.ndarray

IKinPath(path: ndarray, q0: ndarray, max_iterations: int = 100, pos_err: float | None = None, ori_err: float | None = None, task_space: str | None = None, task_DOF: ndarray | None = None, null_space_task: str | None = None, task_cont_space: str = 'Robot', q_opt: ndarray | None = None, v_ns: ndarray | None = None, qdot_ns: ndarray | None = None, x_opt: ndarray | None = None, Kp: float | None = None, Kns: float | None = None) ndarray[source]

Compute inverse kinematics for a path of Cartesian poses.

Parameters:
  • path (np.ndarray) – Path in Cartesian space - poses (n,7) or (n,4,4).

  • q0 (np.ndarray) – Initial joint positions (nj,).

  • max_iterations (int, optional) – Maximum number of iterations, by default 100.

  • pos_err (float, optional) – Position error tolerance, by default None (uses default).

  • ori_err (float, optional) – Orientation error tolerance, by default None (uses default).

  • task_space (str, optional) – Task space in which to compute the inverse kinematics, by default “Robot”.

  • task_DOF (np.ndarray, optional) – Degrees of freedom for the task, by default None.

  • null_space_task (str, optional) – Type of null-space task, by default None.

  • task_cont_space (str, optional) – Task continuity space, by default “Robot”.

  • q_opt (np.ndarray, optional) – Optimal joint positions for null-space tasks, by default None.

  • v_ns (np.ndarray, optional) – Null-space velocity for task-space velocity, by default None.

  • qdot_ns (np.ndarray, optional) – Null-space joint velocities, by default None.

  • x_opt (np.ndarray, optional) – Optimal Cartesian pose for null-space tasks, by default None.

  • Kp (float, optional) – Proportional gain, by default None.

  • Kns (float, optional) – Gain for null-space tasks, by default None.

Returns:

Joint positions at target pose for each point in the path (n, nj).

Return type:

np.ndarray

Jacobi(q: ndarray | None = None, tcp: ndarray | None = None, task_space: str = 'Robot') ndarray[source]

Compute the Jacobian matrix for the robot given joint positions.

Parameters:
  • q (JointConfigurationType, optional) – Joint positions (nj,). If not provided, the actual joint positions are used.

  • tcp (TCPType, optional) – by default the value of self.TCP is used.

  • task_space (str, optional) – The task space in which to compute the Jacobian, by default “Robot”.

Returns:

Jacobian matrix of shape (6, nj) or (6, n), where nj is the number of joints.

Return type:

JacobianType

Manipulability(q: ndarray, task_space: str | None = 'Robot', task_DOF: ndarray | None = None) float[source]

Compute the manipulability measure of the robot at a given joint configuration.

Parameters:
  • q (np.ndarray) – Joint positions (nj,).

  • task_space (str, optional) – The task space frame to use for the Jacobian, by default “Robot”.

  • task_DOF (np.ndarray, optional) – Task Degrees of Freedom (DOF) for the manipulability calculation, by default all 6 DOF are considered.

Returns:

Manipulability measure, which is the square root of the determinant of the Jacobian matrix.

Return type:

float

TaskDistance(x: ndarray, out: str = 'x', task_space: str = 'World', state: str = 'Actual', kinematics: str = 'Calculated', robot_num: int = None) ndarray[source]

Calculate the distance between the current pose and a target pose.

Parameters:
  • x (np.ndarray) – The target pose to compare to the current pose.

  • out (str, optional) – The output form of the distance, by default “x”. Possible values are “x”, “p”, and “Q”.

  • task_space (str, optional) – The task space to use for the pose transformation, by default “World”.

  • state (str, optional) – The state of the current pose, by default “Actual”. Other options include “Command” for commanded poses.

  • kinematics (str, optional) – The type of kinematics to use, by default “Calculated”. Other options might include “Robot”.

  • robot_num (int, optional) – Number of sub-robot, by default None.

Returns:

The distance between the current and target poses.

Return type:

np.ndarray

SetLoad(load: load_params | None = None, mass: float | None = None, COM: ndarray | None = None, inertia: ndarray | None = None, robot_num: int | None = None) None[source]

Set the load properties of the robot.

Parameters:
  • load (load_params, optional) – The load object to be assigned, by default None.

  • mass (float, optional) – The mass of the load, by default None.

  • COM (np.ndarray, optional) – The center of mass of the load, by default None.

  • inertia (np.ndarray, optional) – The inertia of the load, by default None.

  • robot_num (int, optional) – Number of sub-robot, by default None.

SetTCP(tcp: ndarray | None = None, frame: str = 'Gripper', robot_num: int | None = None) None[source]

Set the Tool Center Point (TCP) of robots in combined system.

Parameters:
  • tcp (np.ndarray, optional) – The transformation matrix or pose of the TCP. Default is the identity matrix.

  • frame (str, optional) – The frame to which the TCP is referenced. Can be “Gripper” or “Flange”. Default is “Gripper”.

  • robot_num (int, optional) – Number of sub-robot, by default None.

Return type:

None

SetTCPGripper(tcp: ndarray | None = None, robot_num: int | None = None) None[source]

Set the TCP for the gripper of robots in combined system.

Parameters:
  • tcp (np.ndarray, optional) – The transformation matrix or pose of the gripper TCP. Default is the identity matrix.

  • robot_num (int, optional) – Number of sub-robot, by default None.

Return type:

None

SetObject(x: ndarray | None = None, robot_num: int | None = None) None[source]

Set the object pose in the robot’s coordinate system for robots in combined system.

Parameters:
  • x (np.ndarray, optional) – The pose of the object (7,) or (4, 4) (default is None, which sets to the actual object pose).

  • robot_num (int, optional) – Number of sub-robot, by default None.

Return type:

None

SetBasePose(x: ndarray, robot_num: int = None) None[source]

Set the robot base pose for robots in combined system.

Parameters:
  • x (np.ndarray) – The pose of the base (7,) or (4, 4).

  • robot_num (int, optional) – Number of sub-robot, by default None.

Return type:

None

Raises:

ValueError – If the base pose shape is not recognized.

SetBaseVel(v: ndarray, robot_num: int = None) None[source]

Set the robot base velocity for robots in combined system

Parameters:
  • v (np.ndarray) – The velocity of the base (6,).

  • robot_num (int, optional) – Number of sub-robot, by default None.

Return type:

None

Raises:

ValueError – If the base pose shape is not recognized.

UpdateRobotBase() ndarray[source]

Update the robot base pose from the base platform, if available.

Returns:

The updated base pose.

Return type:

np.ndarray

GetContacts(**kwargs) list | ndarray | None[source]

Return contact information.

Parameters:

**kwargs (Any) – Additional keyword arguments passed to internal methods.

Returns:

Contact information, or None if no contacts are present.

Return type:

list | np.ndarray | None

Start() bool[source]

Start the robot’s motion by setting the control mode to 0.5 and resetting error states.

Return type:

None

Stop() None[source]

Stop the robot’s motion by setting the control mode to 0 and resetting velocities and errors.

Return type:

None

Abort(abort: bool = True) None[source]

Abort the robot’s motion by setting the abort flag and changing the control mode to -2.

Parameters:

abort (bool, optional) – Whether to abort the motion. Default is True.

Return type:

None

class robotblockset.multi_robots.multi_robot(robots: Tuple[robot, ...], robot_name: str | None = None, **kwargs: Any)[source]

Bases: multi_robots

Combined dual-robot system

First task space: robot1 Second task space: robot2

Initialize a combined robot with one task-space output per robot.

Parameters:
  • robots (Tuple[robot, ...]) – Robots included in the combined robot system.

  • robot_name (str, optional) – Name assigned to the combined robot. If omitted, the inherited default is used.

  • **kwargs (Any) – Additional keyword arguments forwarded to the parent constructor.

Returns:

This constructor initializes the combined robot object in place.

Return type:

None

__init__(robots: Tuple[robot, ...], robot_name: str | None = None, **kwargs: Any) None[source]

Initialize a combined robot with one task-space output per robot.

Parameters:
  • robots (Tuple[robot, ...]) – Robots included in the combined robot system.

  • robot_name (str, optional) – Name assigned to the combined robot. If omitted, the inherited default is used.

  • **kwargs (Any) – Additional keyword arguments forwarded to the parent constructor.

Returns:

This constructor initializes the combined robot object in place.

Return type:

None

Kinmodel(q: ndarray | None = None, tcp: ndarray | None = None, out: str = 'x') Tuple[ndarray, ndarray][source]

Calculate the forward kinematics of the combined dual robot system.

Parameters:
  • q (JointConfigurationType, optional) – Joint positions for both robots (length: robot1.nj + robot2.nj). If None, uses the current actual joint state.

  • tcp (Union[Poses3DType, HomogeneousMatricesType], optional) – Tool Center Points (TCP) for both robots. If None, uses default TCP.

  • out (str, optional) – Output format. Only “x” is supported for combined robots.

Returns:

Pose and JacobianType.

Return type:

Tuple

class robotblockset.multi_robots.bimanual_robot(robots: Tuple[robot, ...], robot_name: str | None = None, **kwargs: Any)[source]

Bases: multi_robots

Combined bimanual-robot system

Relative task: the base is at the end-effector of the first robot and the end-effector is the end-effector of the second robot.

Absolute task: the base is the base of the first robot and the end-effector is the end-effector of the fiirst robot.

Initialize a bimanual robot model built from exactly two robots.

Parameters:
  • robots (Tuple[robot, ...]) – Pair of robots used to form the bimanual system.

  • robot_name (str, optional) – Name assigned to the bimanual robot. If omitted, a default name is used.

  • **kwargs (Any) – Additional keyword arguments forwarded to the parent constructor.

Returns:

This constructor initializes the bimanual robot object in place.

Return type:

None

__init__(robots: Tuple[robot, ...], robot_name: str | None = None, **kwargs: Any) None[source]

Initialize a bimanual robot model built from exactly two robots.

Parameters:
  • robots (Tuple[robot, ...]) – Pair of robots used to form the bimanual system.

  • robot_name (str, optional) – Name assigned to the bimanual robot. If omitted, a default name is used.

  • **kwargs (Any) – Additional keyword arguments forwarded to the parent constructor.

Returns:

This constructor initializes the bimanual robot object in place.

Return type:

None

GetState() None[source]

Update and synchronize the internal state of the combined robot.

This method updates the joint positions, velocities, forces/torques, task space position and velocity, and the base pose of the dual robot system. It synchronizes the state of all robots and computes the combined state. The method handles the relative force computation and updates the base pose and velocity for the system.

The state synchronization occurs if the time since the last update exceeds a certain threshold, determined by the sampling rate (tsamp).

Attributes Updated: - Joint positions (self._actual.q) - Joint velocities (self._actual.qdot) - Joint torques (self._actual.trq) - Task space position (self._actual.x) - Task space velocity (self._actual.v) - Force/Torque sensor data (self._actual.FT)

Notes

  • The self._last_update attribute is updated to the current simulation time to ensure proper time-based synchronization.

Returns:

This method does not return any value. It modifies the internal state of the robot object.

Return type:

None

Kinmodel(q: ndarray | None = None, tcp: ndarray | None = None, out: str = 'x') Tuple[ndarray, ndarray][source]

Calculate the forward kinematics of the combined robot.

Parameters:
  • q (JointConfigurationType, optional) – Joint positions for both robots (length: robot1.nj + robot2.nj). If None, uses the current actual joint state.

  • tcp (Union[Pose3DType, HomogeneousMatrixType], optional) – Tool Center Point (TCP) of the second robot. If None, uses default TCP.

  • out (str, optional) – Output format. Only “x” is supported for combined robots.

Returns:

Pose and JacobianType.

Return type:

Tuple

SetTCP(tcp: ndarray | None = None) None[source]

Set the Tool Center Point (TCP) of combined robot for absolute pose. This TCP is added to the TCP of the first robot.

Note that for relative motion only TCP of basic robots in combined system are considered.

Parameters:

tcp (TCPType, optional) – The transformation matrix or pose of the TCP. Default is the identity matrix.

Return type:

None

class robotblockset.multi_robots.bimanual_robot_mean(robots: Tuple[robot, ...], robot_name: str | None = None, **kwargs: Any)[source]

Bases: multi_robots

Combined bimanual-robot system

Relative task: the base is at the end-effector of the first robot and the end-effector is the end-effector of the second robot.

Absolute task: the base is the base of the first robot and the end-effector is the end-effector of the fiirst robot.

Initialize a bimanual robot model with a mean absolute task definition.

Parameters:
  • robots (Tuple[robot, ...]) – Pair of robots used to form the bimanual system.

  • robot_name (str, optional) – Name assigned to the bimanual robot. If omitted, a default name is used.

  • **kwargs (Any) – Additional keyword arguments forwarded to the parent constructor.

Returns:

This constructor initializes the bimanual robot object in place.

Return type:

None

__init__(robots: Tuple[robot, ...], robot_name: str | None = None, **kwargs: Any) None[source]

Initialize a bimanual robot model with a mean absolute task definition.

Parameters:
  • robots (Tuple[robot, ...]) – Pair of robots used to form the bimanual system.

  • robot_name (str, optional) – Name assigned to the bimanual robot. If omitted, a default name is used.

  • **kwargs (Any) – Additional keyword arguments forwarded to the parent constructor.

Returns:

This constructor initializes the bimanual robot object in place.

Return type:

None

GetState() None[source]

Update and synchronize the internal state of the combined robot.

This method updates the joint positions, velocities, forces/torques, task space position and velocity, and the base pose of the dual robot system. It synchronizes the state of all robots and computes the combined state. The method handles the relative force computation and updates the base pose and velocity for the system.

The state synchronization occurs if the time since the last update exceeds a certain threshold, determined by the sampling rate (tsamp).

Attributes Updated: - Joint positions (self._actual.q) - Joint velocities (self._actual.qdot) - Joint torques (self._actual.trq) - Task space position (self._actual.x) - Task space velocity (self._actual.v) - Force/Torque sensor data (self._actual.FT)

Notes

  • The self._last_update attribute is updated to the current simulation time to ensure proper time-based synchronization.

Returns:

This method does not return any value. It modifies the internal state of the robot object.

Return type:

None

Kinmodel(q: ndarray | None = None, tcp: ndarray | None = None, out: str = 'x') Tuple[ndarray, ndarray][source]

Calculate the forward kinematics of the combined robot.

Parameters:
  • q (JointConfigurationType, optional) – Joint positions for both robots (length: robot1.nj + robot2.nj). If None, uses the current actual joint state.

  • tcp (Union[Pose3DType, HomogeneousMatrixType], optional) – Tool Center Point (TCP) of the second robot. If None, uses default TCP.

  • out (str, optional) – Output format. Only “x” is supported for combined robots.

Returns:

Pose and JacobianType.

Return type:

Tuple

SetTCP(tcp: ndarray | None = None) None[source]

Set the Tool Center Point (TCP) of combined robot for absolute pose. This TCP is added to the TCP of the first robot.

Note that for relative motion only TCP of basic robots in combined system are considered.

Parameters:

tcp (TCPType, optional) – The transformation matrix or pose of the TCP. Default is the identity matrix.

Return type:

None

Functions

join_fixed_robot(p1, R1, p2, R2, J2)

Join a fixed base with a robot: fixed base_1 -> fxed EE_1 -> base_2 -> EE_2.

join_reverse_robot(p1, R1, J1, p2, R2, J2)

Join two robots with the structure: EE_1 -> base_1 -> base_2 -> EE_2.

join_robot(p1, R1, J1, p2, R2, J2)

Join two robot kinematic chains: base_1 -> EE_1 -> base_2 -> EE_2.

join_robot_fixed(p1, R1, J1, p2, R2)

Join a robot to a fixed structure: base_1 -> EE_1 > fixed base -> fixed EE.

join_robot_reverse(p1, R1, J1, p2, R2, J2)

Join two robots in reverse: base_1 -> EE_1 -> EE_2 -> base_2.

robot_reverse(p1, R1, J1)

Compute the reverse kinematics of a robot (from end-effector to base).

Classes

bimanual_robot(robots[, robot_name])

Combined bimanual-robot system

bimanual_robot_mean(robots[, robot_name])

Combined bimanual-robot system

multi_robot(robots[, robot_name])

Combined dual-robot system

multi_robots(robots[, robot_name])

Represents a robot master class with various configurations, transformations, and control mechanisms.