robots_coppelia
Robot interfaces for CoppeliaSim via the ZMQ Remote API.
This module provides RobotBlockSet robot backends for CoppeliaSim. It includes the generic robot_coppelia interface for state acquisition, joint-space commanding, object pose access, and simulator lifecycle handling, together with concrete robot wrappers such as lwr, ur10, panda, and iiwa that define robot-specific joint naming and base-frame conventions.
- robotblockset.coppelia.robots_coppelia.c_float_p
alias of
LP_c_float
- class robotblockset.coppelia.robots_coppelia.robot_coppelia(robot_name: str, host: str = 'localhost', port: int = 23000, **kwargs: Any)[source]
Bases:
robotInterface class for controlling a robot in CoppeliaSim via RemoteAPI.
This class extends the base robot class and provides simulation-specific setup and naming conventions for joints, end effectors, and sensors. It uses the CoppeliaSim RemoteAPI to establish communication with the simulation.
- Attributes:
Name (str) – Name of the RobotBlockSet robot instance.
BaseName (str) – Base name of the robot in the CoppeliaSim scene hierarchy.
JointNames (list[str] or None) – Explicit list of joint object names, if configured.
JointNamesAlias (str or None) – Alias used when joints are accessed by indexed object names.
FlangeName (str) – Name of the end-effector flange object in the scene.
TCPName (str) – Name of the tool center point object in the scene.
SensorForceName (str) – Name of the force-torque sensor object in the scene.
client (RemoteAPIClient) – Remote API client connected to CoppeliaSim.
sim (Any) – Simulation API object returned by the remote client.
Create a CoppeliaSim-backed robot interface.
- Parameters:
robot_name (str) – Base name of the robot used in the CoppeliaSim scene.
host (str, optional) – Host running the CoppeliaSim ZMQ Remote API server.
port (int, optional) – Port used by the CoppeliaSim ZMQ Remote API server.
**kwargs (Any) – Additional keyword arguments used to configure joint, flange, TCP, and sensor object names.
- Returns:
This constructor initializes the CoppeliaSim robot interface in place.
- Return type:
None
- __init__(robot_name: str, host: str = 'localhost', port: int = 23000, **kwargs: Any) None[source]
Create a CoppeliaSim-backed robot interface.
- Parameters:
robot_name (str) – Base name of the robot used in the CoppeliaSim scene.
host (str, optional) – Host running the CoppeliaSim ZMQ Remote API server.
port (int, optional) – Port used by the CoppeliaSim ZMQ Remote API server.
**kwargs (Any) – Additional keyword arguments used to configure joint, flange, TCP, and sensor object names.
- Returns:
This constructor initializes the CoppeliaSim robot interface in place.
- Return type:
None
- Close() None[source]
Close or clean up the simulation interface.
Currently does not stop the simulation explicitly.
- Returns:
This method is reserved for simulation cleanup.
- Return type:
None
- Init() None[source]
Initialize the robot from the CoppeliaSim scene.
This method performs the following: - Retrieves the robot base handle. - Computes the robot’s base transform matrix. - Retrieves joint handles based on configured joint names or aliases. - Retrieves and computes the TCP (Tool Center Point) transform relative to the end effector. - Retrieves the force/torque sensor handle if defined. - Initializes simulation-related internal state, joint positions, and handles.
- Raises:
ValueError – If the robot base is not found in the CoppeliaSim scene.
- Returns:
This method initializes simulator handles and cached robot state.
- Return type:
None
- GetState() None[source]
Update the robot’s internal state from the CoppeliaSim simulation.
This method queries joint positions, velocities, and torques, along with the TCP pose and velocity (if available), and force/torque sensor data (if available). The update occurs only if the elapsed simulation time exceeds the sampling period.
Updates the following internal state attributes: - self._actual.q : Joint positions - self._actual.qdot : Joint velocities - self._actual.trq : Joint torques - self._actual.x : TCP pose (in base frame) - self._actual.v : TCP velocity (in base frame) - self._actual.FT : Force/torque sensor readings - self._actual.trqExt : External joint torques (zeroed by default)
Notes
Uses self.tsamp as the minimum time interval between updates.
Falls back to forward kinematics if TCP is not defined.
Sets force/torque to zeros if sensor is unavailable or inactive.
- Returns:
This method refreshes the internal robot state caches.
- Return type:
None
- isReady() bool[source]
Check whether the simulation is running.
- Returns:
True if the simulation is not in a stopped state, False otherwise.
- Return type:
bool
- isActive() bool[source]
Check if the robot target is active.
- Returns:
Indicating if the robot target is active.
- Return type:
bool
- Restart(qpos: ndarray | None = None) None[source]
Restart the simulation.
Stops and restarts the CoppeliaSim simulation. This method waits briefly after each step to allow the simulator to cleanly stop and start.
- Parameters:
qpos (JointConfigurationType, optional) – Placeholder for future support of setting initial joint positions after restart. Currently unused.
- Returns:
This method restarts the CoppeliaSim simulation.
- Return type:
None
- GoTo_q(q: ndarray, qdot: ndarray | None = None, trq: ndarray | None = None, wait: float | None = None, **kwargs: Any) int[source]
Update joint positions and wait
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, optional) – Desired joint velocities (nj,).
trq (JointTorqueType, optional) – Desired joint torques (nj,).
wait (float, optional) – Time to wait (in seconds) after commanding the robot to move.
- Returns:
Status of the move (0 for success, non-zero for error).
- Return type:
int
- SetStrategy(strategy: str) None[source]
Set the robot’s control strategy.
- Parameters:
strategy (str) – Name of the control strategy to be used (e.g., ‘JointPosition’).
- Returns:
This placeholder currently does not change controller behavior.
- Return type:
None
Notes
This method is currently a placeholder and does not implement any behavior.
- GetObjectPose(ide: str | int, out: str = 'x') ndarray | None[source]
Retrieve the pose of an object from the simulation.
- Parameters:
ide (Union[str, int]) – Object name or handle.
out (str, optional) – Output format.
- Returns:
Pose in the requested format if found, else None.
- Return type:
Optional[Union[Pose3DType, HomogeneousMatrixType, Vector3DType, RotationMatrixType]]
- SetObjectPose(ide: str | int, x: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...]) None[source]
Set the pose of an object in the simulation.
- Parameters:
ide (Union[str, int]) – Object name or body ID.
x (ArrayLike) –
- Pose to be set. Supported formats:
4x4 transformation matrix
3x3 rotation matrix
7D vector [pos(3), quat(4)]
3D position vector
4D quaternion
- Returns:
This method updates the pose of the selected simulation object.
- Return type:
None
- Raises:
ValueError – If the shape of x is not one of the supported formats.
- class robotblockset.coppelia.robots_coppelia.lwr(robot_name: str = 'LBR4p', **kwargs: Any)[source]
Bases:
robot_coppelia,lwr_specCoppeliaSim wrapper for the KUKA LWR manipulator.
Create a CoppeliaSim KUKA LWR robot wrapper.
- Parameters:
robot_name (str, optional) – Robot object name in the CoppeliaSim scene.
**kwargs (Any) – Additional keyword arguments passed to robot_coppelia.__init__.
- Returns:
This constructor initializes the LWR robot wrapper in place.
- Return type:
None
- __init__(robot_name: str = 'LBR4p', **kwargs: Any) None[source]
Create a CoppeliaSim KUKA LWR robot wrapper.
- Parameters:
robot_name (str, optional) – Robot object name in the CoppeliaSim scene.
**kwargs (Any) – Additional keyword arguments passed to robot_coppelia.__init__.
- Returns:
This constructor initializes the LWR robot wrapper in place.
- Return type:
None
- class robotblockset.coppelia.robots_coppelia.ur10(robot_name: str = 'UR10', **kwargs: Any)[source]
Bases:
robot_coppelia,ur10_specCoppeliaSim wrapper for the Universal Robots UR10 manipulator.
Create a CoppeliaSim UR10 robot wrapper.
- Parameters:
robot_name (str, optional) – Robot object name in the CoppeliaSim scene.
**kwargs (Any) – Additional keyword arguments passed to robot_coppelia.__init__.
- Returns:
This constructor initializes the UR10 robot wrapper in place.
- Return type:
None
- __init__(robot_name: str = 'UR10', **kwargs: Any) None[source]
Create a CoppeliaSim UR10 robot wrapper.
- Parameters:
robot_name (str, optional) – Robot object name in the CoppeliaSim scene.
**kwargs (Any) – Additional keyword arguments passed to robot_coppelia.__init__.
- Returns:
This constructor initializes the UR10 robot wrapper in place.
- Return type:
None
- class robotblockset.coppelia.robots_coppelia.panda(robot_name: str = 'Franka', JointNamesAlias: str = 'joint', **kwargs: Any)[source]
Bases:
robot_coppelia,panda_specCoppeliaSim wrapper for the Franka Emika Panda manipulator.
Create a CoppeliaSim Franka Panda robot wrapper.
- Parameters:
robot_name (str, optional) – Robot object name in the CoppeliaSim scene.
JointNamesAlias (str, optional) – Indexed alias used to access joint objects in the scene.
**kwargs (Any) – Additional keyword arguments passed to robot_coppelia.__init__.
- Returns:
This constructor initializes the Panda robot wrapper in place.
- Return type:
None
- __init__(robot_name: str = 'Franka', JointNamesAlias: str = 'joint', **kwargs: Any) None[source]
Create a CoppeliaSim Franka Panda robot wrapper.
- Parameters:
robot_name (str, optional) – Robot object name in the CoppeliaSim scene.
JointNamesAlias (str, optional) – Indexed alias used to access joint objects in the scene.
**kwargs (Any) – Additional keyword arguments passed to robot_coppelia.__init__.
- Returns:
This constructor initializes the Panda robot wrapper in place.
- Return type:
None
- class robotblockset.coppelia.robots_coppelia.iiwa(robot_name: str = 'iiwa', JointNamesAlias: str = 'joint', **kwargs: Any)[source]
Bases:
robot_coppelia,iiwa_specCoppeliaSim wrapper for the KUKA iiwa manipulator.
Create a CoppeliaSim KUKA iiwa robot wrapper.
- Parameters:
robot_name (str, optional) – Robot object name in the CoppeliaSim scene.
JointNamesAlias (str, optional) – Indexed alias used to access joint objects in the scene.
**kwargs (Any) – Additional keyword arguments passed to robot_coppelia.__init__.
- Returns:
This constructor initializes the iiwa robot wrapper in place.
- Return type:
None
- __init__(robot_name: str = 'iiwa', JointNamesAlias: str = 'joint', **kwargs: Any) None[source]
Create a CoppeliaSim KUKA iiwa robot wrapper.
- Parameters:
robot_name (str, optional) – Robot object name in the CoppeliaSim scene.
JointNamesAlias (str, optional) – Indexed alias used to access joint objects in the scene.
**kwargs (Any) – Additional keyword arguments passed to robot_coppelia.__init__.
- Returns:
This constructor initializes the iiwa robot wrapper in place.
- Return type:
None
Classes
alias of |
|
|
CoppeliaSim wrapper for the KUKA iiwa manipulator. |
|
CoppeliaSim wrapper for the KUKA LWR manipulator. |
|
CoppeliaSim wrapper for the Franka Emika Panda manipulator. |
|
Interface class for controlling a robot in CoppeliaSim via RemoteAPI. |
|
CoppeliaSim wrapper for the Universal Robots UR10 manipulator. |