diff --git a/examples/ioai_examples/grasp_reg.py b/examples/ioai_examples/grasp_reg.py new file mode 100644 index 0000000..6148a39 --- /dev/null +++ b/examples/ioai_examples/grasp_reg.py @@ -0,0 +1,363 @@ +import numpy as np +from scipy.spatial.transform import Rotation as R +from typing import Dict, Any, Tuple +import copy + + +class GraspRegistration: + """Register the grasp labels. + + Note: + Assume that the object is placed on the table. + x-axis is the longer side of the object. + y-axis is the shorter side of the object. + z-axis is the height of the object. + """ + + def __init__(self): + x_p = np.array([1.0, 0, 0]) + self.x_p = x_p / np.linalg.norm(x_p) + + z_n = np.array([0, 0, -1.0]) + self.z_n = z_n / np.linalg.norm(z_n) + + def move_matrix_along_x_axis(self, matrix, distance): + """Move the matrix along the x-axis. + Args: + matrix (np.ndarray): The input matrix. + distance (float): The distance to move in meters. + Returns: + np.ndarray: The moved matrix. + """ + transform_matrix = np.array( + [ + [1, 0, 0, distance], + [0, 1, 0, 0], + [0, 0, 1, 0], + [0, 0, 0, 1], + ], + dtype=np.float64, + ) + new_matrix = matrix @ transform_matrix + return new_matrix + + def move_matrix_along_y_axis(self, matrix, distance): + """Move the matrix along the y-axis. + Args: + matrix (np.ndarray): The input matrix. + distance (float): The distance to move in meters. + Returns: + np.ndarray: The moved matrix. + """ + transform_matrix = np.array( + [ + [1, 0, 0, 0], + [0, 1, 0, distance], + [0, 0, 1, 0], + [0, 0, 0, 1], + ], + dtype=np.float64, + ) + new_matrix = matrix @ transform_matrix + return new_matrix + + def move_matrix_along_z_axis(self, matrix, distance): + """Move the matrix along the z-axis. + Args: + matrix (np.ndarray): The input matrix. + distance (float): The distance to move in meters. + Returns: + np.ndarray: The moved matrix. + """ + transform_matrix = np.array( + [ + [1, 0, 0, 0], + [0, 1, 0, 0], + [0, 0, 1, distance], + [0, 0, 0, 1], + ], + dtype=np.float64, + ) + new_matrix = matrix @ transform_matrix + return new_matrix + + def rotate_matrix_along_x_axis(self, matrix, angle): + """Rotate the matrix along the z-axis. + Args: + matrix (np.ndarray): The input matrix. + angle (float): The angle to rotate in degrees. + Returns: + np.ndarray: The rotated matrix. + """ + theta = np.deg2rad(angle) + transform_matrix = np.array( + [ + [1, 0, 0, 0], + [0, np.cos(theta), -np.sin(theta), 0], + [0, np.sin(theta), np.cos(theta), 0], + [0, 0, 0, 1], + ], + dtype=np.float64, + ) + new_matrix = matrix @ transform_matrix + return new_matrix + + def rotate_matrix_along_y_axis(self, matrix, angle): + """Rotate the matrix along the y-axis. + Args: + matrix (np.ndarray): The input matrix. + angle (float): The angle to rotate in degrees. + Returns: + np.ndarray: The rotated matrix. + """ + theta = np.deg2rad(angle) + transform_matrix = np.array( + [ + [np.cos(theta), 0, np.sin(theta), 0], + [0, 1, 0, 0], + [-np.sin(theta), 0, np.cos(theta), 0], + [0, 0, 0, 1], + ], + dtype=np.float64, + ) + new_matrix = matrix @ transform_matrix + return new_matrix + + def rotate_matrix_along_z_axis(self, matrix, angle): + """Rotate the matrix along the z-axis. + Args: + matrix (np.ndarray): The input matrix. + angle (float): The angle to rotate in degrees. + Returns: + np.ndarray: The rotated matrix. + """ + theta = np.deg2rad(angle) + transform_matrix = np.array( + [ + [np.cos(theta), -np.sin(theta), 0, 0], + [np.sin(theta), np.cos(theta), 0, 0], + [0, 0, 1, 0], + [0, 0, 0, 1], + ], + dtype=np.float64, + ) + new_matrix = matrix @ transform_matrix + return new_matrix + + @staticmethod + def quat_pose_to_se3(quat_pose: np.ndarray) -> np.ndarray: + """Convert a pose in quaternion representation to SE(3) representation.""" + if not isinstance(quat_pose, np.ndarray) or quat_pose.shape != (7,): + raise ValueError("Input must be a numpy array of shape (7,).") + + position, quat = quat_pose[:3], quat_pose[3:] + quat = quat / np.linalg.norm(quat) # Normalize quaternion + rot_mat = R.from_quat(quat).as_matrix() + + se3 = np.eye(4) + se3[:3, :3] = rot_mat + se3[:3, 3] = position + return se3 + + @staticmethod + def se3_to_quat_pose(se3: np.ndarray) -> np.ndarray: + """Convert a pose in SE(3) representation to quaternion representation.""" + if not isinstance(se3, np.ndarray) or se3.shape != (4, 4): + raise ValueError("Input must be a numpy array of shape (4, 4).") + + position = se3[:3, 3] + quat = R.from_matrix(se3[:3, :3]).as_quat() + return np.hstack([position, quat]) + + def _modify_se3(self, se3: np.ndarray) -> np.ndarray: + """Check if the pose is valid and modify it.""" + # make sure the z-axis is pointing to the front + grasp_z_p = se3[:3, 2] + dot = np.dot(grasp_z_p, self.x_p) + if dot < 0: + se3[:3, 2] = -se3[:3, 2] + z = copy.deepcopy(se3[:3, 2]) + + # select the vector that is closer to the reference vector as the x-axis + dot1 = np.dot(se3[:3, 0], self.z_n) + dot2 = np.dot(se3[:3, 1], self.z_n) + if dot1 > dot2: + x = copy.deepcopy(se3[:3, 0]) + y = np.cross(z, x) + else: + x = copy.deepcopy(se3[:3, 1]) + y = np.cross(z, x) + se3[:3, 0] = x + se3[:3, 1] = y + se3[:3, 2] = z + return se3 + + def _rotate_sample_se3(self, se3, angle_range, angle_step): + """Sample SE(3) in rotation mode""" + grasp_se3_list = [se3] + sample_num = int((angle_range[1] - angle_range[0]) / angle_step) + angle_list = np.linspace(angle_range[0], angle_range[1], sample_num) + for angle in angle_list: + sampled_se3 = self.rotate_matrix_along_z_axis(se3, angle) + grasp_se3_list.append(sampled_se3) + # sort the grasp poses based on the difference between the x-axis of the sampled se3 and the initial se3 + grasp_se3_list = sorted( + grasp_se3_list, key=lambda x: np.dot(x[:3, 0], self.z_n), reverse=True + ) + return grasp_se3_list + + def _adjust_se3(self, se3: np.ndarray) -> np.ndarray: + """Adjust the se3 to make sure the z-axis is pointing to the front.""" + grasp_z_p = se3[:3, 2] + dot = np.dot(grasp_z_p, self.x_p) + if dot < 0: + grasp_se3 = self.rotate_matrix_along_x_axis(se3, 180) + else: + grasp_se3 = se3.copy() + return grasp_se3 + + def _convert_foundation_se3_to_obb_se3( + self, se3: np.ndarray, part_id: str + ) -> np.ndarray: + """Convert the foundation se3 to obb se3.""" + if part_id == "96641-O3000": # HORN ASSY-L/PITCH SHELL ELECT + x = se3[:3, 2] # z + y = se3[:3, 1] # y + z = -se3[:3, 0] # -x + center = se3[:3, 3] + obb_se3 = np.eye(4) + obb_se3[:3, 0] = x + obb_se3[:3, 1] = y + obb_se3[:3, 2] = z + obb_se3[:3, 3] = center + elif part_id == "29136-L4250": # GUARD-AIR LH + x = se3[:3, 2] # z + y = -se3[:3, 1] # -y + z = se3[:3, 0] # x + center = se3[:3, 3] + obb_se3 = np.eye(4) + obb_se3[:3, 0] = x + obb_se3[:3, 1] = y + obb_se3[:3, 2] = z + obb_se3[:3, 3] = center + else: + x = -se3[:3, 2] # -z + y = -se3[:3, 1] # -y + z = -se3[:3, 0] # -x + center = se3[:3, 3] + obb_se3 = np.eye(4) + obb_se3[:3, 0] = x + obb_se3[:3, 1] = y + obb_se3[:3, 2] = z + obb_se3[:3, 3] = center + return obb_se3 + + def register_grasp( + self, part_id: str, object_pose: np.ndarray + ) -> Tuple[list, float]: + """Register the grasp pose based on the object pose. + Args: + object_pose (np.ndarray): The object pose in quaternion representation or SE(3) representation. + + Returns: + List[np.ndarray]: A list of grasp poses in SE(3) representation. + float: The gripper width. + """ + if object_pose.shape == (7,): + object_se3 = self.quat_pose_to_se3(object_pose) + elif object_pose.shape == (4, 4): + object_se3 = object_pose.copy() + else: + raise ValueError("Input must be a numpy array of shape (7,) or (4, 4).") + + assert part_id in ["power_drill", "extrusion", "toy", "cube", "bin"], \ + f"Unsupported part_id: {part_id}" + + grasp_se3_list = [] + gripper_width = 0.5 + if part_id == "power_drill": + se3 = object_se3.copy() + se3 = self.move_matrix_along_z_axis(se3, 0.055) + se3 = self.move_matrix_along_y_axis(se3, -0.02) + se3 = self.rotate_matrix_along_y_axis(se3, 180) + grasp_se3_list.append(se3) + + se3 = object_se3.copy() + se3 = self.move_matrix_along_z_axis(se3, 0.055) + se3 = self.move_matrix_along_y_axis(se3, -0.02) + grasp_se3_list.append(se3) + + se3 = object_se3.copy() + se3 = self.move_matrix_along_z_axis(se3, 0.12) + se3 = self.rotate_matrix_along_y_axis(se3, 90) + se3 = self.rotate_matrix_along_x_axis(se3, 90) + grasp_se3_list.append(se3) + + gripper_width = 0.7 + elif part_id == "extrusion": + se3 = object_se3.copy() + se3 = self.move_matrix_along_z_axis(se3, 0.015) + se3 = self.rotate_matrix_along_z_axis(se3, 90) + se3 = self.rotate_matrix_along_x_axis(se3, 90) + grasp_se3_list = self._rotate_sample_se3( + se3, angle_range=(-180, 180), angle_step=10 + ) + gripper_width = 0.6 + + elif part_id == "toy": + se3 = object_se3.copy() + se3 = self.move_matrix_along_z_axis(se3, 0.05) + grasp_se3_list = self._rotate_sample_se3( + se3, angle_range=(-180, 180), angle_step=10 + ) + gripper_width = 0.6 + + elif part_id == "cube": + se3 = object_se3.copy() + grasp_se3_list1 = self._rotate_sample_se3( + se3, angle_range=(-180, 180), angle_step=10 + ) + grasp_se3_list += grasp_se3_list1 + + se3 = object_se3.copy() + se3 = self.rotate_matrix_along_x_axis(se3, 90) + grasp_se3_list2 = self._rotate_sample_se3( + se3, angle_range=(-180, 180), angle_step=10 + ) + grasp_se3_list += grasp_se3_list2 + + gripper_width = 0.6 + elif part_id == "bin": + se3 = object_se3.copy() + se3 = self.move_matrix_along_z_axis(se3, 0.05) + se3 = self.rotate_matrix_along_x_axis(se3, 90) + grasp_se3_list = self._rotate_sample_se3( + se3, angle_range=(-180, 180), angle_step=10 + ) + + return grasp_se3_list, gripper_width + + def predict_grasp(self, part_id: str, object_pose: np.ndarray) -> Dict[str, Any]: + """Predict the grasp pose from the grasp SE(3) list. + Args: + part_id (str): The part ID. + object_pose (np.ndarray): The object pose in quaternion representation or SE(3) representation. + Returns: + Dict[str, Any]: A dictionary containing the part ID, object pose, grasp SE(3), grasp pose, and gripper width. + """ + grasp_se3_list, gripper_width = self.register_grasp(part_id, object_pose) + grasp_se3_list = sorted( + grasp_se3_list, key=lambda x: np.dot(x[:3, 0], self.z_n), reverse=True + ) + grasp_se3 = self._adjust_se3(grasp_se3_list[0]) + grasp_pose = self.se3_to_quat_pose(grasp_se3) + + grasp = { + "part_id": part_id, + "object_pose": object_pose, + "grasp_se3": grasp_se3, + "grasp_pose": grasp_pose, + "gripper_width": gripper_width, + } + + return grasp diff --git a/examples/ioai_examples/ioai_env.py b/examples/ioai_examples/ioai_env.py index 658474a..7607186 100644 --- a/examples/ioai_examples/ioai_env.py +++ b/examples/ioai_examples/ioai_env.py @@ -45,7 +45,7 @@ from physics_simulator.utils.data_types import JointTrajectory import time import os - +import math from physics_simulator.utils.state_machine import SimpleStateMachine def interpolate_joint_positions(start_positions, end_positions, steps): @@ -86,6 +86,8 @@ def _setup_simulator(self, headless=False): # Add default scene (default ground plane) self.simulator.add_default_scene() + self.robot_init_position = [0, 4, 0] + self.robot_init_orientation = [0, 0, 0.70711, -0.70711] # Add robot robot_config = RobotConfig( prim_path="/World/Galbot", @@ -96,8 +98,8 @@ def _setup_simulator(self, headless=False): .joinpath("robots") .joinpath("galbot_one_foxtrot_description_simplified") .joinpath("galbot_one_foxtrot.xml"), - position=[0, 0, 0], - orientation=[0, 0, 0, 1] + position=[0, 4, 0], + orientation=[0, 0, 0.70711, -0.70711] ) self.simulator.add_robot(robot_config) self.robot = self.simulator.get_robot("/World/Galbot") @@ -156,6 +158,7 @@ def _setup_simulator(self, headless=False): # Add table table_config = MeshConfig( + name="table", prim_path="/World/Table", mjcf_path=Path() .joinpath(self.simulator.synthnova_assets_directory) @@ -170,6 +173,7 @@ def _setup_simulator(self, headless=False): # Add bin bin_config = MeshConfig( + name="bin", prim_path="/World/bin", mjcf_path=Path() .joinpath(self.simulator.synthnova_assets_directory) @@ -184,8 +188,9 @@ def _setup_simulator(self, headless=False): # Add cube cube_config = CuboidConfig( + name="cube", prim_path="/World/Cube", - position=[0.6, -0.3, 0.56], + position=[0.5, -0.3, 0.56], orientation=[0, 0, 0, 1], scale=[0.05, 0.05, 0.05], color=[0.5, 0.5, 0.5], # Gray color @@ -194,6 +199,7 @@ def _setup_simulator(self, headless=False): # Add toy toy_config = MeshConfig( + name="toy", prim_path="/World/toy", mjcf_path=Path() .joinpath(self.simulator.synthnova_assets_directory) @@ -201,13 +207,14 @@ def _setup_simulator(self, headless=False): .joinpath("objects") .joinpath("toy") .joinpath("toy.xml"), - position=[0.7, -0.2, 0.5], - orientation=[0, 0, 0, 1], + position=[0.65, -0.3, 0.55], + orientation=[0, 0, 0, -1], ) self.simulator.add_object(toy_config) # Add extrusion extrusion_config = MeshConfig( + name="extrusion", prim_path="/World/Extrusion", mjcf_path=Path() .joinpath(self.simulator.synthnova_assets_directory) @@ -215,13 +222,14 @@ def _setup_simulator(self, headless=False): .joinpath("objects") .joinpath("extrusion") .joinpath("extrusion.xml"), - position=[0.7, 0, 0.55], + position=[0.6, -0.2, 0.55], orientation=[0, 0, 0, 1], ) self.simulator.add_object(extrusion_config) # Add power drill power_drill_config = MeshConfig( + name="power_drill", prim_path="/World/PowerDrill", mjcf_path=Path() .joinpath(self.simulator.synthnova_assets_directory) @@ -229,13 +237,14 @@ def _setup_simulator(self, headless=False): .joinpath("objects") .joinpath("power_drill") .joinpath("power_drill.xml"), - position=[0.6, -0.1, 0.55], + position=[0.65, -0.1, 0.55], orientation=[0, 0, 0, 1], ) self.simulator.add_object(power_drill_config) # Add mug mug_config = MeshConfig( + name="mug", prim_path="/World/Mug", mjcf_path=Path() .joinpath(self.simulator.synthnova_assets_directory) @@ -243,7 +252,7 @@ def _setup_simulator(self, headless=False): .joinpath("objects") .joinpath("mug") .joinpath("mug.xml"), - position=[0.7, 0, 0.55], + position=[0.5, 0, 0.55], orientation=[0, 0, 0, 1], ) self.simulator.add_object(mug_config) @@ -256,6 +265,7 @@ def _setup_simulator(self, headless=False): # Add walls wall_1_config = CuboidConfig( + name="wall_1", prim_path="/World/Wall1", position=[center_x, center_y+wall_width/2, wall_height / 2], orientation=[0, 0, 0, 1], @@ -266,6 +276,7 @@ def _setup_simulator(self, headless=False): self.simulator.add_object(wall_1_config) wall_2_config = CuboidConfig( + name="wall_2", prim_path="/World/Wall2", position=[center_x, center_y-wall_width/2, wall_height / 2], orientation=[0, 0, 0, 1], @@ -276,6 +287,7 @@ def _setup_simulator(self, headless=False): self.simulator.add_object(wall_2_config) wall_3_config = CuboidConfig( + name="wall_3", prim_path="/World/Wall3", position=[center_x+wall_width/2, center_y, wall_height / 2], orientation=[0, 0, 0, 1], @@ -286,6 +298,7 @@ def _setup_simulator(self, headless=False): self.simulator.add_object(wall_3_config) wall_4_config = CuboidConfig( + name="wall_4", prim_path="/World/Wall4", position=[center_x-wall_width/2, center_y, wall_height / 2], orientation=[0, 0, 0, 1], @@ -297,6 +310,7 @@ def _setup_simulator(self, headless=False): # Add shelf shelf_config = MeshConfig( + name="shelf", prim_path="/World/Shelf", mjcf_path=Path() .joinpath(self.simulator.synthnova_assets_directory) @@ -311,6 +325,7 @@ def _setup_simulator(self, headless=False): # Add cones cone_1_config = MeshConfig( + name="cone_1", prim_path="/World/Cone1", mjcf_path=Path() .joinpath(self.simulator.synthnova_assets_directory) @@ -324,6 +339,7 @@ def _setup_simulator(self, headless=False): self.simulator.add_object(cone_1_config) cone_2_config = MeshConfig( + name="cone_2", prim_path="/World/Cone2", mjcf_path=Path() .joinpath(self.simulator.synthnova_assets_directory) @@ -336,18 +352,18 @@ def _setup_simulator(self, headless=False): ) self.simulator.add_object(cone_2_config) - cone_3_config = MeshConfig( - prim_path="/World/Cone3", - mjcf_path=Path() - .joinpath(self.simulator.synthnova_assets_directory) - .joinpath("synthnova_assets") - .joinpath("objects") - .joinpath("cone") - .joinpath("cone.xml"), - position=[1, 1, 0.55], - orientation=[0, 0, 0.70711, 0.70711], - ) - self.simulator.add_object(cone_3_config) + # cone_3_config = MeshConfig( + # prim_path="/World/Cone3", + # mjcf_path=Path() + # .joinpath(self.simulator.synthnova_assets_directory) + # .joinpath("synthnova_assets") + # .joinpath("objects") + # .joinpath("cone") + # .joinpath("cone.xml"), + # position=[1, 1, 0.55], + # orientation=[0, 0, 0.70711, 0.70711], + # ) + # self.simulator.add_object(cone_3_config) # Initialize the simulator self.simulator.initialize() @@ -533,6 +549,97 @@ def robot_to_world_frame(self, robot_position, robot_orientation): return world_position, world_orientation + def world_to_robot_init_frame(self, world_position, world_orientation=None): + """Transform pose from world frame to robot initial frame. + + Args: + world_position: Position in world frame [x, y, z] + world_orientation: Orientation in world frame [qx, qy, qz, qw] (optional) + + Returns: + Tuple of (robot_init_position, robot_init_orientation) in robot initial frame + """ + from scipy.spatial.transform import Rotation + + # Get robot initial pose in world frame + init_position = self.robot_init_position + init_orientation = self.robot_init_orientation + + # Create transformation matrix for initial pose + init_rot = Rotation.from_quat(init_orientation) + + # Transform position: subtract initial position and rotate + relative_position = world_position - init_position + robot_init_position = init_rot.inv().apply(relative_position) + + # Transform orientation if provided + if world_orientation is not None: + world_rot = Rotation.from_quat(world_orientation) + robot_init_orientation = (init_rot.inv() * world_rot).as_quat() + else: + robot_init_orientation = None + + return robot_init_position, robot_init_orientation + + def robot_init_to_world_frame(self, robot_init_position, robot_init_orientation=None): + """Transform pose from robot initial frame to world frame. + + Args: + robot_init_position: Position in robot initial frame [x, y, z] + robot_init_orientation: Orientation in robot initial frame [qx, qy, qz, qw] (optional) + + Returns: + Tuple of (world_position, world_orientation) in world frame + """ + from scipy.spatial.transform import Rotation + + # Get robot initial pose in world frame + init_position = self.robot_init_position + init_orientation = self.robot_init_orientation + + # Create transformation matrix for initial pose + init_rot = Rotation.from_quat(init_orientation) + + # Transform position: rotate and add initial position + world_position = init_rot.apply(robot_init_position) + init_position + + # Transform orientation if provided + if robot_init_orientation is not None: + robot_init_rot = Rotation.from_quat(robot_init_orientation) + world_orientation = (init_rot * robot_init_rot).as_quat() + else: + world_orientation = None + + return world_position, world_orientation + + def world_to_robot_init_frame_2d(self, world_position_2d): + """Transform 2D position from world frame to robot initial frame. + + Args: + world_position_2d: Position in world frame [x, y] + + Returns: + robot_init_position_2d: Position in robot initial frame [x, y] + """ + from scipy.spatial.transform import Rotation + + # Get robot initial pose in world frame + init_position = self.robot_init_position + init_orientation = self.robot_init_orientation + + # Create transformation matrix for initial pose + init_rot = Rotation.from_quat(init_orientation) + + # Convert 2D to 3D by adding z=0 + world_position_3d = [world_position_2d[0], world_position_2d[1], 0] + + # Transform position: subtract initial position and rotate + relative_position = np.array(world_position_3d) - np.array(init_position) + robot_init_position_3d = init_rot.inv().apply(relative_position) + + # Return only 2D coordinates + return robot_init_position_3d[:2] + def compute_simple_ik(self, start_joint, target_pose, arm_id="left_arm"): """Compute inverse kinematics using Mink. @@ -668,13 +775,162 @@ def compute_simple_fk(self, arm_id="left_arm"): # Return pose in base link frame [x, y, z, qx, qy, qz, qw] return np.concatenate([tcp_position_base, tcp_orientation_base]) + def get_left_gripper_pose(self): + """Get left gripper TCP pose in world frame""" + site_data = self.simulator.data.site(self.robot.namespace + "left_gripper_tcp") + position = site_data.xpos + from scipy.spatial.transform import Rotation + quaternion = Rotation.from_matrix(site_data.xmat.reshape((3, 3))).as_quat() + return position, quaternion + + def get_right_gripper_pose(self): + """Get right gripper TCP pose in world frame""" + site_data = self.simulator.data.site(self.robot.namespace + "right_gripper_tcp") + position = site_data.xpos + from scipy.spatial.transform import Rotation + quaternion = Rotation.from_matrix(site_data.xmat.reshape((3, 3))).as_quat() + return position, quaternion + + def move_arm_to_pose(self, arm_id, target_position, target_orientation): + # Prepare target pose in robot frame + target_pose = np.concatenate([target_position, target_orientation]) + + # Solve IK and start motion + current_joints = self.mink_config.q + arm_joints = self.compute_simple_ik(current_joints, target_pose, arm_id) + arm_module = getattr(self.interface, arm_id) + self._move_joints_to_target(arm_module, arm_joints) + + def move_left_arm_to_pose(self, target_position, target_orientation): + """Move left arm to target pose""" + return self.move_arm_to_pose("left_arm", target_position, target_orientation) + + def move_right_arm_to_pose(self, target_position, target_orientation): + """Move right arm to target pose""" + return self.move_arm_to_pose("right_arm", target_position, target_orientation) + + def move_chassis_follow_path(self, waypoints): + """Move chassis to follow a path defined by waypoints in world coordinates + + Args: + waypoints: List of 2D waypoints [(x1, y1), (x2, y2), ...] in world frame + """ + if not waypoints or len(waypoints) < 2: + print("Invalid waypoints: need at least 2 points") + return + + # Initialize path following components + from physics_simulator.utils.control_utils import BasicPathFollower + path_follower = BasicPathFollower(velocity=0.8) + waypoint_tolerance = 0.1 + current_target_index = 0 + path = waypoints + + def follow_path_callback(): + nonlocal current_target_index + + # Check if path is complete + if current_target_index >= len(path): + self.interface.chassis.set_joint_velocities([0.0, 0.0, 0.0]) + self.simulator.remove_physics_callback("follow_path_callback") + return + + # Get current state + current_pos = self.interface.chassis.get_joint_positions()[:2] + current_heading = self.interface.chassis.get_joint_positions()[2] + + # Update target waypoint + if current_target_index < len(path): + target_pos = path[current_target_index] + target_pos = self.world_to_robot_init_frame_2d(target_pos) + + distance = math.sqrt( + (target_pos[0] - current_pos[0])**2 + (target_pos[1] - current_pos[1])**2 + ) + if distance < waypoint_tolerance: + current_target_index += 1 + return + else: + target_pos = path[-1] + + # Calculate control commands + forward_vel, side_vel, yaw_vel = path_follower.calculate_control( + current_pos, current_heading, target_pos + ) + + # Set chassis velocities + self.interface.chassis.set_joint_velocities([forward_vel, side_vel, yaw_vel]) + + # Add physics callback for path following + self.simulator.add_physics_callback("follow_path_callback", follow_path_callback) + + def move_chassis_rotate(self, target_angle_world, angular_velocity=0.5): + """Rotate chassis to face a specific angle in world coordinates. + + Args: + target_angle_world: Target angle in world frame (radians), 0 is along positive x-axis + angular_velocity: Angular velocity for rotation (rad/s), default 0.5 + """ + # Remove existing callback + try: + self.simulator.remove_physics_callback("rotate_callback") + except: + pass + + # Calculate target heading in robot frame + from scipy.spatial.transform import Rotation + init_rot = Rotation.from_quat(self.robot_init_orientation) + init_z_angle = init_rot.as_euler('xyz')[2] # Extract z-axis rotation + target_heading = -init_z_angle + target_angle_world + + def rotate_callback(): + current_heading = self.interface.chassis.get_joint_positions()[2] + heading_error = target_heading - current_heading + + # Normalize error to [-pi, pi] + while heading_error > math.pi: + heading_error -= 2 * math.pi + while heading_error < -math.pi: + heading_error += 2 * math.pi + + if abs(heading_error) < 0.05: + self.interface.chassis.set_joint_velocities([0.0, 0.0, 0.0]) + self.simulator.remove_physics_callback("rotate_callback") + else: + yaw_vel = angular_velocity if heading_error > 0 else -angular_velocity + self.interface.chassis.set_joint_velocities([0.0, 0.0, yaw_vel]) + + self.simulator.add_physics_callback("rotate_callback", rotate_callback) + + def get_camera_images(self): + """Get RGB and depth images from the front head camera. + + Returns: + Tuple of (rgb_image, depth_image) or (rgb_image, None) if depth not available + """ + try: + # Get RGB image + rgb_image = self.interface.front_head_camera.get_rgb() + + # Get depth image if available + depth_image = None + try: + depth_image = self.interface.front_head_camera.get_depth() + except: + pass # Depth image not available + + return rgb_image, depth_image + except Exception as e: + print(f"Error getting camera images: {e}") + return None, None + def _init_pose(self): # Initialize robot pose poses = { self.interface.head: [0.0, 0.26], self.interface.leg: [0.0821758285164833, 0.6340972781181335,0.5227039456367493, -0.00001198422432935331], - self.interface.left_arm: [2.0020599365234375,-1.5977126359939575,-0.5948255658149719,-1.694089651107788,-0.0002879792882595211,-0.7909831404685974,-0.00016755158139858395], - self.interface.right_arm: [-2.001628875732422,1.6029852628707886,0.6024474501609802,1.6955766677856445,-0.0002391100861132145,0.7967827916145325,-0.00014311698032543063] + self.interface.left_arm: [2.00,-1.60, -0.60, -1.70, 0.00, -0.80, 0.00], + self.interface.right_arm: [-2.00, 1.60, 0.60, 1.70, 0.00, 0.80, 0.00] } for module, pose in poses.items(): @@ -691,81 +947,6 @@ def _is_joint_positions_reached(self, module, target_positions, atol=0.01): """Check if joint positions are reached within tolerance.""" current_positions = module.get_joint_positions() return np.allclose(current_positions, target_positions, atol=atol) - - def _is_left_arm_motion_complete(self, atol=0.01): - """Check if left arm has reached its target position.""" - for module_name, target_positions in self.target_joint_positions.items(): - module = getattr(self.interface, module_name) - if not self._is_joint_positions_reached(module, target_positions, atol): - return False - return True - - def _is_right_arm_motion_complete(self, atol=0.01): - """Check if right arm has reached its target position.""" - for module_name, target_positions in self.target_joint_positions.items(): - module = getattr(self.interface, module_name) - if not self._is_joint_positions_reached(module, target_positions, atol): - return False - return True - - def _move_left_arm_to_pose(self, target_position, target_orientation): - """Move left arm to target pose with IK solving and motion control. - - Args: - target_position: Target position [x, y, z] in robot base frame - target_orientation: Target orientation [qx, qy, qz, qw] in robot base frame - - Returns: - True if motion is complete, False otherwise - """ - if not self.motion_in_progress: - # Prepare target pose in robot frame - target_pose = np.concatenate([target_position, target_orientation]) - - # Solve IK and start motion - current_joints = self.mink_config.q - left_arm_joints = self.compute_simple_ik(current_joints, target_pose, "left_arm") - self._move_joints_to_target(self.interface.left_arm, left_arm_joints) - - # Store target positions for completion check - self.target_joint_positions = {"left_arm": left_arm_joints} - self.motion_in_progress = True - - # Check if motion is complete - if self._is_left_arm_motion_complete(): - self.motion_in_progress = False - return True - return False - - def _move_right_arm_to_pose(self, target_position, target_orientation): - """Move right arm to target pose with IK solving and motion control. - - Args: - target_position: Target position [x, y, z] in robot base frame - target_orientation: Target orientation [qx, qy, qz, qw] in robot base frame - - Returns: - True if motion is complete, False otherwise - """ - if not self.motion_in_progress: - # Prepare target pose in robot frame - target_pose = np.concatenate([target_position, target_orientation]) - - # Solve IK and start motion - current_joints = self.mink_config.q - right_arm_joints = self.compute_simple_ik(current_joints, target_pose, "right_arm") - self._move_joints_to_target(self.interface.right_arm, right_arm_joints) - - # Store target positions for completion check - self.target_joint_positions = {"right_arm": right_arm_joints} - self.motion_in_progress = True - - # Check if motion is complete - if self._is_right_arm_motion_complete(): - self.motion_in_progress = False - return True - return False - def run(self): self.simulator.loop() diff --git a/examples/ioai_examples/ioai_grasp_env.py b/examples/ioai_examples/ioai_grasp_env.py index 1b7e44b..74f2faf 100644 --- a/examples/ioai_examples/ioai_grasp_env.py +++ b/examples/ioai_examples/ioai_grasp_env.py @@ -53,6 +53,9 @@ from physics_simulator.utils.state_machine import SimpleStateMachine +from grasp_reg import GraspRegistration +grasp_reg = GraspRegistration() + @dataclass class PoseEstimationResult: """Data class for pose estimation result""" @@ -254,7 +257,7 @@ def _setup_simulator(self, headless=False): "front_head_depth_camera", ), translation=[ - 0.10084319533055261, + 0.10084319533055261,# grasp power_drill -0.059042081352783105, 0.03184978861787491 ], @@ -501,15 +504,15 @@ def robot_to_world_frame(self, robot_position, robot_orientation): return world_position, world_orientation - def camera_to_world_frame(self, camera_position, camera_orientation): - """Transform pose from camera frame to world frame. + def camera_to_robot_frame(self, camera_position, camera_orientation): + """Transform pose from camera frame to robot base frame. Args: camera_position: Position in camera frame [x, y, z] camera_orientation: Orientation in camera frame [qx, qy, qz, qw] Returns: - Tuple of (world_position, world_orientation) in world frame + Tuple of (robot_position, robot_orientation) in robot base frame """ from scipy.spatial.transform import Rotation @@ -519,26 +522,33 @@ def camera_to_world_frame(self, camera_position, camera_orientation): camera_world_position = camera_state["transform_to_base_link"]["position"] camera_world_orientation = camera_state["transform_to_base_link"]["orientation"] + # Get robot base pose in world frame + base_position = self.robot.get_position() + base_orientation = self.robot.get_orientation() + # Create transformation matrices camera_world_rot = Rotation.from_quat(camera_world_orientation) camera_local_rot = Rotation.from_quat(camera_orientation) + base_rot = Rotation.from_quat(base_orientation) - # Transform position: rotate and add camera world position + # Transform position: camera frame -> world frame -> robot frame world_position = camera_world_rot.apply(camera_position) + camera_world_position + relative_position = world_position - base_position + robot_position = base_rot.inv().apply(relative_position) - # Transform orientation: compose rotations + # Transform orientation: camera frame -> world frame -> robot frame world_orientation = (camera_world_rot * camera_local_rot).as_quat() + robot_orientation = (base_rot.inv() * Rotation.from_quat(world_orientation)).as_quat() - return world_position, world_orientation + return robot_position, robot_orientation - def world_to_camera_frame(self, world_position, world_orientation): - """Transform pose from world frame to camera frame. + def robot_to_camera_frame(self, robot_position, robot_orientation): + """Transform pose from robot base frame to camera frame. Args: - world_position: Position in world frame [x, y, z] - world_orientation: Orientation in world frame [qx, qy, qz, qw] - - Returns: + robot_position: Position in robot base frame [x, y, z] + robot_orientation: Orientation in robot base frame [qx, qy, qz, qw] + # orientation=[0, 0, 0.7071, 0.7071] Tuple of (camera_position, camera_orientation) in camera frame """ from scipy.spatial.transform import Rotation @@ -546,19 +556,26 @@ def world_to_camera_frame(self, world_position, world_orientation): # Get camera pose in world frame camera_prim_path = self.front_head_rgb_camera_path camera_state = self.simulator.get_sensor_state(camera_prim_path) - camera_world_position = camera_state["position"] - camera_world_orientation = camera_state["orientation"] + camera_world_position = camera_state["transform_to_base_link"]["position"] + camera_world_orientation = camera_state["transform_to_base_link"]["orientation"] + + # Get robot base pose in world frame + base_position = self.robot.get_position() + base_orientation = self.robot.get_orientation() # Create transformation matrices camera_world_rot = Rotation.from_quat(camera_world_orientation) - world_rot = Rotation.from_quat(world_orientation) + base_rot = Rotation.from_quat(base_orientation) + robot_rot = Rotation.from_quat(robot_orientation) - # Transform position: subtract camera position and rotate + # Transform position: robot frame -> world frame -> camera frame + world_position = base_rot.apply(robot_position) + base_position relative_position = world_position - camera_world_position camera_position = camera_world_rot.inv().apply(relative_position) - # Transform orientation: compose rotations - camera_orientation = (camera_world_rot.inv() * world_rot).as_quat() + # Transform orientation: robot frame -> world frame -> camera frame + world_orientation = (base_rot * robot_rot).as_quat() + camera_orientation = (camera_world_rot.inv() * Rotation.from_quat(world_orientation)).as_quat() return camera_position, camera_orientation @@ -608,10 +625,10 @@ def estimate_object_poses(self) -> List[PoseEstimationResult]: return pose_results def get_object_pose_from_estimation(self, target_class: str = "cube") -> Optional[Tuple[np.ndarray, np.ndarray]]: - """Get object pose from pose estimation""" + """Get object pose from pose estimation in robot base frame""" # Estimate object poses pose_results = self.estimate_object_poses() - + # Find target object target_result = None for result in pose_results: @@ -623,12 +640,18 @@ def get_object_pose_from_estimation(self, target_class: str = "cube") -> Optiona print(f"Target object '{target_class}' not found in pose estimation") return None - # Transform from camera frame to world frame - world_position, world_orientation = self.camera_to_world_frame( - target_result.position, target_result.orientation + target_pose = np.concatenate([target_result.position, target_result.orientation]) + grasp_pose = grasp_reg.predict_grasp(target_class, target_pose)["grasp_pose"] + + gripper_position = grasp_pose[:3] + gripper_orientation = grasp_pose[3:7] + + # Transform from camera frame to robot base frame + robot_position, robot_orientation = self.camera_to_robot_frame( + gripper_position, gripper_orientation ) - return world_position, world_orientation + return robot_position, robot_orientation def compute_simple_ik(self, start_joint, target_pose, arm_id="left_arm"): """Compute inverse kinematics using Mink. @@ -729,40 +752,28 @@ def compute_simple_fk(self, arm_id="left_arm"): arm_id: The ID of the arm, either "left_arm" or "right_arm" Returns: - TCP pose in base link frame [x, y, z, qx, qy, qz, qw] + TCP pose in robot base frame [x, y, z, qx, qy, qz, qw] """ if arm_id == "left_arm": - # Get left gripper TCP pose from simulator position, quaternion = self.get_left_gripper_pose() elif arm_id == "right_arm": - # Get right gripper TCP pose from simulator position, quaternion = self.get_right_gripper_pose() else: raise ValueError(f"Invalid arm_id: {arm_id}") - # Transform from world frame to base link frame + # Transform from world frame to robot base frame base_position = self.robot.get_position() base_orientation = self.robot.get_orientation() - # Create transformation matrices from scipy.spatial.transform import Rotation - - # World to base transformation base_rot = Rotation.from_quat(base_orientation) - base_rot_matrix = base_rot.as_matrix() - - # TCP in world frame tcp_rot = Rotation.from_quat(quaternion) - tcp_rot_matrix = tcp_rot.as_matrix() - # Transform position: subtract base position and rotate + # Transform position and orientation relative_position = position - base_position tcp_position_base = base_rot.inv().apply(relative_position) - - # Transform orientation: compose rotations tcp_orientation_base = (base_rot.inv() * tcp_rot).as_quat() - # Return pose in base link frame [x, y, z, qx, qy, qz, qw] return np.concatenate([tcp_position_base, tcp_orientation_base]) def _init_pose(self): @@ -789,28 +800,21 @@ def _is_joint_positions_reached(self, module, target_positions, atol=0.01): current_positions = module.get_joint_positions() return np.allclose(current_positions, target_positions, atol=atol) - def _is_left_arm_motion_complete(self, atol=0.01): - """Check if left arm has reached its target position.""" + def _is_arm_motion_complete(self, atol=0.01): + """Check if arm has reached its target position.""" for module_name, target_positions in self.target_joint_positions.items(): module = getattr(self.interface, module_name) if not self._is_joint_positions_reached(module, target_positions, atol): return False return True - def _is_right_arm_motion_complete(self, atol=0.01): - """Check if right arm has reached its target position.""" - for module_name, target_positions in self.target_joint_positions.items(): - module = getattr(self.interface, module_name) - if not self._is_joint_positions_reached(module, target_positions, atol): - return False - return True - - def _move_left_arm_to_pose(self, target_position, target_orientation): - """Move left arm to target pose with IK solving and motion control. + def _move_arm_to_pose(self, target_position, target_orientation, arm_id="left_arm"): + """Move arm to target pose with IK solving and motion control. Args: target_position: Target position [x, y, z] in robot base frame target_orientation: Target orientation [qx, qy, qz, qw] in robot base frame + arm_id: The ID of the arm, either "left_arm" or "right_arm" Returns: True if motion is complete, False otherwise @@ -821,76 +825,42 @@ def _move_left_arm_to_pose(self, target_position, target_orientation): # Solve IK and start motion current_joints = self.mink_config.q - left_arm_joints = self.compute_simple_ik(current_joints, target_pose, "left_arm") - self._move_joints_to_target(self.interface.left_arm, left_arm_joints) + arm_joints = self.compute_simple_ik(current_joints, target_pose, arm_id) + arm_module = getattr(self.interface, arm_id) + self._move_joints_to_target(arm_module, arm_joints) # Store target positions for completion check - self.target_joint_positions = {"left_arm": left_arm_joints} + self.target_joint_positions = {arm_id: arm_joints} self.motion_in_progress = True # Check if motion is complete - if self._is_left_arm_motion_complete(): + if self._is_arm_motion_complete(): self.motion_in_progress = False return True return False + def _move_left_arm_to_pose(self, target_position, target_orientation): + """Move left arm to target pose""" + return self._move_arm_to_pose(target_position, target_orientation, "left_arm") + def _move_right_arm_to_pose(self, target_position, target_orientation): - """Move right arm to target pose with IK solving and motion control. - - Args: - target_position: Target position [x, y, z] in robot base frame - target_orientation: Target orientation [qx, qy, qz, qw] in robot base frame - - Returns: - True if motion is complete, False otherwise - """ - if not self.motion_in_progress: - # Prepare target pose in robot frame - target_pose = np.concatenate([target_position, target_orientation]) - - # Solve IK and start motion - current_joints = self.mink_config.q - right_arm_joints = self.compute_simple_ik(current_joints, target_pose, "right_arm") - self._move_joints_to_target(self.interface.right_arm, right_arm_joints) - - # Store target positions for completion check - self.target_joint_positions = {"right_arm": right_arm_joints} - self.motion_in_progress = True - - # Check if motion is complete - if self._is_right_arm_motion_complete(): - self.motion_in_progress = False - return True - return False + """Move right arm to target pose""" + return self._move_arm_to_pose(target_position, target_orientation, "right_arm") def get_left_gripper_pose(self): - tmat = np.eye(4) - tmat[:3,:3] = self.simulator.data.site(self.robot.namespace + "left_gripper_tcp").xmat.reshape((3,3)) - tmat[:3,3] = self.simulator.data.site(self.robot.namespace + "left_gripper_tcp").xpos - - # Extract position - position = tmat[:3, 3] - - # Extract orientation as quaternion (x, y, z, w) + """Get left gripper TCP pose in world frame""" + site_data = self.simulator.data.site(self.robot.namespace + "left_gripper_tcp") + position = site_data.xpos from scipy.spatial.transform import Rotation - rotation_matrix = tmat[:3, :3] - quaternion = Rotation.from_matrix(rotation_matrix).as_quat() - + quaternion = Rotation.from_matrix(site_data.xmat.reshape((3, 3))).as_quat() return position, quaternion def get_right_gripper_pose(self): - tmat = np.eye(4) - tmat[:3,:3] = self.simulator.data.site(self.robot.namespace + "right_gripper_tcp").xmat.reshape((3,3)) - tmat[:3,3] = self.simulator.data.site(self.robot.namespace + "right_gripper_tcp").xpos - - # Extract position - position = tmat[:3, 3] - - # Extract orientation as quaternion (x, y, z, w) + """Get right gripper TCP pose in world frame""" + site_data = self.simulator.data.site(self.robot.namespace + "right_gripper_tcp") + position = site_data.xpos from scipy.spatial.transform import Rotation - rotation_matrix = tmat[:3, :3] - quaternion = Rotation.from_matrix(rotation_matrix).as_quat() - + quaternion = Rotation.from_matrix(site_data.xmat.reshape((3, 3))).as_quat() return position, quaternion def pick_and_place_callback(self): @@ -898,42 +868,60 @@ def pick_and_place_callback(self): def init_state(): """Move to initial pose""" - # Convert world frame pose to robot frame - world_pos = np.array([0.5, 0.3, 0.7]) - world_ori = np.array([0, 0.7071, 0, 0.7071]) - robot_pos, robot_ori = self.world_to_robot_frame(world_pos, world_ori) + robot_pos = np.array([0.5, 0.3, 0.7]) + robot_ori = np.array([0, 0.7071, 0, 0.7071]) return self._move_left_arm_to_pose(robot_pos, robot_ori) def move_to_pre_pick_state(): """Move to pre-pick position""" + # Get cube position from estimation or cached value if self.state_first_entry: - # Use pose estimation to get object pose instead of ground truth + # Estimate object position on first entry pose_result = self.get_object_pose_from_estimation("cube") - world_pos, world_ori = pose_result - self.cube_position = world_pos.copy() - self.cube_orientation = world_ori.copy() - print(f"Pose estimation detected cube at position: {world_pos}") + if pose_result is None: + print("Failed to estimate cube pose, cannot move to pick state.") + return False + robot_pos, robot_ori = pose_result + # Cache for subsequent use + self.cube_position = robot_pos.copy() + self.cube_orientation = robot_ori.copy() self.state_first_entry = False - - # Convert world frame pose to robot frame - world_pos = self.cube_position + np.array([0, 0, 0.15]) - world_ori = np.array([0, 0.7071, 0, 0.7071]) # Fixed orientation for grasping - robot_pos, robot_ori = self.world_to_robot_frame(world_pos, world_ori) - return self._move_left_arm_to_pose(robot_pos, robot_ori) + else: + # Use cached cube position + robot_pos = getattr(self, "cube_position", None) + robot_ori = getattr(self, "cube_orientation", None) + if robot_pos is None or robot_ori is None: + print("Cube position/orientation not set, cannot move to pick state.") + return False + + # Move to pre-pick position (offset above cube) + pre_pick_pos = robot_pos + np.array([0, 0, 0.2]) + return self._move_left_arm_to_pose(pre_pick_pos, robot_ori) + def move_to_pick_state(): """Move to pick position""" + # Get cube position from estimation or cached value if self.state_first_entry: - # Re-estimate object position for more accurate pick (only once) + # Estimate object position on first entry pose_result = self.get_object_pose_from_estimation("cube") - world_pos, world_ori = pose_result - # Use estimated position for more accurate pick - self.pick_pos = world_pos + np.array([0, 0, 0.03]) + if pose_result is None: + print("Failed to estimate cube pose, cannot move to pick state.") + return False + robot_pos, robot_ori = pose_result + # Cache for subsequent use + self.cube_position = robot_pos.copy() + self.cube_orientation = robot_ori.copy() self.state_first_entry = False - - # Convert world frame pose to robot frame - world_ori = np.array([0, 0.7071, 0, 0.7071]) # Fixed orientation for grasping - robot_pos, robot_ori = self.world_to_robot_frame(self.pick_pos, world_ori) + else: + # Use cached cube position + robot_pos = getattr(self, "cube_position", None) + robot_ori = getattr(self, "cube_orientation", None) + if robot_pos is None or robot_ori is None: + print("Cube position/orientation not set, cannot move to pick state.") + return False + + # Move to pick position return self._move_left_arm_to_pose(robot_pos, robot_ori) def grasp_state(): @@ -950,28 +938,29 @@ def grasp_state(): def move_to_pre_place_state(): """Move to pre-place position""" - # Convert world frame pose to robot frame - world_pos = self.cube_position + np.array([-0.1, 0, 0.4]) - world_ori = np.array([0, 0.7071, 0, 0.7071]) - robot_pos, robot_ori = self.world_to_robot_frame(world_pos, world_ori) - return self._move_left_arm_to_pose(robot_pos, robot_ori) + # Move to pre-place position relative to cube + pre_place_pos = self.cube_position + np.array([-0.1, 0, 0.4]) + pre_place_ori = np.array([0, 0.7071, 0, 0.7071]) + return self._move_left_arm_to_pose(pre_place_pos, pre_place_ori) def move_to_place_state(): """Move to place position""" if self.state_first_entry: - # Use pose estimation to get bin pose instead of ground truth + # Use pose estimation to get bin pose pose_result = self.get_object_pose_from_estimation("bin") - world_pos, world_ori = pose_result - self.bin_position = world_pos.copy() - self.bin_orientation = world_ori.copy() - print(f"Pose estimation detected bin at position: {world_pos}") + if pose_result is None: + print("Failed to estimate bin pose, cannot move to place state.") + return False + robot_pos, robot_ori = pose_result + self.bin_position = robot_pos.copy() + self.bin_orientation = robot_ori.copy() + print(f"Pose estimation detected bin at position: {robot_pos}") self.state_first_entry = False - # Convert world frame pose to robot frame - world_pos = self.bin_position + np.array([0, 0, 0.3]) - world_ori = np.array([0, 0.7071, 0, 0.7071]) # Fixed orientation for placing - robot_pos, robot_ori = self.world_to_robot_frame(world_pos, world_ori) - return self._move_left_arm_to_pose(robot_pos, robot_ori) + # Move to place position above bin + place_pos = self.bin_position + np.array([0, 0, 0.3]) + place_ori = np.array([0, 0.7071, 0, 0.7071]) # Fixed orientation for placing + return self._move_left_arm_to_pose(place_pos, place_ori) def release_state(): """Release the object""" diff --git a/examples/ioai_examples/ioai_test_env.py b/examples/ioai_examples/ioai_test_env.py deleted file mode 100644 index 4f314d3..0000000 --- a/examples/ioai_examples/ioai_test_env.py +++ /dev/null @@ -1,121 +0,0 @@ -##################################################################################### -# Copyright (c) 2023-2025 Galbot. All Rights Reserved. -# -# This software contains confidential and proprietary information of Galbot, Inc. -# ("Confidential Information"). You shall not disclose such Confidential Information -# and shall use it only in accordance with the terms of the license agreement you -# entered into with Galbot, Inc. -# -# UNAUTHORIZED COPYING, USE, OR DISTRIBUTION OF THIS SOFTWARE, OR ANY PORTION OR -# DERIVATIVE THEREOF, IS STRICTLY PROHIBITED. IF YOU HAVE RECEIVED THIS SOFTWARE IN -# ERROR, PLEASE NOTIFY GALBOT, INC. IMMEDIATELY AND DELETE IT FROM YOUR SYSTEM. -##################################################################################### -# _____ _ _ _ _ -# / ____| | | | | | \ | | -# | (___ _ _ _ __ | |_| |__ | \| | _____ ____ _ -# \___ \| | | | '_ \| __| '_ \ | . ` |/ _ \ \ / / _` | -# ____) | |_| | | | | |_| | | | | |\ | (_) \ V / (_| | -# |_____/ \__, |_| |_|\__|_| |_| |_| \_|\___/ \_/ \__,_| -# __/ | -# |___/ -# -##################################################################################### -# -# Description: A test env code for setting up ioai -# Author: Chenyu Cao@Galbot -# Date: 2025-07-24 -# -##################################################################################### - -from physics_simulator import PhysicsSimulator -from synthnova_config import PhysicsSimulatorConfig, ScenarioConfig, MujocoConfig -from physics_simulator.galbot_interface import GalbotInterface, GalbotInterfaceConfig -from pathlib import Path - -class IoaiTestEnv: - def __init__(self, headless=False): - self.simulator = None - self.robot = None - self.interface = None - - self._setup_simulator(headless) - self._setup_interface() - self._init_pose() - - def _setup_simulator(self, headless=False): - sn_config = PhysicsSimulatorConfig( - mujoco_config=MujocoConfig(headless=headless) - ) - - scenario_config = ScenarioConfig.load_from_file( - Path() - .joinpath(PhysicsSimulator.get_root_directory()) - .joinpath("assets") - .joinpath("synthnova_assets") - .joinpath("scenarios") - .joinpath("ioai_test_scenario_grasp.json") - ) - sn_config.scenario_config = scenario_config - - self.simulator = PhysicsSimulator(sn_config) - self.simulator.initialize() - - self.robot = self.simulator.get_robot("/World/Galbot") - - def _setup_interface(self): - self.interface = GalbotInterface( - galbot_interface_config=self.galbot_interface_config, - simulator=self.simulator - ) - self.interface.initialize() - - def _setup_interface(self): - config = GalbotInterfaceConfig() - config.robot.prim_path = "/World/Galbot" - - robot_name = self.robot.name - config.modules_manager.enabled_modules.extend([ - "right_arm", "left_arm", "leg", "head", "chassis" - ]) - - # Joint configurations - config.right_arm.joint_names = [f"{robot_name}/right_arm_joint{i}" for i in range(1, 8)] - config.left_arm.joint_names = [f"{robot_name}/left_arm_joint{i}" for i in range(1, 8)] - config.leg.joint_names = [f"{robot_name}/leg_joint{i}" for i in range(1, 5)] - config.head.joint_names = [f"{robot_name}/head_joint{i}" for i in range(1, 3)] - config.chassis.joint_names = [ - f"{robot_name}/mobile_forward_joint", - f"{robot_name}/mobile_side_joint", - f"{robot_name}/mobile_yaw_joint", - ] - - # sensor configurations - config.modules_manager.enabled_modules.append("front_head_camera") - config.front_head_camera.prim_path_rgb = "/World/Galbot/head_link2/head_end_effector_mount_link/front_head_rgb_camera" - config.front_head_camera.prim_path_depth = "/World/Galbot/head_link2/head_end_effector_mount_link/front_head_depth_camera" - - self.interface = GalbotInterface(galbot_interface_config=config, simulator=self.simulator) - self.interface.initialize() - - def _init_pose(self): - # Initialize robot pose - poses = { - self.interface.head: [0.0, 0.0], - self.interface.leg: [0.0835, 0.635, 0.523, 0.0], - self.interface.left_arm: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], - self.interface.right_arm: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] - } - - for module, pose in poses.items(): - module.set_joint_positions(pose, immediate=True) - - def run(self): - self.simulator.loop() - - def close(self): - self.simulator.close() - -if __name__ == "__main__": - env = IoaiTestEnv(headless=False) - env.run() - env.close() \ No newline at end of file diff --git a/examples/ioai_examples/main.py b/examples/ioai_examples/main.py new file mode 100644 index 0000000..fd26210 --- /dev/null +++ b/examples/ioai_examples/main.py @@ -0,0 +1,276 @@ +# This software contains confidential and proprietary information of Galbot, Inc. +# ("Confidential Information"). You shall not disclose such Confidential Information +# and shall use it only in accordance with the terms of the license agreement you +# entered into with Galbot, Inc. +# +# UNAUTHORIZED COPYING, USE, OR DISTRIBUTION OF THIS SOFTWARE, OR ANY PORTION OR +# DERIVATIVE THEREOF, IS STRICTLY PROHIBITED. IF YOU HAVE RECEIVED THIS SOFTWARE IN +# ERROR, PLEASE NOTIFY GALBOT, INC. IMMEDIATELY AND DELETE IT FROM YOUR SYSTEM. +##################################################################################### +# _____ _ _ _ _ +# / ____| | | | | | \ | | +# | (___ _ _ _ __ | |_| |__ | \| | _____ ____ _ +# \___ \| | | | '_ \| __| '_ \ | . ` |/ _ \ \ / / _` | +# ____) | |_| | | | | |_| | | | | |\ | (_) \ V / (_| | +# |_____/ \__, |_| |_|\__|_| |_| |_| \_|\___/ \_/ \__,_| +# __/ | +# |___/ +# +##################################################################################### +# +# Description: a rough pipeline for IOAI env +# Author: Chenyu Cao@Galbot +# Date: 2025-07-28 +# +##################################################################################### + +from ioai_env import IOAIEnv +import numpy as np +from physics_simulator.utils.state_machine import SimpleStateMachine +from physics_simulator.utils.data_types import JointTrajectory +import math + +# ---------- Init env --------- +env = IOAIEnv(headless=False) + +# ---------- Useful functions --------- +def interpolate_joint_positions(start_positions, end_positions, steps): + return np.linspace(start_positions, end_positions, steps).tolist() + +# ---------- Init Grasp Reg --------- +# It is a simple toolbox to generate a grsping pose from the detected pose +# you can modify this as well +from grasp_reg import GraspRegistration +grasp_reg = GraspRegistration() + +# --------- Pose Estimator ------ + +class BasePoseEstimator: + def __init__(self): + pass + + def estimate_pose(self, object_name): + pass + +class DummyPoseEstimator: + def __init__(self): + pass + + # NOTE: You need to change the dummy pose estimator to the vision-based one + # A state-based method, which you can only get the basic scores + def estimate_pose(self, object_name): + if object_name == "cube": + cube_prim_path = "/World/Cube" + cube_state = env.simulator.get_object_state(cube_prim_path) + return cube_state["position"], cube_state["orientation"] + elif object_name == "power_drill": + power_drill_prim_path = "/World/PowerDrill" + power_drill_state = env.simulator.get_object_state(power_drill_prim_path) + return power_drill_state["position"], power_drill_state["orientation"] + elif object_name == "extrusion": + extrusion_prim_path = "/World/Extrusion" + extrusion_state = env.simulator.get_object_state(extrusion_prim_path) + return extrusion_state["position"], extrusion_state["orientation"] + elif object_name == "cone": + cone_prim_path = "/World/Cone" + cone_state = env.simulator.get_object_state(cone_prim_path) + return cone_state["position"], cone_state["orientation"] + elif object_name == "bin": + bin_prim_path = "/World/Bin" + bin_state = env.simulator.get_object_state(bin_prim_path) + return bin_state["position"], bin_state["orientation"] + elif object_name == "toy": + raise NotImplementedError("Toy is not implemented yet") + else: + raise ValueError(f"Unknown object name: {object_name}") + + return np.array([0.0, 0.0, 0.0]), np.array([0.0, 0.0, 0.0, 1.0]) + +pose_estimator = DummyPoseEstimator() + +# ---- Init State Machine ------ +state_machine = SimpleStateMachine(max_states=-1) +state_machine.state_first_entry = True +state_machine.object_name = "cube" +# ----- define your states here ----- +# You need to plan a set of waypoints +def move_to_table_state(): + if state_machine.state_first_entry: + env.move_chassis_follow_path([[0, 4], [0, 2], [0, -0.2]]) + state_machine.state_first_entry = False + return not env.simulator.physics_callback_exists("follow_path_callback") + +def front_to_table_state(): + if state_machine.state_first_entry: + env.move_chassis_rotate(0) + state_machine.state_first_entry = False + return not env.simulator.physics_callback_exists("rotate_callback") + +def init_state(): + if state_machine.state_first_entry: + robot_pos = np.array([0.5, 0.1, 0.8]) + robot_ori = np.array([0, 0.7071, 0, 0.7071]) + env.move_left_arm_to_pose(robot_pos, robot_ori) + state_machine.state_first_entry = False + return not env.simulator.physics_callback_exists("LeftArm_follow_trajectory_callback") + +def detect_object_state(): + object_name = state_machine.object_name + pose = pose_estimator.estimate_pose(object_name) + if pose is None: + return False + state_machine.object_pose = pose + state_machine.grasp_pose = grasp_reg.predict_grasp(object_name, np.concatenate([pose[0], pose[1]]))['grasp_pose'] + return True + +def pre_grasp_state(): + if state_machine.state_first_entry: + robot_pos = state_machine.grasp_pose[:3] + np.array([0, 0, 0.2]) + robot_ori = [0, 0.7071, 0, 0.7071] + env.move_left_arm_to_pose(robot_pos, robot_ori) + state_machine.state_first_entry = False + return not env.simulator.physics_callback_exists("LeftArm_follow_trajectory_callback") + +def grasp_state(): + if state_machine.state_first_entry: + robot_pos = state_machine.grasp_pose[:3] + robot_ori = state_machine.grasp_pose[3:] + env.move_left_arm_to_pose(robot_pos, robot_ori) + state_machine.state_first_entry = False + return not env.simulator.physics_callback_exists("LeftArm_follow_trajectory_callback") + +def grasp_object_state(): + if state_machine.state_first_entry: + env.interface.left_gripper.open() + state_machine.state_first_entry = False + return True + +def wait_state(): + return True + +def pre_place_state(): + return True + +def place_state(): + return True + +def release_state(): + return True + +def retrun_to_init_state(): + if state_machine.state_first_entry: + robot_pos = np.array([0.5, 0.1, 0.8]) + robot_ori = np.array([0, 0.7071, 0, 0.7071]) + env.move_left_arm_to_pose(robot_pos, robot_ori) + state_machine.state_first_entry = False + return not env.simulator.physics_callback_exists("LeftArm_follow_trajectory_callback") + +def move_to_bin_state(): + if state_machine.state_first_entry: + waypoints_1 = np.linspace([0, 0], [0, 0.9], 30).tolist() + waypoints_2 = np.linspace([0, 0.9], [0.65, 0.9], 30).tolist() + waypoints = waypoints_1 + waypoints_2 + env.move_chassis_follow_path(waypoints) + state_machine.state_first_entry = False + return not env.simulator.physics_callback_exists("follow_path_callback") + +def front_to_bin_state(): + if state_machine.state_first_entry: + env.move_chassis_rotate(-math.pi / 2) + state_machine.state_first_entry = False + return not env.simulator.physics_callback_exists("rotate_callback") + +def detect_bin_state(): + return True + +def navigate_to_shelf_state(): + return True + +def front_to_shelf_state(): + return True + +def place_bin_state(): + return True +state_machine.add_state(16, "Detect bin", detect_bin_state) +# ----- Initialize state machine ----- +state_machine.add_state(0, "Init", init_state) +state_machine.add_state(1, "Move to table", move_to_table_state) +state_machine.add_state(2, "Front to table", front_to_table_state) +state_machine.add_state(3, "Detect Object", detect_object_state) +state_machine.add_state(4, "Move to Pre Grasp", pre_grasp_state) +state_machine.add_state(5, "Move to Grasp State", grasp_state) +state_machine.add_state(6, "Grasp the object", grasp_object_state) +state_machine.add_state(7, "Wait for 3 seconds", wait_state) +state_machine.add_state(7, "Move to Pre Place State", pre_place_state) +state_machine.add_state(8, "Move to Place State", place_state) +state_machine.add_state(9, "Release the object", release_state) +state_machine.add_state(10, "Return to Init State", retrun_to_init_state) +state_machine.add_state(11, "Move to bin", move_to_bin_state) +state_machine.add_state(12, "Front to bin", front_to_bin_state) +state_machine.add_state(13, "Navigate to shelf", navigate_to_shelf_state) +state_machine.add_state(14, "Front to shelf", front_to_shelf_state) +state_machine.add_state(15, "Place bin", place_bin_state) +state_machine.add_state(16, "", detect_bin_state) + +# ----- please define your callbacks here ----- + +def ioai_main_callback(): + # First check if this is a new state (trigger should be called first) + if state_machine.trigger(): + state_machine.state_first_entry = True + print(f"Current state: {state_machine.get_state_name()}") + + # Then execute current state and move to next when complete + if state_machine.execute_current_state(): + # TODO: define your custom state transition logic + if state_machine.state_idx == 10: + if state_machine.object_name == "cube": + state_machine.object_name = "power_drill" + state_machine.state_idx = 3 + state_machine.state_first_entry = True + elif state_machine.object_name == "power_drill": + state_machine.object_name = "extrusion" + state_machine.state_idx = 3 + state_machine.state_first_entry = True + elif state_machine.object_name == "extrusion": + # Move on + state_machine.state_idx = 11 + state_machine.state_first_entry = True + + # Default: normal state progression + else: + # Normal state progression + if not state_machine.next(): + # Task completed, reset state machine for next cycle + print("Task completed!") + state_machine.reset() + + +env.simulator.add_physics_callback("ioai_main_callback", ioai_main_callback) + +# ---------- Add referee --------- +# The referee will check the rules and give scores +# You can modify the rules in referee/rules.json +import os +try: + from ..referee.referee import Referee +except ImportError: + import sys + sys.path.append(os.path.join(os.path.dirname(os.path.abspath(__file__)), "../referee")) + from referee import Referee +referee = Referee(env.simulator.model._model, os.path.join(os.path.dirname(os.path.abspath(__file__)), "../referee/rules.json")) +env.simulator.add_physics_callback("referee_callback", lambda: referee.update(env.simulator.data._data)) + +# ----------- +try: + env.run() +except KeyboardInterrupt: + print("Simulation interrupted by user.") +finally: + print("-" * 100) + referee.save_results() + print(f"Total score: {referee.total_score}") + print(f"Task status:") + for k, v in referee.task_status.items(): + print(f" {k}: {v['status']} (sim_time: {v['sim_time']})") + print("-" * 100) \ No newline at end of file diff --git a/examples/ioai_examples/run_yolo_pose_est_grasp.py b/examples/ioai_examples/run_yolo_pose_est_grasp.py index 6d35e3c..3a7b1d3 100644 --- a/examples/ioai_examples/run_yolo_pose_est_grasp.py +++ b/examples/ioai_examples/run_yolo_pose_est_grasp.py @@ -15,7 +15,8 @@ def main(): # Configuration paths # yolo_model_path = script_dir / ".." / "yolo_seg_examples" / "real_all_class_0730.pt" - yolo_model_path = script_dir / ".." / "yolo_seg_examples" / "best.pt" + # yolo_model_path = script_dir / ".." / "yolo_seg_examples" / "best.pt" + yolo_model_path = script_dir / ".." / "yolo_seg_examples" / "cotrain_all_class_0730.pt" cad_models_dir = script_dir / ".." / "pose_est_examples" / "models" # Camera intrinsic parameters (adjust based on your camera) diff --git a/examples/ioai_examples/yolo_pose_estimation_model.py b/examples/ioai_examples/yolo_pose_estimation_model.py index ff4e8b8..84a27c2 100644 --- a/examples/ioai_examples/yolo_pose_estimation_model.py +++ b/examples/ioai_examples/yolo_pose_estimation_model.py @@ -10,11 +10,8 @@ from pathlib import Path # Import pose estimation module -import sys -sys.path.append(os.path.join(os.path.dirname(__file__), '..', 'pose_est_examples')) -from pose_est import PoseEstimator - -from ioai_grasp_env import PoseEstimationResult, PoseEstimationModel +from physics_simulator.utils.pose_estimation import PoseEstimator +from physics_simulator.utils.pose_estimation import PoseEstimationResult, PoseEstimationModel from physics_simulator.utils import preprocess_depth @@ -30,7 +27,6 @@ def __init__(self, yolo_model_path: str, cad_models_dir: str, camera_matrix: Lis cad_models_dir: Directory containing CAD models (.obj files) camera_matrix: Camera intrinsic parameters [fx, fy, cx, cy] """ - super().__init__() self.yolo_model_path = yolo_model_path self.cad_models_dir = Path(cad_models_dir) self.camera_matrix = camera_matrix @@ -141,18 +137,15 @@ def _estimate_single_pose(self, rgb_image: np.ndarray, depth_image: np.ndarray, cv2.imwrite(str(mask_temp), mask_binary) # Get CAD model path - cad_path = self.available_models[class_name.lower()] + cad_name = class_name.lower() # Run pose estimation pose_matrix = self.pose_estimator.estimate_pose( rgb_path=str(rgb_temp), depth_path=str(depth_temp), mask_path=str(mask_temp), - cad_path=cad_path + cad_name=cad_name ) - - if class_name == "cube": - print("1") # Clean up temporary files for temp_file in [rgb_temp, depth_temp, mask_temp]: @@ -182,4 +175,31 @@ def _estimate_single_pose(self, rgb_image: np.ndarray, depth_image: np.ndarray, except Exception as e: print(f"Error estimating pose for {class_name}: {e}") - return None \ No newline at end of file + return None + + +def create_yolo_pose_estimation_model( + yolo_model_path: str = "examples/yolo_seg_examples/best.pt", + cad_models_dir: str = "examples/pose_est_examples/models", + camera_matrix: List[float] = None +) -> YoloPoseEstimationModel: + """ + Factory function to create YOLO pose estimation model with default parameters + + Args: + yolo_model_path: Path to YOLO segmentation model + cad_models_dir: Directory containing CAD models (.obj files) + camera_matrix: Camera intrinsic parameters [fx, fy, cx, cy] + + Returns: + YoloPoseEstimationModel instance + """ + # Default camera matrix for RealSense D436 + if camera_matrix is None: + camera_matrix = [637.7254326533274, 637.7254326533274, 640.0, 360.0] # [fx, fy, cx, cy] + + return YoloPoseEstimationModel( + yolo_model_path=yolo_model_path, + cad_models_dir=cad_models_dir, + camera_matrix=camera_matrix + ) \ No newline at end of file diff --git a/examples/referee/referee.py b/examples/referee/referee.py new file mode 100644 index 0000000..f8581a3 --- /dev/null +++ b/examples/referee/referee.py @@ -0,0 +1,207 @@ +import os +import json +import time +import numpy as np +from scipy.spatial.transform import Rotation + +import mujoco + +SUFFIX = "_main" +ROBOT_NAME = "galbot_one_foxtrot" + +class Referee: + invalid_names = set() + def __init__(self, mj_model, rules_file_path): + self.time_stamp = time.time() + self.mj_model = mj_model + self.rules = json.load(open(rules_file_path, 'r', encoding='utf-8')) + for k in self.rules: + self.rules[k]['status'] = None + self.rules[k]['sim_time'] = None + + def update(self, mj_data): + self.mj_data = mj_data + sim_time = self.mj_data.time + + for k, v in self.rules.items(): + # Check if the rule is already satisfied + if v['status'] in ["success", "fail"]: + continue + + # Check if prerequisites are met + prerequisite_done = True + if "prerequisite" in v: + for prereq in v['prerequisite']: + if self.rules[prereq]['status'] != "success": + prerequisite_done = False + break + if not prerequisite_done: + continue + + # Check if before until + if "until" in v and self.rules[v['until']]['status'] == "success": + if v['status'] is None: + v['sim_time'] = sim_time + v['status'] = "success" + print(f"{sim_time:5.2f}s: '{k}' succeeded, get score {self.rules[k]['score']}.") + continue + + if v['type'] == 'in_2d_range': + if self.check_in_2d_range(v['range']): + v['status'] = "success" + + elif v['type'] == 'in_3d_range': + if self.check_in_3d_range(v['object1_name'], v['range'], v.get('object2_name', None)): + v['status'] = "success" + + elif v['type'] == 'no_collision': + for group in v['collision_group']: + robot_bodies = group[0] + obstacle_bodies = group[1] + collision_detected = False + for robot_body in robot_bodies: + for obstacle_body in obstacle_bodies: + if self.check_contact(robot_body, obstacle_body): + collision_detected = True + break + if collision_detected: + break + if collision_detected: + v['status'] = "fail" + break + + elif v['type'] == 'pick_up': + if (self.check_contact(f"{ROBOT_NAME}/left_gripper_r_finger_link", v['object1_name']) and \ + self.check_contact(f"{ROBOT_NAME}/left_gripper_l_finger_link", v['object1_name']) \ + ) or ( \ + self.check_contact(f"{ROBOT_NAME}/right_gripper_r_finger_link", v['object1_name']) and \ + self.check_contact(f"{ROBOT_NAME}/right_gripper_l_finger_link", v['object1_name']) \ + ): + v['status'] = "success" + + elif v['type'] == 'pick_up_dual': + if self.check_contact(f"{ROBOT_NAME}/left_gripper_r_finger_link", v['object1_name']) and \ + self.check_contact(f"{ROBOT_NAME}/left_gripper_l_finger_link", v['object1_name']) and \ + self.check_contact(f"{ROBOT_NAME}/right_gripper_r_finger_link", v['object1_name']) and \ + self.check_contact(f"{ROBOT_NAME}/right_gripper_l_finger_link", v['object1_name']): + v['status'] = "success" + + if v['status'] == "fail": + self.rules[k]['sim_time'] = sim_time + print(f"{sim_time:5.2f}s: '{k}' failed.") + elif v['status'] == "success": + self.rules[k]['sim_time'] = sim_time + print(f"{sim_time:5.2f}s: '{k}' succeeded, get score {self.rules[k]['score']}.") + + def get_body_tmat(self, body_name): + body_name += SUFFIX if not body_name.endswith(SUFFIX) else "" + tmat = np.eye(4) + tmat[:3,:3] = Rotation.from_quat(self.mj_data.body(body_name).xquat[[1,2,3,0]]).as_matrix() + tmat[:3,3] = self.mj_data.body(body_name).xpos + return tmat + + def check_in_2d_range(self, range): + robot_posi = self.mj_data.body(f"{ROBOT_NAME}/omni_chassis_base_link").xpos + return (range['x'][0] <= robot_posi[0] <= range['x'][1]) and (range['y'][0] <= robot_posi[1] <= range['y'][1]) + + def check_in_3d_range(self, object_name, range_3d, ref_body_name=None): + ref_body_tmat = self.get_body_tmat(ref_body_name) if ref_body_name else np.eye(4) + object_tmat = self.get_body_tmat(object_name) + object_wrt_ref = np.linalg.inv(ref_body_tmat) @ object_tmat + ref_posi = object_wrt_ref[:3, 3] + return (range_3d['x'][0] <= ref_posi[0] <= range_3d['x'][1]) and \ + (range_3d['y'][0] <= ref_posi[1] <= range_3d['y'][1]) and \ + (range_3d['z'][0] <= ref_posi[2] <= range_3d['z'][1]) + + def check_contact(self, body1, body2): + body1 += SUFFIX if (not body1.endswith(SUFFIX) and not body1.startswith(f"{ROBOT_NAME}/")) else "" + body2 += SUFFIX if (not body2.endswith(SUFFIX) and not body2.startswith(f"{ROBOT_NAME}/")) else "" + try: + body1_gemo_id_range = (self.mj_model.body(body1).geomadr[0], self.mj_model.body(body1).geomadr[0]+self.mj_model.body(body1).geomnum[0]) + except KeyError: + if body1 not in self.invalid_names: + print(f"Warning: Body '{body1}' not found in the model.") + self.invalid_names.add(body1) + return False + try: + body2_gemo_id_range = (self.mj_model.body(body2).geomadr[0], self.mj_model.body(body2).geomadr[0]+self.mj_model.body(body2).geomnum[0]) + except KeyError: + if body2 not in self.invalid_names: + print(f"Warning: Body '{body2}' not found in the model.") + self.invalid_names.add(body2) + return False + b1r = body1_gemo_id_range if body1_gemo_id_range[0] < body2_gemo_id_range[0] else body2_gemo_id_range + b2r = body2_gemo_id_range if body1_gemo_id_range[0] < body2_gemo_id_range[0] else body1_gemo_id_range + + for i in range(self.mj_data.ncon): + geom_id = sorted(self.mj_data.contact.geom[i].tolist()) + if b1r[0] <= geom_id[0] < b1r[1] and b2r[0] <= geom_id[1] < b2r[1]: + return True + return False + + @property + def total_score(self): + total_score = 0 + for k, v in self.rules.items(): + if v['status']: + total_score += v['score'] + return total_score + + @property + def task_status(self): + status = {} + for k, v in self.rules.items(): + status[k] = { + "status": v['status'], + "sim_time": v['sim_time'], + "score": v['score'] if v['status'] == "success" else 0 + } + return status + + def save_results(self, file_path=None): + if file_path is None: + file_path = os.path.join(os.path.dirname(__file__), f'results_{time.strftime("%Y_%m_%d-%H_%M_%S", time.localtime(self.time_stamp))}.json') + else: + file_path = file_path.replace('.json', f'_{time.strftime("%Y_%m_%d-%H_%M_%S", time.localtime(self.time_stamp))}.json') + with open(file_path, 'w', encoding='utf-8') as f: + res = {} + res["total_score"] = self.total_score + res.update(self.task_status) + json.dump(res, f, indent=4, ensure_ascii=False) + print(f"Results saved to {file_path}") + + +if __name__ == "__main__": + print("Running referee example...") + + print(""" + # make a env + env = None + + # ---------- Add referee --------- + # The referee will check the rules and give scores + # You can modify the rules in referee/rules.json + import os + try: + from ..referee.referee import Referee + except ImportError: + import sys + sys.path.append(os.path.join(os.path.dirname(os.path.abspath(__file__)), "../referee")) + from referee import Referee + referee = Referee(env.simulator.model._model, os.path.join(os.path.dirname(os.path.abspath(__file__)), "../referee/rules.json")) + env.simulator.add_physics_callback("referee_callback", lambda: referee.update(env.simulator.data._data)) + + # ----------- + try: + env.run() + except KeyboardInterrupt: + print("Simulation interrupted by user.") + finally: + print("-" * 100) + referee.save_results() + print(f"Total score: /{referee.total_score/}") + print(f"Task status:") + for k, v in referee.task_status.items(): + print(f" /{k/}: {v['status']} (sim_time: {v['sim_time']})") + print("-" * 100) + """) \ No newline at end of file diff --git a/examples/referee/referee_plt.ipynb b/examples/referee/referee_plt.ipynb new file mode 100644 index 0000000..d808d8a --- /dev/null +++ b/examples/referee/referee_plt.ipynb @@ -0,0 +1,587 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "id": "cd154629", + "metadata": {}, + "outputs": [ + { + "ename": "TypeError", + "evalue": "unhashable type: 'dict'", + "output_type": "error", + "traceback": [ + "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", + "\u001b[0;31mTypeError\u001b[0m Traceback (most recent call last)", + "Cell \u001b[0;32mIn[1], line 1\u001b[0m\n\u001b[0;32m----> 1\u001b[0m scoling_rules \u001b[38;5;241m=\u001b[39m {\n\u001b[1;32m 2\u001b[0m {\n\u001b[1;32m 3\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m成功移动到桌子面前\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 4\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m1\u001b[39m,\n\u001b[1;32m 5\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m5\u001b[39m,\n\u001b[1;32m 6\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124min_2d_range\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 7\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mrange\u001b[39m\u001b[38;5;124m'\u001b[39m : {\n\u001b[1;32m 8\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mx\u001b[39m\u001b[38;5;124m\"\u001b[39m : [\u001b[38;5;241m-\u001b[39m\u001b[38;5;241m0.35\u001b[39m, \u001b[38;5;241m0.1\u001b[39m],\n\u001b[1;32m 9\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124my\u001b[39m\u001b[38;5;124m\"\u001b[39m : [\u001b[38;5;241m-\u001b[39m\u001b[38;5;241m0.35\u001b[39m, \u001b[38;5;241m0.35\u001b[39m],\n\u001b[1;32m 10\u001b[0m }\n\u001b[1;32m 11\u001b[0m },\n\u001b[1;32m 12\u001b[0m {\n\u001b[1;32m 13\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m从出发区移动到桌子面前物体抓取区过程中没有碰撞行为\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 14\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m2\u001b[39m,\n\u001b[1;32m 15\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m5\u001b[39m,\n\u001b[1;32m 16\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mno_collision\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 17\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124muntil\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 18\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到桌子面前\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 19\u001b[0m ],\n\u001b[1;32m 20\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mcollision_group\u001b[39m\u001b[38;5;124m\"\u001b[39m : [\n\u001b[1;32m 21\u001b[0m [[\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mrobot\u001b[39m\u001b[38;5;124m\"\u001b[39m], [\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mtable\u001b[39m\u001b[38;5;124m\"\u001b[39m, \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mbasket\u001b[39m\u001b[38;5;124m\"\u001b[39m, \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mwall\u001b[39m\u001b[38;5;124m\"\u001b[39m]]\n\u001b[1;32m 22\u001b[0m ]\n\u001b[1;32m 23\u001b[0m },\n\u001b[1;32m 24\u001b[0m {\n\u001b[1;32m 25\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m成功抓取普通物品 power_drill\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 26\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m3\u001b[39m,\n\u001b[1;32m 27\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m10\u001b[39m,\n\u001b[1;32m 28\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mpick_up\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 29\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 30\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到桌子面前\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 31\u001b[0m ],\n\u001b[1;32m 32\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mobject1_name\u001b[39m\u001b[38;5;124m\"\u001b[39m : \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mpower_drill\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 33\u001b[0m },\n\u001b[1;32m 34\u001b[0m {\n\u001b[1;32m 35\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m成功抓取普通物品 cube\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 36\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m3\u001b[39m,\n\u001b[1;32m 37\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m10\u001b[39m,\n\u001b[1;32m 38\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mpick_up\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 39\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 40\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到桌子面前\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 41\u001b[0m ],\n\u001b[1;32m 42\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mobject1_name\u001b[39m\u001b[38;5;124m\"\u001b[39m : \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mcube\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 43\u001b[0m },\n\u001b[1;32m 44\u001b[0m {\n\u001b[1;32m 45\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m成功抓取普通物品 extrusion\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 46\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m3\u001b[39m,\n\u001b[1;32m 47\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m10\u001b[39m,\n\u001b[1;32m 48\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mpick_up\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 49\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 50\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到桌子面前\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 51\u001b[0m ],\n\u001b[1;32m 52\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mobject1_name\u001b[39m\u001b[38;5;124m\"\u001b[39m : \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mextrusion\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 53\u001b[0m },\n\u001b[1;32m 54\u001b[0m {\n\u001b[1;32m 55\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m成功放置物品 power_drill\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 56\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m4\u001b[39m,\n\u001b[1;32m 57\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m5\u001b[39m,\n\u001b[1;32m 58\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124min_3d_range\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 59\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 60\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功抓取普通物品 power_drill\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 61\u001b[0m ],\n\u001b[1;32m 62\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mobject1_name\u001b[39m\u001b[38;5;124m\"\u001b[39m : \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mpower_drill\u001b[39m\u001b[38;5;124m\"\u001b[39m,\n\u001b[1;32m 63\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mobject2_name\u001b[39m\u001b[38;5;124m\"\u001b[39m : \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mbasket\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 64\u001b[0m },\n\u001b[1;32m 65\u001b[0m {\n\u001b[1;32m 66\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m成功放置物品 cube\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 67\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m4\u001b[39m,\n\u001b[1;32m 68\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m5\u001b[39m,\n\u001b[1;32m 69\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124min_3d_range\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 70\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 71\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功抓取普通物品 cube\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 72\u001b[0m ],\n\u001b[1;32m 73\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mobject1_name\u001b[39m\u001b[38;5;124m\"\u001b[39m : \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mcube\u001b[39m\u001b[38;5;124m\"\u001b[39m,\n\u001b[1;32m 74\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mobject2_name\u001b[39m\u001b[38;5;124m\"\u001b[39m : \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mbasket\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 75\u001b[0m },\n\u001b[1;32m 76\u001b[0m {\n\u001b[1;32m 77\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m成功放置物品 extrusion\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 78\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m4\u001b[39m,\n\u001b[1;32m 79\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m5\u001b[39m,\n\u001b[1;32m 80\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124min_3d_range\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 81\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 82\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功抓取普通物品 extrusion\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 83\u001b[0m ],\n\u001b[1;32m 84\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mobject1_name\u001b[39m\u001b[38;5;124m\"\u001b[39m : \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mextrusion\u001b[39m\u001b[38;5;124m\"\u001b[39m,\n\u001b[1;32m 85\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mobject2_name\u001b[39m\u001b[38;5;124m\"\u001b[39m : \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mbasket\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 86\u001b[0m },\n\u001b[1;32m 87\u001b[0m {\n\u001b[1;32m 88\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m抓取到放置中没有碰撞(桌子、料框、围挡)\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 89\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m5\u001b[39m,\n\u001b[1;32m 90\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m5\u001b[39m,\n\u001b[1;32m 91\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mno_collision\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 92\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 93\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功抓取普通物品 power_drill\u001b[39m\u001b[38;5;124m\"\u001b[39m,\n\u001b[1;32m 94\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功抓取普通物品 cube\u001b[39m\u001b[38;5;124m\"\u001b[39m,\n\u001b[1;32m 95\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功抓取普通物品 extrusion\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 96\u001b[0m ],\n\u001b[1;32m 97\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124muntil\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 98\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到料框抓取区(桌子侧面)\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 99\u001b[0m ],\n\u001b[1;32m 100\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mcollision_group\u001b[39m\u001b[38;5;124m\"\u001b[39m : [\n\u001b[1;32m 101\u001b[0m [[\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mrobot\u001b[39m\u001b[38;5;124m\"\u001b[39m], [\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mtable\u001b[39m\u001b[38;5;124m\"\u001b[39m, \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mbasket\u001b[39m\u001b[38;5;124m\"\u001b[39m, \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mwall\u001b[39m\u001b[38;5;124m\"\u001b[39m]]\n\u001b[1;32m 102\u001b[0m ]\n\u001b[1;32m 103\u001b[0m },\n\u001b[1;32m 104\u001b[0m {\n\u001b[1;32m 105\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m成功抓取神秘物体\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 106\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m6\u001b[39m,\n\u001b[1;32m 107\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m30\u001b[39m,\n\u001b[1;32m 108\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mpick_up\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 109\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 110\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到桌子面前\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 111\u001b[0m ],\n\u001b[1;32m 112\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mobject1_name\u001b[39m\u001b[38;5;124m\"\u001b[39m : \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mtoy\u001b[39m\u001b[38;5;124m\"\u001b[39m,\n\u001b[1;32m 113\u001b[0m \n\u001b[1;32m 114\u001b[0m },\n\u001b[1;32m 115\u001b[0m {\n\u001b[1;32m 116\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m成功把神秘物体放置到料框里\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 117\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m7\u001b[39m,\n\u001b[1;32m 118\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m5\u001b[39m,\n\u001b[1;32m 119\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124min_3d_range\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 120\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 121\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功抓取神秘物体\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 122\u001b[0m ],\n\u001b[1;32m 123\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mobject1_name\u001b[39m\u001b[38;5;124m\"\u001b[39m : \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mtoy\u001b[39m\u001b[38;5;124m\"\u001b[39m,\n\u001b[1;32m 124\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mobject2_name\u001b[39m\u001b[38;5;124m\"\u001b[39m : \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mbasket\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 125\u001b[0m },\n\u001b[1;32m 126\u001b[0m {\n\u001b[1;32m 127\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m神秘物体放置到料框的过程中没有碰撞行为\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 128\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m8\u001b[39m,\n\u001b[1;32m 129\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m5\u001b[39m,\n\u001b[1;32m 130\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mno_collision\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 131\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 132\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功抓取神秘物体\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 133\u001b[0m ],\n\u001b[1;32m 134\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124muntil\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 135\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到料框抓取区(桌子侧面)\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 136\u001b[0m ],\n\u001b[1;32m 137\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mcollision_group\u001b[39m\u001b[38;5;124m\"\u001b[39m : [\n\u001b[1;32m 138\u001b[0m [[\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mrobot\u001b[39m\u001b[38;5;124m\"\u001b[39m], [\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mtable\u001b[39m\u001b[38;5;124m\"\u001b[39m, \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mbasket\u001b[39m\u001b[38;5;124m\"\u001b[39m, \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mwall\u001b[39m\u001b[38;5;124m\"\u001b[39m]]\n\u001b[1;32m 139\u001b[0m ]\n\u001b[1;32m 140\u001b[0m },\n\u001b[1;32m 141\u001b[0m {\n\u001b[1;32m 142\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m成功移动到料框抓取区(桌子侧面)\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 143\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m9\u001b[39m,\n\u001b[1;32m 144\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m5\u001b[39m,\n\u001b[1;32m 145\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124min_2d_range\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 146\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 147\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到桌子面前\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 148\u001b[0m ],\n\u001b[1;32m 149\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mrange\u001b[39m\u001b[38;5;124m\"\u001b[39m : {\n\u001b[1;32m 150\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mx\u001b[39m\u001b[38;5;124m\"\u001b[39m : [\u001b[38;5;241m0.4\u001b[39m, \u001b[38;5;241m0.9\u001b[39m],\n\u001b[1;32m 151\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124my\u001b[39m\u001b[38;5;124m\"\u001b[39m : [\u001b[38;5;241m0.7\u001b[39m, \u001b[38;5;241m0.9\u001b[39m],\n\u001b[1;32m 152\u001b[0m }\n\u001b[1;32m 153\u001b[0m },\n\u001b[1;32m 154\u001b[0m {\n\u001b[1;32m 155\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m从物体抓取区移动到料框抓取区过程中没有碰撞行为\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 156\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m10\u001b[39m,\n\u001b[1;32m 157\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m5\u001b[39m,\n\u001b[1;32m 158\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mno_collision\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 159\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 160\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到桌子面前\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 161\u001b[0m ],\n\u001b[1;32m 162\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124muntil\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 163\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到料框抓取区(桌子侧面)\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 164\u001b[0m ],\n\u001b[1;32m 165\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mcollision_group\u001b[39m\u001b[38;5;124m\"\u001b[39m : [\n\u001b[1;32m 166\u001b[0m [[\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mrobot\u001b[39m\u001b[38;5;124m\"\u001b[39m], [\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mtable\u001b[39m\u001b[38;5;124m\"\u001b[39m, \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mbasket\u001b[39m\u001b[38;5;124m\"\u001b[39m, \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mwall\u001b[39m\u001b[38;5;124m\"\u001b[39m]]\n\u001b[1;32m 167\u001b[0m ]\n\u001b[1;32m 168\u001b[0m },\n\u001b[1;32m 169\u001b[0m {\n\u001b[1;32m 170\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m成功抓起料框\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 171\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m11\u001b[39m,\n\u001b[1;32m 172\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m10\u001b[39m,\n\u001b[1;32m 173\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mpick_up_dual\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 174\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 175\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到料框抓取区(桌子侧面)\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 176\u001b[0m ],\n\u001b[1;32m 177\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mobject1_name\u001b[39m\u001b[38;5;124m\"\u001b[39m : \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mbasket\u001b[39m\u001b[38;5;124m\"\u001b[39m,\n\u001b[1;32m 178\u001b[0m },\n\u001b[1;32m 179\u001b[0m {\n\u001b[1;32m 180\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m成功移动到货架面前\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 181\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m13\u001b[39m,\n\u001b[1;32m 182\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m5\u001b[39m,\n\u001b[1;32m 183\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124min_2d_range\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 184\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 185\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到料框抓取区(桌子侧面)\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 186\u001b[0m ],\n\u001b[1;32m 187\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mrange\u001b[39m\u001b[38;5;124m\"\u001b[39m : {\n\u001b[1;32m 188\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mx\u001b[39m\u001b[38;5;124m\"\u001b[39m : [\u001b[38;5;241m2.5\u001b[39m, \u001b[38;5;241m3.5\u001b[39m],\n\u001b[1;32m 189\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124my\u001b[39m\u001b[38;5;124m\"\u001b[39m : [\u001b[38;5;241m3.5\u001b[39m, \u001b[38;5;241m4.5\u001b[39m],\n\u001b[1;32m 190\u001b[0m }\n\u001b[1;32m 191\u001b[0m },\n\u001b[1;32m 192\u001b[0m {\n\u001b[1;32m 193\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m从料框抓取区移动到料框放置区(货架)过程中没有碰撞行为\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 194\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m14\u001b[39m,\n\u001b[1;32m 195\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m5\u001b[39m,\n\u001b[1;32m 196\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mno_collision\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 197\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 198\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功抓起料框\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 199\u001b[0m ],\n\u001b[1;32m 200\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124muntil\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 201\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到货架面前\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 202\u001b[0m ],\n\u001b[1;32m 203\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mcollision_group\u001b[39m\u001b[38;5;124m\"\u001b[39m : [\n\u001b[1;32m 204\u001b[0m [[\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mrobot\u001b[39m\u001b[38;5;124m\"\u001b[39m], [\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mtable\u001b[39m\u001b[38;5;124m\"\u001b[39m, \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mbasket\u001b[39m\u001b[38;5;124m\"\u001b[39m, \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mwall\u001b[39m\u001b[38;5;124m\"\u001b[39m, \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mtraffic_cone\u001b[39m\u001b[38;5;124m\"\u001b[39m]]\n\u001b[1;32m 205\u001b[0m ]\n\u001b[1;32m 206\u001b[0m },\n\u001b[1;32m 207\u001b[0m {\n\u001b[1;32m 208\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m成功将箱子放置到货架上\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 209\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m15\u001b[39m,\n\u001b[1;32m 210\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m10\u001b[39m,\n\u001b[1;32m 211\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124min_3d_range\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 212\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 213\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到货架面前\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 214\u001b[0m ],\n\u001b[1;32m 215\u001b[0m },\n\u001b[1;32m 216\u001b[0m {\n\u001b[1;32m 217\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m将箱子放置到货架的过程中没有碰撞行为(桌子、料框、围挡)\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 218\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m16\u001b[39m,\n\u001b[1;32m 219\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m10\u001b[39m,\n\u001b[1;32m 220\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mno_collision\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 221\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 222\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到货架面前\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 223\u001b[0m ],\n\u001b[1;32m 224\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124muntil\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 225\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到任务结束点\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 226\u001b[0m ],\n\u001b[1;32m 227\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mcollision_group\u001b[39m\u001b[38;5;124m\"\u001b[39m : [\n\u001b[1;32m 228\u001b[0m [[\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mrobot\u001b[39m\u001b[38;5;124m\"\u001b[39m], [\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mtable\u001b[39m\u001b[38;5;124m\"\u001b[39m, \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mbasket\u001b[39m\u001b[38;5;124m\"\u001b[39m, \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mwall\u001b[39m\u001b[38;5;124m\"\u001b[39m]]\n\u001b[1;32m 229\u001b[0m ]\n\u001b[1;32m 230\u001b[0m },\n\u001b[1;32m 231\u001b[0m {\n\u001b[1;32m 232\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m成功移动到任务结束点\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 233\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m5\u001b[39m,\n\u001b[1;32m 234\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m17\u001b[39m,\n\u001b[1;32m 235\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124min_2d_range\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 236\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 237\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到货架面前\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 238\u001b[0m ],\n\u001b[1;32m 239\u001b[0m },\n\u001b[1;32m 240\u001b[0m {\n\u001b[1;32m 241\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mdescription\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;124m'\u001b[39m\u001b[38;5;124m从料框放置区移动到任务结束区过程中没有碰撞行为(桌子、料框、围挡)\u001b[39m\u001b[38;5;124m'\u001b[39m, \n\u001b[1;32m 242\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtask_index\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m18\u001b[39m,\n\u001b[1;32m 243\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mscore\u001b[39m\u001b[38;5;124m'\u001b[39m: \u001b[38;5;241m5\u001b[39m,\n\u001b[1;32m 244\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mtype\u001b[39m\u001b[38;5;124m'\u001b[39m : \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mno_collision\u001b[39m\u001b[38;5;124m'\u001b[39m,\n\u001b[1;32m 245\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124mprerequisite\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 246\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到货架面前\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 247\u001b[0m ],\n\u001b[1;32m 248\u001b[0m \u001b[38;5;124m'\u001b[39m\u001b[38;5;124muntil\u001b[39m\u001b[38;5;124m'\u001b[39m : [\n\u001b[1;32m 249\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m成功移动到任务结束点\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 250\u001b[0m ],\n\u001b[1;32m 251\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mcollision_group\u001b[39m\u001b[38;5;124m\"\u001b[39m : [\n\u001b[1;32m 252\u001b[0m [[\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mrobot\u001b[39m\u001b[38;5;124m\"\u001b[39m], [\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mtable\u001b[39m\u001b[38;5;124m\"\u001b[39m, \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mbasket\u001b[39m\u001b[38;5;124m\"\u001b[39m, \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mwall\u001b[39m\u001b[38;5;124m\"\u001b[39m]]\n\u001b[1;32m 253\u001b[0m ]\n\u001b[1;32m 254\u001b[0m }\n\u001b[1;32m 255\u001b[0m }\n", + "\u001b[0;31mTypeError\u001b[0m: unhashable type: 'dict'" + ] + } + ], + "source": [ + "scoling_rules = {\n", + " {\n", + " 'description': '成功移动到桌子面前', \n", + " 'task_index': 1,\n", + " 'score': 5,\n", + " 'type' : 'in_2d_range',\n", + " 'range' : {\n", + " \"x\" : [-0.35, 0.1],\n", + " \"y\" : [-0.35, 0.35],\n", + " }\n", + " },\n", + " {\n", + " 'description': '从出发区移动到桌子面前物体抓取区过程中没有碰撞行为', \n", + " 'task_index': 2,\n", + " 'score': 5,\n", + " 'type' : 'no_collision',\n", + " 'until' : [\n", + " \"成功移动到桌子面前\"\n", + " ],\n", + " \"collision_group\" : [\n", + " [[\"robot\"], [\"table\", \"basket\", \"wall\"]]\n", + " ]\n", + " },\n", + " {\n", + " 'description': '成功抓取普通物品 power_drill', \n", + " 'task_index': 3,\n", + " 'score': 10,\n", + " 'type' : 'pick_up',\n", + " 'prerequisite' : [\n", + " \"成功移动到桌子面前\"\n", + " ],\n", + " \"object1_name\" : \"power_drill\"\n", + " },\n", + " {\n", + " 'description': '成功抓取普通物品 cube', \n", + " 'task_index': 3,\n", + " 'score': 10,\n", + " 'type' : 'pick_up',\n", + " 'prerequisite' : [\n", + " \"成功移动到桌子面前\"\n", + " ],\n", + " \"object1_name\" : \"cube\"\n", + " },\n", + " {\n", + " 'description': '成功抓取普通物品 extrusion', \n", + " 'task_index': 3,\n", + " 'score': 10,\n", + " 'type' : 'pick_up',\n", + " 'prerequisite' : [\n", + " \"成功移动到桌子面前\"\n", + " ],\n", + " \"object1_name\" : \"extrusion\"\n", + " },\n", + " {\n", + " 'description': '成功放置物品 power_drill', \n", + " 'task_index': 4,\n", + " 'score': 5,\n", + " 'type' : 'in_3d_range',\n", + " 'prerequisite' : [\n", + " \"成功抓取普通物品 power_drill\"\n", + " ],\n", + " \"object1_name\" : \"power_drill\",\n", + " \"object2_name\" : \"basket\"\n", + " },\n", + " {\n", + " 'description': '成功放置物品 cube', \n", + " 'task_index': 4,\n", + " 'score': 5,\n", + " 'type' : 'in_3d_range',\n", + " 'prerequisite' : [\n", + " \"成功抓取普通物品 cube\"\n", + " ],\n", + " \"object1_name\" : \"cube\",\n", + " \"object2_name\" : \"basket\"\n", + " },\n", + " {\n", + " 'description': '成功放置物品 extrusion', \n", + " 'task_index': 4,\n", + " 'score': 5,\n", + " 'type' : 'in_3d_range',\n", + " 'prerequisite' : [\n", + " \"成功抓取普通物品 extrusion\"\n", + " ],\n", + " \"object1_name\" : \"extrusion\",\n", + " \"object2_name\" : \"basket\"\n", + " },\n", + " {\n", + " 'description': '抓取到放置中没有碰撞(桌子、料框、围挡)', \n", + " 'task_index': 5,\n", + " 'score': 5,\n", + " 'type' : 'no_collision',\n", + " 'prerequisite' : [\n", + " \"成功抓取普通物品 power_drill\",\n", + " \"成功抓取普通物品 cube\",\n", + " \"成功抓取普通物品 extrusion\"\n", + " ],\n", + " 'until' : [\n", + " \"成功移动到料框抓取区(桌子侧面)\"\n", + " ],\n", + " \"collision_group\" : [\n", + " [[\"robot\"], [\"table\", \"basket\", \"wall\"]]\n", + " ]\n", + " },\n", + " {\n", + " 'description': '成功抓取神秘物体', \n", + " 'task_index': 6,\n", + " 'score': 30,\n", + " 'type' : 'pick_up',\n", + " 'prerequisite' : [\n", + " \"成功移动到桌子面前\"\n", + " ],\n", + " \"object1_name\" : \"toy\",\n", + " \n", + " },\n", + " {\n", + " 'description': '成功把神秘物体放置到料框里', \n", + " 'task_index': 7,\n", + " 'score': 5,\n", + " 'type' : 'in_3d_range',\n", + " 'prerequisite' : [\n", + " \"成功抓取神秘物体\"\n", + " ],\n", + " \"object1_name\" : \"toy\",\n", + " \"object2_name\" : \"basket\"\n", + " },\n", + " {\n", + " 'description': '神秘物体放置到料框的过程中没有碰撞行为', \n", + " 'task_index': 8,\n", + " 'score': 5,\n", + " 'type' : 'no_collision',\n", + " 'prerequisite' : [\n", + " \"成功抓取神秘物体\"\n", + " ],\n", + " 'until' : [\n", + " \"成功移动到料框抓取区(桌子侧面)\"\n", + " ],\n", + " \"collision_group\" : [\n", + " [[\"robot\"], [\"table\", \"basket\", \"wall\"]]\n", + " ]\n", + " },\n", + " {\n", + " 'description': '成功移动到料框抓取区(桌子侧面)', \n", + " 'task_index': 9,\n", + " 'score': 5,\n", + " 'type' : 'in_2d_range',\n", + " 'prerequisite' : [\n", + " \"成功移动到桌子面前\"\n", + " ],\n", + " \"range\" : {\n", + " \"x\" : [0.4, 0.9],\n", + " \"y\" : [0.7, 0.9],\n", + " }\n", + " },\n", + " {\n", + " 'description': '从物体抓取区移动到料框抓取区过程中没有碰撞行为', \n", + " 'task_index': 10,\n", + " 'score': 5,\n", + " 'type' : 'no_collision',\n", + " 'prerequisite' : [\n", + " \"成功移动到桌子面前\"\n", + " ],\n", + " 'until' : [\n", + " \"成功移动到料框抓取区(桌子侧面)\"\n", + " ],\n", + " \"collision_group\" : [\n", + " [[\"robot\"], [\"table\", \"basket\", \"wall\"]]\n", + " ]\n", + " },\n", + " {\n", + " 'description': '成功抓起料框', \n", + " 'task_index': 11,\n", + " 'score': 10,\n", + " 'type' : 'pick_up_dual',\n", + " 'prerequisite' : [\n", + " \"成功移动到料框抓取区(桌子侧面)\"\n", + " ],\n", + " \"object1_name\" : \"basket\",\n", + " },\n", + " {\n", + " 'description': '成功移动到货架面前', \n", + " 'task_index': 13,\n", + " 'score': 5,\n", + " 'type' : 'in_2d_range',\n", + " 'prerequisite' : [\n", + " \"成功移动到料框抓取区(桌子侧面)\"\n", + " ],\n", + " \"range\" : {\n", + " \"x\" : [2.5, 3.5],\n", + " \"y\" : [3.5, 4.5],\n", + " }\n", + " },\n", + " {\n", + " 'description': '从料框抓取区移动到料框放置区(货架)过程中没有碰撞行为', \n", + " 'task_index': 14,\n", + " 'score': 5,\n", + " 'type' : 'no_collision',\n", + " 'prerequisite' : [\n", + " \"成功抓起料框\"\n", + " ],\n", + " 'until' : [\n", + " \"成功移动到货架面前\"\n", + " ],\n", + " \"collision_group\" : [\n", + " [[\"robot\"], [\"table\", \"basket\", \"wall\", \"traffic_cone\"]]\n", + " ]\n", + " },\n", + " {\n", + " 'description': '成功将箱子放置到货架上', \n", + " 'task_index': 15,\n", + " 'score': 10,\n", + " 'type' : 'in_3d_range',\n", + " 'prerequisite' : [\n", + " \"成功移动到货架面前\"\n", + " ],\n", + " },\n", + " {\n", + " 'description': '将箱子放置到货架的过程中没有碰撞行为(桌子、料框、围挡)', \n", + " 'task_index': 16,\n", + " 'score': 10,\n", + " 'type' : 'no_collision',\n", + " 'prerequisite' : [\n", + " \"成功移动到货架面前\"\n", + " ],\n", + " 'until' : [\n", + " \"成功移动到任务结束点\"\n", + " ],\n", + " \"collision_group\" : [\n", + " [[\"robot\"], [\"table\", \"basket\", \"wall\"]]\n", + " ]\n", + " },\n", + " {\n", + " 'description': '成功移动到任务结束点', \n", + " 'score': 5,\n", + " 'task_index': 17,\n", + " 'type' : 'in_2d_range',\n", + " 'prerequisite' : [\n", + " \"成功移动到货架面前\"\n", + " ],\n", + " },\n", + " {\n", + " 'description': '从料框放置区移动到任务结束区过程中没有碰撞行为(桌子、料框、围挡)', \n", + " 'task_index': 18,\n", + " 'score': 5,\n", + " 'type' : 'no_collision',\n", + " 'prerequisite' : [\n", + " \"成功移动到货架面前\"\n", + " ],\n", + " 'until' : [\n", + " \"成功移动到任务结束点\"\n", + " ],\n", + " \"collision_group\" : [\n", + " [[\"robot\"], [\"table\", \"basket\", \"wall\"]]\n", + " ]\n", + " }\n", + "}" + ] + }, + { + "cell_type": "markdown", + "id": "09bdba75", + "metadata": {}, + "source": [ + "# 🤖 机器人任务评分规则依赖关系分析\n", + "\n", + "本notebook分析机器人任务评分规则的依赖关系,并通过可视化图形展示任务之间的依赖结构。\n", + "\n", + "## 📋 分析内容\n", + "1. **依赖关系图**: 展示任务间的前置条件和执行顺序\n", + "2. **统计分析**: 按类型、分值、依赖关系进行统计\n", + "3. **关键路径**: 识别核心任务和执行路径\n", + "\n", + "## 🎯 任务类型\n", + "- 🔵 **2D位置检查**: 机器人位置验证\n", + "- 🟣 **3D位置检查**: 物体放置位置验证 \n", + "- 🟢 **抓取动作**: 物体抓取操作\n", + "- 🔴 **碰撞检查**: 安全碰撞检测\n", + "\n", + "## 📊 评分规则数据\n", + "总共包含 **21个任务**,总分值 **160分**" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "04b1b572", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "✅ 成功创建图:21 个节点,21 条前置依赖边,7 条until边\n" + ] + }, + { + "name": "stderr", + "output_type": "stream", + "text": [ + "/tmp/ipykernel_117241/3297008030.py:226: UserWarning: Tight layout not applied. The left and right margins cannot be made large enough to accommodate all Axes decorations.\n", + " plt.tight_layout()\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# 机器人任务评分规则依赖关系图分析\n", + "import zhplot\n", + "import matplotlib.pyplot as plt\n", + "import networkx as nx\n", + "import numpy as np\n", + "from collections import defaultdict\n", + "\n", + "# 设置中文字体\n", + "plt.rcParams['font.sans-serif'] = ['SimHei', 'DejaVu Sans']\n", + "plt.rcParams['axes.unicode_minus'] = False\n", + "\n", + "# 定义节点颜色映射\n", + "type_colors = {\n", + " 'in_2d_range': '#3498db', # 蓝色 - 2D位置检查\n", + " 'in_3d_range': '#9b59b6', # 紫色 - 3D位置检查 \n", + " 'no_collision': '#e74c3c', # 红色 - 碰撞检查\n", + " 'pick_up': '#2ecc71', # 绿色 - 抓取动作\n", + " 'unknown': '#95a5a6' # 灰色 - 未知类型\n", + "}\n", + "\n", + "# 创建有向图\n", + "G = nx.DiGraph()\n", + "\n", + "# 添加所有节点和依赖关系\n", + "node_labels = {}\n", + "node_colors = []\n", + "node_sizes = []\n", + "prerequisite_edges = []\n", + "until_edges = []\n", + "\n", + "for rule in scoling_rules:\n", + " description = rule['description']\n", + " task_index = rule['task_index']\n", + " score = rule['score']\n", + " rule_type = rule.get('type', 'unknown')\n", + " \n", + " # 创建更详细的节点标签\n", + " if '成功移动到桌子面前' in description:\n", + " label = f\"T{task_index}: 移动到桌子面前\\n(2D位置检查, {score}分)\"\n", + " elif '从出发区移动到桌子面前物体抓取区过程中没有碰撞行为' in description:\n", + " label = f\"T{task_index}: 出发→桌子\\n无碰撞({score}分)\"\n", + " elif '成功抓取普通物品 power_drill' in description:\n", + " label = f\"T{task_index}: 抓取电钻\\n(抓取动作, {score}分)\"\n", + " elif '成功抓取普通物品 cube' in description:\n", + " label = f\"T{task_index}: 抓取方块\\n(抓取动作, {score}分)\"\n", + " elif '成功抓取普通物品 extrusion' in description:\n", + " label = f\"T{task_index}: 抓取挤压件\\n(抓取动作, {score}分)\"\n", + " elif '成功放置物品 power_drill' in description:\n", + " label = f\"T{task_index}: 放置电钻\\n(3D位置, {score}分)\"\n", + " elif '成功放置物品 cube' in description:\n", + " label = f\"T{task_index}: 放置方块\\n(3D位置, {score}分)\"\n", + " elif '成功放置物品 extrusion' in description:\n", + " label = f\"T{task_index}: 放置挤压件\\n(3D位置, {score}分)\"\n", + " elif '抓取到放置中没有碰撞' in description:\n", + " label = f\"T{task_index}: 抓取放置过程\\n无碰撞({score}分)\"\n", + " elif '成功抓取神秘物体' in description:\n", + " label = f\"T{task_index}: 抓取神秘物体\\n★高价值★({score}分)\"\n", + " elif '成功把神秘物体放置到料框里' in description:\n", + " label = f\"T{task_index}: 神秘物体→料框\\n(3D位置, {score}分)\"\n", + " elif '神秘物体放置到料框的过程中没有碰撞行为' in description:\n", + " label = f\"T{task_index}: 神秘物体放置\\n无碰撞({score}分)\"\n", + " elif '成功移动到料框抓取区(桌子侧面)' in description:\n", + " label = f\"T{task_index}: 移动到料框区\\n(桌子侧面, {score}分)\"\n", + " elif '从物体抓取区移动到料框抓取区过程中没有碰撞行为' in description:\n", + " label = f\"T{task_index}: 抓取区→料框区\\n无碰撞({score}分)\"\n", + " elif '成功抓起料框' in description:\n", + " label = f\"T{task_index}: 抓取料框\\n(抓取动作, {score}分)\"\n", + " elif '成功移动到货架面前' in description:\n", + " label = f\"T{task_index}: 移动到货架前\\n(2D位置, {score}分)\"\n", + " elif '从料框抓取区移动到料框放置区(货架)过程中没有碰撞行为' in description:\n", + " label = f\"T{task_index}: 料框区→货架\\n无碰撞({score}分)\"\n", + " elif '成功将箱子放置到货架上' in description:\n", + " label = f\"T{task_index}: 料框放置货架\\n(3D位置, {score}分)\"\n", + " elif '将箱子放置到货架的过程中没有碰撞行为' in description:\n", + " label = f\"T{task_index}: 货架放置过程\\n无碰撞({score}分)\"\n", + " elif '成功移动到任务结束点' in description:\n", + " label = f\"T{task_index}: 移动到结束点\\n(2D位置, {score}分)\"\n", + " elif '从料框放置区移动到任务结束区过程中没有碰撞行为' in description:\n", + " label = f\"T{task_index}: 货架→结束点\\n无碰撞({score}分)\"\n", + " else:\n", + " label = f\"T{task_index}: {description[:10]}...\\n({score}分)\"\n", + " \n", + " # 添加节点\n", + " G.add_node(description)\n", + " node_labels[description] = label\n", + " node_colors.append(type_colors.get(rule_type, '#95a5a6'))\n", + " # 根据分数调整节点大小,神秘物体任务特别突出\n", + " if score == 30:\n", + " node_sizes.append(800) # 神秘物体任务特别大\n", + " else:\n", + " node_sizes.append(500 + score * 20)\n", + " \n", + " # 添加前置依赖边\n", + " if 'prerequisite' in rule:\n", + " for prereq in rule['prerequisite']:\n", + " if prereq in [r['description'] for r in scoling_rules]:\n", + " G.add_edge(prereq, description)\n", + " prerequisite_edges.append((prereq, description))\n", + " \n", + " # 添加until边\n", + " if 'until' in rule:\n", + " for until_condition in rule['until']:\n", + " if until_condition in [r['description'] for r in scoling_rules]:\n", + " until_edges.append((description, until_condition))\n", + "\n", + "print(f\"✅ 成功创建图:{G.number_of_nodes()} 个节点,{G.number_of_edges()} 条前置依赖边,{len(until_edges)} 条until边\")\n", + "\n", + "# 创建单个层次图\n", + "fig, ax = plt.subplots(figsize=(6, 24))\n", + "\n", + "# 层次布局 - 按任务阶段分组\n", + "task_groups = defaultdict(list)\n", + "for rule in scoling_rules:\n", + " task_groups[rule['task_index']].append(rule)\n", + "\n", + "pos = {}\n", + "# 重新设计Y轴位置,更好地反映任务流程\n", + "y_positions = {\n", + " 1: 10, # 开始:移动到桌子前\n", + " 2: 9, # 移动碰撞检查\n", + " 3: 8, # 抓取普通物品\n", + " 4: 7, # 放置普通物品\n", + " 5: 6, # 抓取放置碰撞检查\n", + " 6: 5, # 抓取神秘物体\n", + " 7: 4, # 放置神秘物体\n", + " 8: 3, # 神秘物体碰撞检查\n", + " 9: 2, # 移动到料框区\n", + " 10: 1, # 移动碰撞检查\n", + " 11: 0, # 抓取料框\n", + " 13: -1, # 移动到货架\n", + " 14: -2, # 料框移动碰撞检查\n", + " 15: -3, # 放置料框到货架\n", + " 16: -4, # 货架放置碰撞检查\n", + " 17: -5, # 移动到结束点\n", + " 18: -6 # 最终移动碰撞检查\n", + "}\n", + "\n", + "# 为每个任务组分配位置\n", + "for task_index, rules in task_groups.items():\n", + " y = y_positions.get(task_index, 0)\n", + " \n", + " # 如果同一task_index有多个规则,水平排列\n", + " if len(rules) == 1:\n", + " pos[rules[0]['description']] = (0, y)\n", + " else:\n", + " x_spacing = 4 # 增加水平间距\n", + " x_start = -(len(rules) - 1) * x_spacing / 2\n", + " for i, rule in enumerate(rules):\n", + " pos[rule['description']] = (x_start + i * x_spacing, y)\n", + "\n", + "# 绘制节点\n", + "nx.draw_networkx_nodes(G, pos, node_color=node_colors, node_size=node_sizes,\n", + " alpha=0.8, linewidths=2, edgecolors='black', ax=ax)\n", + "\n", + "# 绘制前置依赖边\n", + "nx.draw_networkx_edges(G, pos, edgelist=prerequisite_edges, edge_color='#2c3e50', \n", + " arrows=True, arrowsize=25, arrowstyle='->', width=2, alpha=0.8,\n", + " connectionstyle=\"arc3,rad=0.15\", ax=ax)\n", + "\n", + "# 绘制until边(虚线)\n", + "if until_edges:\n", + " nx.draw_networkx_edges(G, pos, edgelist=until_edges, edge_color='#e67e22', \n", + " arrows=True, arrowsize=20, arrowstyle='->', width=2, alpha=0.7,\n", + " style='dashed', connectionstyle=\"arc3,rad=-0.15\", ax=ax)\n", + "\n", + "# 绘制详细标签\n", + "nx.draw_networkx_labels(G, pos, node_labels, font_size=9, font_weight='bold', ax=ax)\n", + "\n", + "# 添加更详细的任务阶段标注\n", + "stage_labels = {\n", + " 10: \"任务开始\", \n", + " 9: \"移动阶段\", \n", + " 8: \"抓取普通物品\", \n", + " 7: \"放置普通物品\", \n", + " 6: \"抓取过程检查\", \n", + " 5: \"神秘物体抓取\", \n", + " 4: \"神秘物体放置\", \n", + " 3: \"神秘物体检查\", \n", + " 2: \"移动到料框区\", \n", + " 1: \"移动过程检查\", \n", + " 0: \"料框抓取\", \n", + " -1: \"移动到货架\", \n", + " -2: \"料框移动检查\", \n", + " -3: \"货架放置\", \n", + " -4: \"货架放置检查\", \n", + " -5: \"移动到终点\", \n", + " -6: \"最终检查\"\n", + "}\n", + "\n", + "for y, label in stage_labels.items():\n", + " ax.text(-12, y, label, fontsize=16, fontweight='bold', \n", + " bbox=dict(boxstyle=\"round,pad=0.5\", facecolor='lightblue', alpha=0.8),\n", + " verticalalignment='center')\n", + "\n", + "# 添加分数统计文本框\n", + "score_info = f\"\"\"\n", + "分数统计:\n", + "• 总分: {sum(r['score'] for r in scoling_rules)}分\n", + "• 神秘物体: 30分 (最高)\n", + "• 抓取动作: {sum(r['score'] for r in scoling_rules if r.get('type') == 'pick_up')}分\n", + "• 位置检查: {sum(r['score'] for r in scoling_rules if 'range' in r.get('type', ''))}分\n", + "• 碰撞检查: {sum(r['score'] for r in scoling_rules if r.get('type') == 'no_collision')}分\n", + "\"\"\"\n", + "\n", + "ax.text(12, 8, score_info, fontsize=16, \n", + " bbox=dict(boxstyle=\"round,pad=0.8\", facecolor='lightyellow', alpha=0.9),\n", + " verticalalignment='top')\n", + "\n", + "# 创建详细图例\n", + "legend_elements = [\n", + " plt.Line2D([0], [0], marker='o', color='w', markerfacecolor='#3498db', markersize=15, label='2D位置检查'),\n", + " plt.Line2D([0], [0], marker='o', color='w', markerfacecolor='#9b59b6', markersize=15, label='3D位置检查'),\n", + " plt.Line2D([0], [0], marker='o', color='w', markerfacecolor='#2ecc71', markersize=15, label='抓取动作'),\n", + " plt.Line2D([0], [0], marker='o', color='w', markerfacecolor='#e74c3c', markersize=15, label='碰撞检查'),\n", + " plt.Line2D([0], [0], color='#2c3e50', linewidth=3, label='→ 前置依赖'),\n", + " plt.Line2D([0], [0], color='#e67e22', linewidth=3, linestyle='--', label='--> Until条件')\n", + "]\n", + "\n", + "ax.legend(handles=legend_elements, loc='upper right', bbox_to_anchor=(1, 1), fontsize=16,\n", + " title=\"任务类型与关系\", title_fontsize=18)\n", + "\n", + "ax.set_title(\"机器人任务评分规则依赖关系图(层次化流程)\", fontsize=24, fontweight='bold', pad=30)\n", + "ax.axis('off')\n", + "\n", + "# 调整布局\n", + "plt.tight_layout()\n", + "plt.show()" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "discoverse", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.10.16" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/referee/rules.json b/examples/referee/rules.json new file mode 100644 index 0000000..95f5972 --- /dev/null +++ b/examples/referee/rules.json @@ -0,0 +1,246 @@ +{ + "成功移动到桌子面前": { + "task_index": 1, + "score": 5, + "type" : "in_2d_range", + "range" : { + "x" : [-0.35, 0.1], + "y" : [-0.35, 0.35] + } + }, + "从出发区移动到桌子面前物体抓取区过程中没有碰撞行为" : { + "task_index": 2, + "score": 5, + "type" : "no_collision", + "until" : "成功移动到桌子面前", + "collision_group" : [ + [["galbot_one_foxtrot/base_link"], ["table", "bin", "wall_1", "wall_2", "wall_3"]] + ] + }, + "成功抓取普通物品 power_drill" : { + "task_index": 3, + "score": 10, + "type" : "pick_up", + "prerequisite" : [ + "成功移动到桌子面前" + ], + "object1_name" : "power_drill" + }, + "成功抓取普通物品 cube" : { + "task_index": 3, + "score": 10, + "type" : "pick_up", + "prerequisite" : [ + "成功移动到桌子面前" + ], + "object1_name" : "cube" + }, + "成功抓取普通物品 extrusion" : { + "task_index": 3, + "score": 10, + "type" : "pick_up", + "prerequisite" : [ + "成功移动到桌子面前" + ], + "object1_name" : "extrusion" + }, + "成功放置物品 power_drill" : { + "task_index": 4, + "score": 5, + "type" : "in_3d_range", + "prerequisite" : [ + "成功抓取普通物品 power_drill" + ], + "object1_name" : "power_drill", + "object2_name" : "bin", + "range" : { + "x" : [-0.2, 0.2], + "y" : [-0.3, 0.3], + "z" : [ 0.0, 0.5] + } + }, + "成功放置物品 cube" : { + "task_index": 4, + "score": 5, + "type" : "in_3d_range", + "prerequisite" : [ + "成功抓取普通物品 cube" + ], + "object1_name" : "cube", + "object2_name" : "bin", + "range" : { + "x" : [-0.2, 0.2], + "y" : [-0.3, 0.3], + "z" : [ 0.0, 0.5] + } + }, + "成功放置物品 extrusion" : { + "task_index": 4, + "score": 5, + "type" : "in_3d_range", + "prerequisite" : [ + "成功抓取普通物品 extrusion" + ], + "object1_name" : "extrusion", + "object2_name" : "bin", + "range" : { + "x" : [-0.2, 0.2], + "y" : [-0.3, 0.3], + "z" : [ 0.0, 0.5] + } + }, + "抓取到放置中没有碰撞(桌子、料框、围挡)" : { + "task_index": 5, + "score": 5, + "type" : "no_collision", + "prerequisite" : [ + "成功抓取普通物品 power_drill", + "成功抓取普通物品 cube", + "成功抓取普通物品 extrusion" + ], + "until" : "成功移动到料框抓取区(桌子侧面)", + "collision_group" : [ + [["galbot_one_foxtrot/base_link"], ["table", "bin", "wall_1", "wall_2", "wall_3"]] + ] + }, + "成功抓取神秘物体": { + "task_index": 6, + "score": 30, + "type" : "pick_up", + "prerequisite" : [ + "成功移动到桌子面前" + ], + "object1_name" : "toy" + }, + "成功把神秘物体放置到料框里" : { + "task_index": 7, + "score": 5, + "type" : "in_3d_range", + "prerequisite" : [ + "成功抓取神秘物体" + ], + "object1_name" : "toy", + "object2_name" : "bin", + "range" : { + "x" : [-0.2, 0.2], + "y" : [-0.3, 0.3], + "z" : [ 0.0, 0.5] + } + }, + "神秘物体放置到料框的过程中没有碰撞行为" : { + "task_index": 8, + "score": 5, + "type" : "no_collision", + "prerequisite" : [ + "成功抓取神秘物体" + ], + "until" : "成功移动到料框抓取区(桌子侧面)", + "collision_group" : [ + [["galbot_one_foxtrot/base_link"], ["table", "bin", "wall_1", "wall_2", "wall_3"]] + ] + }, + "成功移动到料框抓取区(桌子侧面)": { + "task_index": 9, + "score": 5, + "type" : "in_2d_range", + "prerequisite" : [ + "成功移动到桌子面前" + ], + "range" : { + "x" : [0.4, 0.9], + "y" : [0.7, 0.9] + } + }, + "从物体抓取区移动到料框抓取区过程中没有碰撞行为": { + "task_index": 10, + "score": 5, + "type" : "no_collision", + "prerequisite" : [ + "成功移动到桌子面前" + ], + "until" : "成功移动到料框抓取区(桌子侧面)", + "collision_group" : [ + [["galbot_one_foxtrot/base_link"], ["table", "bin", "wall_1", "wall_2", "wall_3"]] + ] + }, + "成功抓起料框" : { + "task_index": 11, + "score": 10, + "type" : "pick_up_dual", + "prerequisite" : [ + "成功移动到料框抓取区(桌子侧面)" + ], + "object1_name" : "bin" + }, + "成功移动到货架面前" : { + "task_index": 13, + "score": 5, + "type" : "in_2d_range", + "prerequisite" : [ + "成功移动到料框抓取区(桌子侧面)" + ], + "range" : { + "x" : [2.5, 3.5], + "y" : [3.5, 4.5] + } + }, + "从料框抓取区移动到料框放置区(货架)过程中没有碰撞行为": { + "task_index": 14, + "score": 5, + "type" : "no_collision", + "prerequisite" : [ + "成功抓起料框" + ], + "until" : "成功移动到货架面前", + "collision_group" : [ + [["galbot_one_foxtrot/base_link"], ["table", "bin", "wall_1", "wall_2", "wall_3", "cone_1", "cone_2"]] + ] + }, + "成功将箱子放置到货架上": { + "task_index": 15, + "score": 10, + "type" : "in_3d_range", + "prerequisite" : [ + "成功移动到货架面前" + ], + "object1_name" : "bin", + "object2_name" : "shelf", + "range" : { + "x" : [-1.0, 1.0], + "y" : [-0.5, 0.5], + "z" : [ 0.0, 2.0] + } + }, + "将箱子放置到货架的过程中没有碰撞行为(桌子、料框、围挡)" : { + "task_index": 16, + "score": 10, + "type" : "no_collision", + "prerequisite" : [ + "成功移动到货架面前" + ], + "until" : "成功移动到任务结束点", + "collision_group" : [ + [["galbot_one_foxtrot/base_link"], ["table", "bin", "wall_1", "wall_2", "wall_3"]] + ] + }, + "成功移动到任务结束点": { + "score": 5, + "task_index": 17, + "type" : "in_2d_range", + "prerequisite" : [ + "成功移动到货架面前" + ] + }, + "从料框放置区移动到任务结束区过程中没有碰撞行为(桌子、料框、围挡)": { + "task_index": 18, + "score": 5, + "type" : "no_collision", + "prerequisite" : [ + "成功移动到货架面前" + ], + "until" : "成功移动到任务结束点", + "collision_group" : [ + [["galbot_one_foxtrot/base_link"], ["table", "bin", "wall_1", "wall_2", "wall_3"]] + ] + } +} \ No newline at end of file