platforms

Platform base classes and utilities.

This module defines the common platform abstraction used in robotblockset for mobile bases and related motion-control components. It provides state and command containers, default motion parameters, motion result codes, and the main platform base class with support for coordinate transforms, motion commands, attached robots, and asynchronous execution helpers.

class robotblockset.platforms.MotionResultCodes(*values)[source]

Bases: Enum

Result codes returned by platform motion commands.

Attributes:
  • MOTION_SUCCESS (int) – 0. Motion completed successfully.

  • MOTION_FAILURE (int) – 1. Motion failed.

  • MOTION_ABORTED (int) – 2. Motion was aborted.

  • JOINT_LIMITS (int) – 3. A joint or configuration limit was reached.

  • CLOSE_TO_TARGET (int) – 4. The platform is already close to the requested target.

  • ACTIVE_THREADS (int) – 5. Active worker threads prevent execution of the command.

  • WRONG_STRATEGY (int) – 6. The selected motion strategy is not valid for the requested command.

  • NOT_FEASIBLE (int) – 7. The requested motion is not feasible.

  • NO_ROBOT_ATTACHED (int) – 8. No robot is attached to the platform.

  • RTDE_ERROR (int) – 9. A communication error occurred in the backend interface.

  • NO_RESPONSE (int) – 10. No response was received from the platform or controller.

  • NOT_READY (int) – 11. The platform is not ready to execute motion.

MOTION_SUCCESS = 0
MOTION_FAILURE = 1
MOTION_ABORTED = 2
JOINT_LIMITS = 3
CLOSE_TO_TARGET = 4
ACTIVE_THREADS = 5
WRONG_STRATEGY = 6
NOT_FEASIBLE = 7
NO_ROBOT_ATTACHED = 8
RTDE_ERROR = 9
NO_RESPONSE = 10
NOT_READY = 11
robotblockset.platforms.MotionResultStr(code: MotionResultCodes | int) str[source]

Convert motion result code to a descriptive human-readable string.

Parameters:

code (Union[MotionResultCodes, int]) – Result code to describe.

Returns:

Human-readable description of the result code.

Return type:

str

class robotblockset.platforms.platform(**kwargs: Any)[source]

Bases: rbs_object

Represents a mobile platform base class with state handling, frame transforms, and motion-control utilities.

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

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

  • TRobotBase (HomogeneousMatrixType) – Transformation matrix of the attached robot base relative to the platform.

  • TObject (HomogeneousMatrixType) – Transformation matrix of the tracked or manipulated object.

  • Robot (Optional[robot]) – Robot attached to the platform, if any.

  • User (Optional[Any]) – User-defined data or object associated with the platform.

  • Tag (Optional[str]) – Tag associated with the platform.

Initialize the platform with default values and optional configuration arguments.

Parameters:

**kwargs (Any) – Optional arguments for custom configuration or parameters.

__init__(**kwargs: Any) None[source]

Initialize the platform with default values and optional configuration arguments.

Parameters:

**kwargs (Any) – Optional arguments for custom configuration or parameters.

reset_threads() None[source]

Resets the internal semaphore to its initial state.

This method reinitializes the semaphore with a value of 1, effectively allowing one thread to acquire it.

Return type:

None

jointvar(x: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...]) ndarray[source]

Validates and returns the input x if it has the proper shape for joint positions.

Parameters:

x (ArrayLike) – Input array representing joint positions, which must have the shape (n, nj), where n is the number of samples and nj is the number of joints.

Returns:

The input array x if it has the correct shape.

Return type:

JointConfigurationType

Raises:

TypeError – If the input x does not have the proper shape.

Note

Assuming ‘nj’ represents the number of joints, defined elsewhere in the class

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

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

Parameters:

x (ArrayLike) – The input array representing a spatial quantity, which can be 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.

simtime() float[source]

Returns the current simulation time based on the system’s performance counter.

The perf_counter function provides a high-resolution timer that is useful for measuring time intervals. It is system-dependent and returns the time as a floating-point value in seconds.

Returns:

The current simulation time in seconds since an arbitrary point (usually the start of the program).

Return type:

float

UseThreads(active: bool) None[source]

Enable or disable worker threads for platform control.

This method sets the _threads_active attribute, which controls whether the platform control system should use threads for asynchronous operations.

Parameters:

active (bool) – A boolean value that indicates whether threads should be active. If True, threads are enabled. If False, threads are disabled.

Returns:

This method does not return any value.

Return type:

None

SetTsamp(tsamp: float) None[source]

Set the sampling time for the platform control system.

This method updates the tsamp attribute and synchronizes the default wait interval.

Parameters:

tsamp (float) – The new sampling time in seconds to set for the robot control system.

Returns:

This method does not return any value.

Return type:

None

ResetTime() None[source]

Reset the platform timing reference to the current simulation time.

This method updates the internal time attributes _t0 and _tt0 to the current simulation time and current platform time, respectively.

Returns:

This method does not return any value.

Return type:

None

isReady() bool[source]

Check if the platform is ready for operation.

This method checks the _connected attribute to determine if the platform 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 platform target is active.

This method always returns True, indicating that the platform target is in an active state. It can be overridden in subclasses for more complex behavior.

Returns:

Always returns True, indicating the platform target is active.

Return type:

bool

inMotion() bool[source]

Check if the platform is in motion.

Returns:

True indicating the platform is excetuting motion command.

Return type:

bool

Check(silent: bool = False) list[str][source]

Check the status of the platform.

Parameters:

silent (bool, optional) – If True, suppress status messages while checking the platform state.

Returns:

A list containing non-active status entries and descriptions.

Return type:

list[str]

property Time: float

Get the elapsed wall time since the platform was initialized.

Returns:

Elapsed time in seconds.

Return type:

float

property t: float

Get the elapsed platform time.

Returns:

Time difference in seconds.

Return type:

float

property command: _command

Get the commanded state of the platform.

Returns:

A copy of the commanded state.

Return type:

_command

property actual: _actual

Get the actual state of the platform.

Returns:

A copy of the actual state.

Return type:

_actual

property q: ndarray

Get the current joint positions.

Returns:

Joint positions (nj,).

Return type:

np.ndarray

property qdot: ndarray

Get the current joint velocities.

Returns:

Joint velocities (nj,).

Return type:

np.ndarray

property trq: ndarray

Get the current joint torques.

Returns:

Joint torques (nj,).

Return type:

np.ndarray

property x: ndarray

Get the current platform pose.

Returns:

Platform pose (7,).

Return type:

np.ndarray

property p: ndarray

Get the current planar platform position.

Returns:

Platform position (2,).

Return type:

np.ndarray

property Q: ndarray

Get the current platform orientation as a quaternion.

Returns:

Platform quaternion (4,).

Return type:

np.ndarray

property R: ndarray

Get the current platform orientation as a rotation matrix.

Returns:

Platform rotation matrix (3, 3).

Return type:

np.ndarray

property T: ndarray

Get the current platform pose as a homogeneous transformation matrix.

Returns:

Platform transformation matrix (4, 4).

Return type:

np.ndarray

property theta: float

Get the current platform yaw angle.

Returns:

The rotation about the world z-axis extracted from the platform orientation.

Return type:

float

property v: ndarray

Get the current platform spatial velocity.

Returns:

Platform velocity (6,).

Return type:

np.ndarray

property pdot: ndarray

Get the current planar platform linear velocity.

Returns:

Platform linear velocity (2,).

Return type:

np.ndarray

property w: ndarray

Get the current platform angular velocity.

Returns:

Platform angular velocity (3,).

Return type:

np.ndarray

property FT: ndarray

Get the current force/torque sensor data.

Returns:

Force/Torque sensor data (6,).

Return type:

np.ndarray

property F: ndarray

Get the current force sensor data.

Returns:

Force sensor data (3,) or (…, 3).

Return type:

np.ndarray

property Trq: ndarray

Get the current torque sensor data.

Returns:

Torque sensor data (3,) or (…, 3).

Return type:

np.ndarray

property q_ref: ndarray

Get the commanded platform configuration.

Returns:

Desired joint positions (nj,).

Return type:

np.ndarray

property qdot_ref: ndarray

Get the commanded platform configuration velocities.

Returns:

Desired joint velocities (nj,).

Return type:

np.ndarray

property x_ref: ndarray

Get the commanded platform pose.

Returns:

Desired end-effector pose (7,).

Return type:

np.ndarray

property p_ref: ndarray

Get the commanded planar platform position.

Returns:

Desired end-effector position (2,).

Return type:

np.ndarray

property Q_ref: ndarray

Get the commanded platform orientation as a quaternion.

Returns:

Desired end-effector quaternion (4,).

Return type:

np.ndarray

property R_ref: ndarray

Get the commanded platform orientation as a rotation matrix.

Returns:

Desired end-effector rotation matrix (3, 3).

Return type:

np.ndarray

property T_ref: ndarray

Get the commanded platform pose as a homogeneous transformation matrix.

Returns:

Desired end-effector transformation matrix (4, 4).

Return type:

np.ndarray

property theta_ref: float

Get the commanded platform yaw angle.

Returns:

The rotation about the world z-axis extracted from the commanded orientation.

Return type:

float

property v_ref: ndarray

Get the commanded platform spatial velocity.

Returns:

Commanded platform velocity (6,).

Return type:

np.ndarray

property pdot_ref: ndarray

Get the commanded planar platform linear velocity.

Returns:

Commanded platform linear velocity (2,).

Return type:

np.ndarray

property w_ref: ndarray

Get the commanded platform angular velocity.

Returns:

Desired end-effector angular velocity (3,) or (…, 3).

Return type:

np.ndarray

property FT_ref: ndarray

Get the desired force/torque sensor data.

Returns:

Desired force/torque sensor data (6,).

Return type:

np.ndarray

property F_ref: ndarray

Get the desired force sensor data.

Returns:

Desired force sensor data (3,).

Return type:

np.ndarray

property Trq_ref: ndarray

Get the desired torque sensor data.

Returns:

Desired torque sensor data (3,).

Return type:

np.ndarray

property q_err: ndarray

Get the error in joint positions.

Returns:

Error in joint positions (nj,).

Return type:

np.ndarray

property qdot_err: ndarray

Get the error in joint velocities.

Returns:

Error in joint velocities (nj,).

Return type:

np.ndarray

property x_err: ndarray

Get the error in end-effector pose.

Returns:

Error in end-effector pose (7,).

Return type:

np.ndarray

property p_err: ndarray

Get the error in end-effector position.

Returns:

Error in end-effector position (2,).

Return type:

np.ndarray

property Q_err: ndarray

Get the error in end-effector quaternion.

Returns:

Error in end-effector quaternion (4,).

Return type:

np.ndarray

property R_err: ndarray

Get the error in end-effector rotation matrix.

Returns:

Error in end-effector rotation matrix (3, 3).

Return type:

np.ndarray

property T_err: ndarray

Get the error in end-effector transformation matrix.

Returns:

Error in end-effector transformation matrix (4, 4).

Return type:

np.ndarray

property theta_err: float

Property to calculate the difference between the reference orientation and the current orientation along z-axis.

Returns:

The difference along z-axis between the reference and current orientation.

Return type:

float

property v_err: ndarray

Get the error in end-effector velocity.

Returns:

Error in end-effector velocity (6,).

Return type:

np.ndarray

property pdot_err: ndarray

Get the error in end-effector linear velocity.

Returns:

Error in end-effector linear velocity (2,).

Return type:

np.ndarray

property w_err: ndarray

Get the error in end-effector angular velocity.

Returns:

Error in end-effector angular velocity (3,).

Return type:

np.ndarray

InitObject() None[source]

Initializes the platforms’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

Init() None[source]

Initializes the robot by setting up the object, state, current target, time, and logging a message.

This method calls the following functions to initialize the robot: 1. InitObject() - Initializes the command and actual states with default values. 2. GetState() - Retrieves the current state of the robot. 3. ResetCurrentTarget() - Resets the current target position. 4. ResetTime() - Resets the robot’s internal time.

Returns:

This method does not return any value. It modifies the robot’s internal state and logs a message.

Return type:

None

GetState() None[source]

Abstract method to updates the platforms’s state.

It has to be reimplemented in actual platforms class!

It has to set: - Actual platforms joint and task space states - Read all platforms sensors

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

Returns:

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

Return type:

None

Update() None[source]

Updates the platform’s state and optionally triggers a capture callback.

This method performs the following actions:

  • If _do_update is True, it calls GetState() to update the platform’s internal state.

  • If _do_capture is True and a capture callback function (_capture_callback) is defined, it calls the callback function, passing the platform object as an argument.

Returns:

This method does not return any value. It modifies the internal state of the platform and may trigger a callback.

Return type:

None

EnableUpdate() None[source]

Enables the update of the platform’s internal state.

This method sets the _do_update attribute to True, which allows the platform’s state to be updated.

Returns:

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

Return type:

None

DisableUpdate() None[source]

Disables the update of the platform’s internal state.

This method sets the _do_update attribute to False, which prevents the platform’s state from being updated.

Returns:

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

Return type:

None

GetUpdateStatus() bool[source]

Returns the current status of the update flag.

This method returns the value of the _do_update attribute, which indicates whether the platform’s state update is enabled.

Returns:

True if updates are enabled, False otherwise.

Return type:

bool

ResetCurrentTarget() None[source]

Resets the current target to the actual values of joint positions, velocities, torques, and other state variables.

Return type:

None

GetJointPos(state: str | None = None, refresh: bool | None = None) ndarray[source]

Get the joint positions of the robot based on the specified state.

Parameters:
  • state (str, optional) – The state from which to retrieve joint positions. Can be ‘Actual’ or ‘Commanded’. If None, the default state defined in the robot class is used.

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

Returns:

The joint positions (q) from the specified state, copied to prevent external modifications.

Return type:

np.ndarray

Raises:

ValueError – If the state is not “Actual” or “Commanded”.

GetJointVel(state: str | None = None, refresh: bool | None = None) ndarray[source]

Get the joint velocities of the robot based on the specified state.

Parameters:
  • state (str, optional) – The state from which to retrieve joint velocities. Can be ‘Actual’ or ‘Commanded’. If None, the default state defined in the robot class is used.

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

Returns:

The joint velocities (qdot) from the specified state, copied to prevent external modifications.

Return type:

np.ndarray

Raises:

ValueError – If the state is not “Actual” or “Commanded”.

GetJointTrq(state: str | None = None, refresh: bool | None = None) ndarray[source]

Get the joint torques of the robot based on the specified state.

Parameters:
  • state (str, optional) – The state from which to retrieve joint torques. Can be ‘Actual’ or ‘Commanded’. If None, the default state defined in the robot class is used.

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

Returns:

The joint torques (trq) from the specified state, copied to prevent external modifications.

Return type:

np.ndarray

Raises:

ValueError – If the state is not “Actual” or “Commanded”.

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

Get platform pose

Parameters:
  • out (str, optional) – Output form, by default “x” (“Pose”)

  • task_space (str, optional) – Task space frame, by default “World”

  • state (str, optional) – Variable state, by default “Actual”

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

Returns:

Platform pose

Return type:

array of floats

GetPos(out: str | None = None, task_space: str | None = None, state: str | None = None) ndarray[source]

Get platform position

Parameters:
  • out (str, optional) – Output form, by default “p” (“Position”)

  • task_space (str, optional) – Task space frame, by default “World”

  • state (str, optional) – Variable state, by default “Actual”

Returns:

platform position (3,)

Return type:

array of floats

GetOri(out: str | None = None, task_space: str | None = None, state: str | None = None) ndarray[source]

Get platform orientation

Parameters:
  • out (str, optional) – Output form, by default “Q” (“Quaternion”)

  • task_space (str, optional) – Task space frame, by default “World”

  • state (str, optional) – Variable state, by default “Actual”

Returns:

platform orientation (4,) or (3,3)

Return type:

array of floats

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

Get platform velocity

Parameters:
  • out (str, optional) – Output form, by default “Twist”

  • task_space (str, optional) – Task space frame, by default “World”

  • state (str, optional) – Variable state, by default “Actual”

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

Returns:

Platform velocity (6,) or (3,)

Return type:

array of floats

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

Get the platforms’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 “Platform”. The default is “World”.

  • 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 platforms’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, or task_space options are invalid.

Set_vel(v: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...], wait: float | None = None) int[source]
CMoveToOri(rtheta: float, task_space: str | None = None, wait: float | None = None, vel_fac: float | None = None, ori_err: float | None = None, k_rot: float | None = None, asynchronous: bool = False) Thread | int[source]
CMoveToLocation(rp: ndarray, rtheta: float | None = None, task_space: str | None = None, robot_as_a_sensor: bool = False, min_dist: float | None = None, approach_dist: float | None = None, final_orientation_correction: bool = True, wait: float | None = None, vel_fac: float | None = None, pos_err: float | None = None, ori_err: float | None = None, k_dist: float | None = None, k_dir: float | None = None, asynchronous: bool = False, allow_backward: bool = False, reach_check_fn: Callable[[...], bool] | None = None, **kwargs: Any) Thread | int[source]
PForward(d: float, t: float = 1, traj: str | None = None, asynchronous: bool = False) Thread | int[source]
PTurn(ang: float, t: float = 1, traj: str | None = None, asynchronous: bool = False) Thread | int[source]
AutonomousMotion(callback: Callable[[...], int] | None = None, asynchronous: bool = True, **kwargs: Any) Thread | int[source]
AbortAutonomousMotion() None[source]
PlatformToWorld(x: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...], typ: str | None = None) ndarray[source]

Map from platform 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 (ArrayLike) – argument to map: - pose (7,) or (4, 4) - position (3, ) - orientation (4,) or (3, 3) - velocity or force (6, ) - JacobianType (6, nj) - 2D position (2,) - rotation (1,)

  • typ (str, optional) – Transformation type (None or Wrench)

Returns:

mapped argument

Return type:

array of floats

Raises:

ValueError – Parameter shape not supported

Note

2D position and scalar rotation can be used only if z-axis of both frames are colinear

WorldToPlatform(x: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...], typ: str | None = 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 (ArrayLike) – argument to map: - pose (7,) or (4, 4) - position (3, ) - orientation (4,) or (3, 3) - velocity or force (6, ) - JacobianType (6, nj) - 2D position (2,) - rotation (1,)

  • typ (str, optional) – Transformation type (None or Wrench)

Returns:

mapped argument

Return type:

array of floats

Raises:

ValueError – Parameter shape not supported

Note

2D position and scalar rotation can be used only if z-axis of both frames are colinear

ObjectToWorld(x: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...], typ: str | None = 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 (ArrayLike) – argument to map: - pose (7,) or (4, 4) - position (3, ) - orientation (4,) or (3, 3) - velocity or force (6, ) - JacobianType (6, nj) - 2D position (2,) - rotation (1,)

  • typ (str, optional) – Transformation type (None or Wrench)

Returns:

mapped argument

Return type:

array of floats

Raises:

ValueError – Parameter shape not supported

Note

2D position and scalar rotation can be used only if z-axis of both frames are colinear

WorldToObject(x: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...], typ: str | None = 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 (ArrayLike) – argument to map: - pose (7,) or (4, 4) - position (3, ) - orientation (4,) or (3, 3) - velocity or force (6, ) - JacobianType (6, nj) - 2D position (2,) - rotation (1,)

  • typ (str, optional) – Transformation type (None or Wrench)

Returns:

mapped argument

Return type:

array of floats

Raises:

ValueError – Parameter shape not supported

Note

2D position and scalar rotation can be used only if z-axis of both frames are colinear

Kinmodel(q: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, out: str = 'x') Tuple[ndarray, ndarray][source]
Jacobi() ndarray[source]
SetObject(x: ndarray | None = None) None[source]

Set the object pose in the platform coordinate system.

Parameters:

x (Union[Pose3DType, HomogeneousMatrixType], optional) – The object pose as a pose vector (7,) or homogeneous matrix (4, 4). If None, the current actual platform pose is used.

Return type:

None

Raises:

ValueError – If the pose shape is not supported or if the input pose z-axis is not aligned with [0, 0, 1].

GetObject(out: str = 'T', task_space: str | None = None) ndarray[source]

Get the object pose in the specified task space.

Parameters:
  • out (str, optional) – The output format of the object pose. Default is "T".

  • task_space (str, optional) – The task space for the pose transformation. Supported values are "World", "Object", and "Platform".

Returns:

The object pose in the requested output format.

Return type:

Pose3DType or HomogeneousMatrixType or Vector3DType or QuaternionType or RotationMatrixType

Raises:

ValueError – If the task space is not supported.

AttachTo(robot: robot) None[source]

Attach a robot instance to the platform.

Detach() None[source]

Detach the currently attached robot from the platform.

GetAttachedRobot() Tuple[robot | None, str][source]

Get the attached robot and its name.

Returns:

The attached robot instance and its name, or (None, "None").

Return type:

Tuple[Optional[robot], str]

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

Set the robot base pose relative to the platform.

Parameters:

x (ArrayLike) – The robot base pose as a homogeneous matrix, pose vector, position, rotation matrix, or quaternion.

Return type:

None

Raises:

ValueError – If the base pose shape is not supported.

GetRobotBase(out: str = 'T') ndarray[source]

Get the robot base pose relative to the platform.

Parameters:

out (str, optional) – The output format of the base pose. Default is "T".

Returns:

The robot base pose in the requested output format.

Return type:

Pose3DType or HomogeneousMatrixType or Vector3DType or QuaternionType or RotationMatrixType

GetRobotBasePose(out: str | None = None) ndarray[source]

Get the attached robot base pose in the world frame.

Parameters:

out (str, optional) – The output format of the base pose. If None, the default task pose format is used.

Returns:

The robot base pose in the world frame.

Return type:

Pose3DType or HomogeneousMatrixType or Vector3DType or QuaternionType or RotationMatrixType

Start() bool[source]
Stop() None[source]
WaitUntilStopped(eps: float = 0.001) None[source]
Wait(wait: float, dt: float | None = None) int | None[source]
Restart() None[source]
SetMotionCheckCallback(fun: Callable[[...], int]) None[source]

Set the motion-check callback.

EnableMotionCheck(check: bool = True) None[source]

Enable motion-check callbacks.

DisableMotionCheck() None[source]

Disable motion-check callbacks.

SetCaptureCallback(fun: Callable[[...], None]) None[source]

Set the callback used during capture updates.

StartCapture() None[source]

Enable capture callbacks during state updates.

StopCapture() None[source]

Disable capture callbacks during state updates.

SetUserData(data: Any | None) None[source]

Store user-defined data in the command state.

GetUserData() Any | None[source]

Get user-defined data stored in the command state.

robotblockset.platforms.isplatform(obj: object) bool[source]

Check whether an object is a platform instance.

Parameters:

obj (object) – Object to test.

Returns:

True if obj is an instance of platform, otherwise False.

Return type:

bool

Functions

MotionResultStr(code)

Convert motion result code to a descriptive human-readable string.

isplatform(obj)

Check whether an object is a platform instance.

Classes

MotionResultCodes(*values)

Result codes returned by platform motion commands.

platform(**kwargs)

Represents a mobile platform base class with state handling, frame transforms, and motion-control utilities.