diff options
Diffstat (limited to 'examples/pybullet/gym/pybullet_envs/bullet/minitaur_gym_env.py')
-rw-r--r-- | examples/pybullet/gym/pybullet_envs/bullet/minitaur_gym_env.py | 167 |
1 files changed, 81 insertions, 86 deletions
diff --git a/examples/pybullet/gym/pybullet_envs/bullet/minitaur_gym_env.py b/examples/pybullet/gym/pybullet_envs/bullet/minitaur_gym_env.py index 030840640..7a595b47d 100644 --- a/examples/pybullet/gym/pybullet_envs/bullet/minitaur_gym_env.py +++ b/examples/pybullet/gym/pybullet_envs/bullet/minitaur_gym_env.py @@ -5,8 +5,7 @@ import os, inspect currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe()))) parentdir = os.path.dirname(os.path.dirname(currentdir)) -os.sys.path.insert(0,parentdir) - +os.sys.path.insert(0, parentdir) import math import time @@ -33,6 +32,7 @@ OBSERVATION_EPS = 0.01 RENDER_HEIGHT = 720 RENDER_WIDTH = 960 + class MinitaurBulletEnv(gym.Env): """The gym environment for the minitaur. @@ -43,34 +43,32 @@ class MinitaurBulletEnv(gym.Env): expenditure. """ - metadata = { - "render.modes": ["human", "rgb_array"], - "video.frames_per_second": 50 - } - - def __init__(self, - urdf_root=pybullet_data.getDataPath(), - action_repeat=1, - distance_weight=1.0, - energy_weight=0.005, - shake_weight=0.0, - drift_weight=0.0, - distance_limit=float("inf"), - observation_noise_stdev=0.0, - self_collision_enabled=True, - motor_velocity_limit=np.inf, - pd_control_enabled=False,#not needed to be true if accurate motor model is enabled (has its own better PD) - leg_model_enabled=True, - accurate_motor_model_enabled=True, - motor_kp=1.0, - motor_kd=0.02, - torque_control_enabled=False, - motor_overheat_protection=True, - hard_reset=True, - on_rack=False, - render=False, - kd_for_pd_controllers=0.3, - env_randomizer=minitaur_env_randomizer.MinitaurEnvRandomizer()): + metadata = {"render.modes": ["human", "rgb_array"], "video.frames_per_second": 50} + + def __init__( + self, + urdf_root=pybullet_data.getDataPath(), + action_repeat=1, + distance_weight=1.0, + energy_weight=0.005, + shake_weight=0.0, + drift_weight=0.0, + distance_limit=float("inf"), + observation_noise_stdev=0.0, + self_collision_enabled=True, + motor_velocity_limit=np.inf, + pd_control_enabled=False, #not needed to be true if accurate motor model is enabled (has its own better PD) + leg_model_enabled=True, + accurate_motor_model_enabled=True, + motor_kp=1.0, + motor_kd=0.02, + torque_control_enabled=False, + motor_overheat_protection=True, + hard_reset=True, + on_rack=False, + render=False, + kd_for_pd_controllers=0.3, + env_randomizer=minitaur_env_randomizer.MinitaurEnvRandomizer()): """Initialize the minitaur gym environment. Args: @@ -147,17 +145,14 @@ class MinitaurBulletEnv(gym.Env): self._action_repeat *= NUM_SUBSTEPS if self._is_render: - self._pybullet_client = bullet_client.BulletClient( - connection_mode=pybullet.GUI) + self._pybullet_client = bullet_client.BulletClient(connection_mode=pybullet.GUI) else: self._pybullet_client = bullet_client.BulletClient() self.seed() self.reset() - observation_high = ( - self.minitaur.GetObservationUpperBound() + OBSERVATION_EPS) - observation_low = ( - self.minitaur.GetObservationLowerBound() - OBSERVATION_EPS) + observation_high = (self.minitaur.GetObservationUpperBound() + OBSERVATION_EPS) + observation_low = (self.minitaur.GetObservationLowerBound() - OBSERVATION_EPS) action_dim = 8 action_high = np.array([self._action_bound] * action_dim) self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32) @@ -178,25 +173,25 @@ class MinitaurBulletEnv(gym.Env): numSolverIterations=int(self._num_bullet_solver_iterations)) self._pybullet_client.setTimeStep(self._time_step) plane = self._pybullet_client.loadURDF("%s/plane.urdf" % self._urdf_root) - self._pybullet_client.changeVisualShape(plane,-1,rgbaColor=[1,1,1,0.9]) - self._pybullet_client.configureDebugVisualizer(self._pybullet_client.COV_ENABLE_PLANAR_REFLECTION,0) + self._pybullet_client.changeVisualShape(plane, -1, rgbaColor=[1, 1, 1, 0.9]) + self._pybullet_client.configureDebugVisualizer( + self._pybullet_client.COV_ENABLE_PLANAR_REFLECTION, 0) self._pybullet_client.setGravity(0, 0, -10) acc_motor = self._accurate_motor_model_enabled motor_protect = self._motor_overheat_protection - self.minitaur = (minitaur.Minitaur( - pybullet_client=self._pybullet_client, - urdf_root=self._urdf_root, - time_step=self._time_step, - self_collision_enabled=self._self_collision_enabled, - motor_velocity_limit=self._motor_velocity_limit, - pd_control_enabled=self._pd_control_enabled, - accurate_motor_model_enabled=acc_motor, - motor_kp=self._motor_kp, - motor_kd=self._motor_kd, - torque_control_enabled=self._torque_control_enabled, - motor_overheat_protection=motor_protect, - on_rack=self._on_rack, - kd_for_pd_controllers=self._kd_for_pd_controllers)) + self.minitaur = (minitaur.Minitaur(pybullet_client=self._pybullet_client, + urdf_root=self._urdf_root, + time_step=self._time_step, + self_collision_enabled=self._self_collision_enabled, + motor_velocity_limit=self._motor_velocity_limit, + pd_control_enabled=self._pd_control_enabled, + accurate_motor_model_enabled=acc_motor, + motor_kp=self._motor_kp, + motor_kd=self._motor_kd, + torque_control_enabled=self._torque_control_enabled, + motor_overheat_protection=motor_protect, + on_rack=self._on_rack, + kd_for_pd_controllers=self._kd_for_pd_controllers)) else: self.minitaur.Reset(reload_urdf=False) @@ -206,8 +201,8 @@ class MinitaurBulletEnv(gym.Env): self._env_step_counter = 0 self._last_base_position = [0, 0, 0] self._objectives = [] - self._pybullet_client.resetDebugVisualizerCamera( - self._cam_dist, self._cam_yaw, self._cam_pitch, [0, 0, 0]) + self._pybullet_client.resetDebugVisualizerCamera(self._cam_dist, self._cam_yaw, + self._cam_pitch, [0, 0, 0]) if not self._torque_control_enabled: for _ in range(100): if self._pd_control_enabled or self._accurate_motor_model_enabled: @@ -224,8 +219,7 @@ class MinitaurBulletEnv(gym.Env): for i, action_component in enumerate(action): if not (-self._action_bound - ACTION_EPS <= action_component <= self._action_bound + ACTION_EPS): - raise ValueError( - "{}th action {} out of bounds.".format(i, action_component)) + raise ValueError("{}th action {} out of bounds.".format(i, action_component)) action = self.minitaur.ConvertFromLegModel(action) return action @@ -256,14 +250,15 @@ class MinitaurBulletEnv(gym.Env): base_pos = self.minitaur.GetBasePosition() camInfo = self._pybullet_client.getDebugVisualizerCamera() curTargetPos = camInfo[11] - distance=camInfo[10] + distance = camInfo[10] yaw = camInfo[8] - pitch=camInfo[9] - targetPos = [0.95*curTargetPos[0]+0.05*base_pos[0],0.95*curTargetPos[1]+0.05*base_pos[1],curTargetPos[2]] + pitch = camInfo[9] + targetPos = [ + 0.95 * curTargetPos[0] + 0.05 * base_pos[0], 0.95 * curTargetPos[1] + 0.05 * base_pos[1], + curTargetPos[2] + ] - - self._pybullet_client.resetDebugVisualizerCamera( - distance, yaw, pitch, base_pos) + self._pybullet_client.resetDebugVisualizerCamera(distance, yaw, pitch, base_pos) action = self._transform_action_to_motor_command(action) for _ in range(self._action_repeat): self.minitaur.ApplyAction(action) @@ -285,12 +280,17 @@ class MinitaurBulletEnv(gym.Env): pitch=self._cam_pitch, roll=0, upAxisIndex=2) - proj_matrix = self._pybullet_client.computeProjectionMatrixFOV( - fov=60, aspect=float(RENDER_WIDTH)/RENDER_HEIGHT, - nearVal=0.1, farVal=100.0) - (_, _, px, _, _) = self._pybullet_client.getCameraImage( - width=RENDER_WIDTH, height=RENDER_HEIGHT, viewMatrix=view_matrix, - projectionMatrix=proj_matrix, renderer=pybullet.ER_BULLET_HARDWARE_OPENGL) + proj_matrix = self._pybullet_client.computeProjectionMatrixFOV(fov=60, + aspect=float(RENDER_WIDTH) / + RENDER_HEIGHT, + nearVal=0.1, + farVal=100.0) + (_, _, px, _, + _) = self._pybullet_client.getCameraImage(width=RENDER_WIDTH, + height=RENDER_HEIGHT, + viewMatrix=view_matrix, + projectionMatrix=proj_matrix, + renderer=pybullet.ER_BULLET_HARDWARE_OPENGL) rgb_array = np.array(px) rgb_array = rgb_array[:, :, :3] return rgb_array @@ -301,9 +301,8 @@ class MinitaurBulletEnv(gym.Env): Returns: A numpy array of motor angles. """ - return np.array( - self._observation[MOTOR_ANGLE_OBSERVATION_INDEX: - MOTOR_ANGLE_OBSERVATION_INDEX + NUM_MOTORS]) + return np.array(self._observation[MOTOR_ANGLE_OBSERVATION_INDEX:MOTOR_ANGLE_OBSERVATION_INDEX + + NUM_MOTORS]) def get_minitaur_motor_velocities(self): """Get the minitaur's motor velocities. @@ -312,8 +311,8 @@ class MinitaurBulletEnv(gym.Env): A numpy array of motor velocities. """ return np.array( - self._observation[MOTOR_VELOCITY_OBSERVATION_INDEX: - MOTOR_VELOCITY_OBSERVATION_INDEX + NUM_MOTORS]) + self._observation[MOTOR_VELOCITY_OBSERVATION_INDEX:MOTOR_VELOCITY_OBSERVATION_INDEX + + NUM_MOTORS]) def get_minitaur_motor_torques(self): """Get the minitaur's motor torques. @@ -322,8 +321,8 @@ class MinitaurBulletEnv(gym.Env): A numpy array of motor torques. """ return np.array( - self._observation[MOTOR_TORQUE_OBSERVATION_INDEX: - MOTOR_TORQUE_OBSERVATION_INDEX + NUM_MOTORS]) + self._observation[MOTOR_TORQUE_OBSERVATION_INDEX:MOTOR_TORQUE_OBSERVATION_INDEX + + NUM_MOTORS]) def get_minitaur_base_orientation(self): """Get the minitaur's base orientation, represented by a quaternion. @@ -347,8 +346,7 @@ class MinitaurBulletEnv(gym.Env): rot_mat = self._pybullet_client.getMatrixFromQuaternion(orientation) local_up = rot_mat[6:] pos = self.minitaur.GetBasePosition() - return (np.dot(np.asarray([0, 0, 1]), np.asarray(local_up)) < 0.85 or - pos[2] < 0.13) + return (np.dot(np.asarray([0, 0, 1]), np.asarray(local_up)) < 0.85 or pos[2] < 0.13) def _termination(self): position = self.minitaur.GetBasePosition() @@ -364,12 +362,9 @@ class MinitaurBulletEnv(gym.Env): energy_reward = np.abs( np.dot(self.minitaur.GetMotorTorques(), self.minitaur.GetMotorVelocities())) * self._time_step - reward = ( - self._distance_weight * forward_reward - - self._energy_weight * energy_reward + self._drift_weight * drift_reward - + self._shake_weight * shake_reward) - self._objectives.append( - [forward_reward, energy_reward, drift_reward, shake_reward]) + reward = (self._distance_weight * forward_reward - self._energy_weight * energy_reward + + self._drift_weight * drift_reward + self._shake_weight * shake_reward) + self._objectives.append([forward_reward, energy_reward, drift_reward, shake_reward]) return reward def get_objectives(self): @@ -383,9 +378,9 @@ class MinitaurBulletEnv(gym.Env): self._get_observation() observation = np.array(self._observation) if self._observation_noise_stdev > 0: - observation += (np.random.normal( - scale=self._observation_noise_stdev, size=observation.shape) * - self.minitaur.GetObservationUpperBound()) + observation += ( + np.random.normal(scale=self._observation_noise_stdev, size=observation.shape) * + self.minitaur.GetObservationUpperBound()) return observation if parse_version(gym.__version__) < parse_version('0.9.6'): |