grasp_generator
Main grasp processing
- Author:
Lukas Rustler
- class pybullet_grasper.grasp_generator.ClientProcess(client: Client, id: int, gripper_poses: List[Any], score: Any, after_grasp_poses: Any)[source]
Bases:
ProcessWorker process that evaluates a batch of candidate grasp poses.
- Parameters:
client (Client) – shared simulation client template
id (int) – worker/process identifier
gripper_poses (list[Any]) – pose candidates assigned to this worker
score (Any) – shared array storing pose quality scores
after_grasp_poses (Any) – shared array storing object poses after grasping
- Returns:
None
- Return type:
None
- handle_timeout(signum: int, frame: Any) None[source]
Raises timeout exception from signal alarm callback.
- Parameters:
signum (int) – POSIX signal number
frame (Any) – interrupted frame
- Returns:
None
- Return type:
None
- class pybullet_grasper.grasp_generator.GraspGenerator(object_name: str = 'object_0.obj', init_position: List[float] | ndarray = [0, 0, 0], config_name: str = 'default.yaml', ros: bool = True)[source]
Bases:
objectCreates grasp candidates and prepares simulation resources.
- Parameters:
object_name (str, optional, default="object_0.obj") – object mesh name or path
init_position (list[float] | np.ndarray, optional, default=[0, 0, 0]) – initial object position in world coordinates
config_name (str, optional, default="default.yaml") – configuration file name or path
ros (bool, optional, default=True) – whether ROS message types should be used
- Returns:
None
- Return type:
None
- pybullet_grasper.grasp_generator.quaternion_multiply(q1: List[float] | ndarray, q2: List[float] | ndarray) ndarray[source]
Multiplies two quaternions [x, y, z, w].
- Parameters:
q1 (list[float] | np.ndarray) – first quaternion
q2 (list[float] | np.ndarray) – second quaternion
- Returns:
quaternion product [x, y, z, w]
- Return type:
np.ndarray