def __init__(self): self.time_step = 0.004 self.finger = sim_finger.SimFinger(finger_type=Cage.args.finger_type, time_step=self.time_step, enable_visualization=True,) self.num_fingers = self.finger.number_of_fingers _kwargs = {"physicsClientId": self.finger._pybullet_client_id} if Cage.args.control_mode == "position": self.position_goals = visual_objects.Marker(number_of_goals=self.num_fingers) self.initial_robot_position=np.array([0.0, np.deg2rad(-60), np.deg2rad(-60)] * 3, dtype=np.float32,) self.finger.reset_finger_positions_and_velocities(self.initial_robot_position) self.initial_object_pose = move_cube.Pose(position=[0, 0, move_cube._min_height], orientation=move_cube.Pose().orientation) self.cube = collision_objects.Block(self.initial_object_pose.position, self.initial_object_pose.orientation, mass=0.020, **_kwargs) self.cube_z = 0.0325 self.workspace_radius = 0.18 self.tricamera = camera.TriFingerCameras(**_kwargs) self.initial_marker_position = np.array([[ 0. , 0.17856407, self.cube_z], [ 0.15464102, -0.08928203, self.cube_z], [-0.15464102, -0.08928203, self.cube_z]]) self.position_goals.set_state(self.initial_marker_position) self.marker_position = self.initial_marker_position self.ik_module = geometric_ik.GeometricIK()
def main(): time_step = 0.004 finger = sim_finger.SimFinger( finger_type="trifingerone", time_step=time_step, enable_visualization=True, ) # Important: The cameras need the be created _after_ the simulation is # initialized. cameras = camera.TriFingerCameras() # Move the fingers to random positions while True: goal = np.array( sample.random_joint_positions( number_of_fingers=3, lower_bounds=[-1, -1, -2], upper_bounds=[1, 1, 2], )) finger_action = finger.Action(position=goal) for _ in range(50): t = finger.append_desired_action(finger_action) finger.get_observation(t) images = cameras.get_images() # images are rgb --> convert to bgr for opencv images = [cv2.cvtColor(img, cv2.COLOR_RGB2BGR) for img in images] cv2.imshow("camera60", images[0]) cv2.imshow("camera180", images[1]) cv2.imshow("camera300", images[2]) cv2.waitKey(int(time_step * 1000))
def __init__(self, env): super().__init__(env) self.cameras = camera.TriFingerCameras(image_size=(int(360 * 2), int(270 * 2))) self.metadata = {"render.modes": ["rgb_array"]} self._initial_reset = True self._accum_reward = 0 self._reward_at_step = 0
def __init__( self, visualization=False, initial_robot_position=None, initial_object_pose=None, enable_cameras=False, ): """Initialize. Args: visualization (bool): Set to true to run visualization. initial_robot_position: Initial robot joint angles initial_object_pose: Initial pose for the manipulation object. Can be any object with attributes ``position`` (x, y, z) and ``orientation`` (x, y, z, w). This is optional, if not set, a random pose will be sampled. enable_cameras (bool): Set to true to enable camera observations. By default this is disabled as rendering of images takes a lot of computational power. Therefore the cameras should only be enabled if the images are actually used. """ #: Camera rate in frames per second. Observations of camera and #: object pose will only be updated with this rate. #: NOTE: This is currently not used! self._camera_rate_fps = 30 #: Set to true to render camera observations self.enable_cameras = enable_cameras #: Simulation time step self._time_step = 0.004 # first camera update in the first step self._next_camera_update_step = 0 # Initialize robot, object and cameras # ==================================== self.simfinger = SimFinger( finger_type="trifingerpro", time_step=self._time_step, enable_visualization=visualization, ) if initial_robot_position is None: initial_robot_position = self.spaces.robot_position.default self.simfinger.reset_finger_positions_and_velocities( initial_robot_position) if initial_object_pose is None: initial_object_pose = move_cube.Pose( position=self.spaces.object_position.default, orientation=self.spaces.object_orientation.default, ) self.cube = collision_objects.Block( initial_object_pose.position, initial_object_pose.orientation, mass=0.020, ) self.tricamera = camera.TriFingerCameras() # Forward some methods for convenience # ==================================== # forward "RobotFrontend" methods directly to simfinger self.Action = self.simfinger.Action self.get_desired_action = self.simfinger.get_desired_action self.get_applied_action = self.simfinger.get_applied_action self.get_timestamp_ms = self.simfinger.get_timestamp_ms self.get_current_timeindex = self.simfinger.get_current_timeindex self.get_robot_observation = self.simfinger.get_observation # forward kinematics directly to simfinger self.forward_kinematics = ( self.simfinger.pinocchio_utils.forward_kinematics) # Initialize log # ============== self._action_log = { "initial_robot_position": initial_robot_position.tolist(), "initial_object_pose": { "position": initial_object_pose.position.tolist(), "orientation": initial_object_pose.orientation.tolist(), }, "actions": [], }