def reset(self, initial_motor_angles=None, reset_duration_test=1.0): self._pybullet_client.configureDebugVisualizer( self._pybullet_client.COV_ENABLE_RENDERING, 0) if self._env_step_counter > 0: self.logging.save_episode(self._episode_proto) self._episode_proto = minitaur_logging_pb2.MinitaurEpisode() minitaur_logging.preallocate_episode_proto(self._episode_proto, self._num_steps_to_log) if self._hard_reset: self._pybullet_client.resetSimulation() self._pybullet_client.setPhysicsEngineParameter( numSolverIterations=int(self._num_bullet_solver_iterations)) self._pybullet_client.setTimeStep(self._time_step) self._ground_id = self._pybullet_client.loadURDF("%s/plane.urdf" % self._urdf_root) if (self._reflection): self._pybullet_client.changeVisualShape( self._ground_id, -1, rgbaColor=[1, 1, 1, 0.8]) self._pybullet_client.configureDebugVisualizer( self._pybullet_client.COV_ENABLE_PLANAR_REFLECTION, self._ground_id) self._pybullet_client.setGravity(0, 0, -10) acc_motor = self._accurate_motor_model_enabled motor_protect = self._motor_overheat_protection self.minitaur = Minitaur( pybullet_client=self._pybullet_client, action_repeat=self._action_repeat, 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, remove_default_joint_damping=self._remove_default_joint_damping, motor_kp=self._motor_kp, motor_kd=self._motor_kd, control_latency=self._control_latency, pd_latency=self._pd_latency, observation_noise_stdev=self._observation_noise_stdev, torque_control_enabled=self._torque_control_enabled, motor_overheat_protection=motor_protect, on_rack=self._on_rack) print('-----Enter Minitaur.Reset2-----') self.minitaur.Reset(reload_urdf=False, default_motor_angles=initial_motor_angles, reset_time=reset_duration_test) print('-----Exit Minitaur.Reset2------') for env_randomizer in self._env_randomizers: env_randomizer.randomize_env(self) self._pybullet_client.setPhysicsEngineParameter(enableConeFriction=0) 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.configureDebugVisualizer( self._pybullet_client.COV_ENABLE_RENDERING, 1) return self._get_true_observation()
def reset(self, initial_motor_angles=None, reset_duration=1.0): self._pybullet_client.configureDebugVisualizer(self._pybullet_client.COV_ENABLE_RENDERING, 0) if self._env_step_counter > 0: self.logging.save_episode(self._episode_proto) self._episode_proto = minitaur_logging_pb2.MinitaurEpisode() minitaur_logging.preallocate_episode_proto(self._episode_proto, self._num_steps_to_log) if self._hard_reset: self._pybullet_client.resetSimulation() self._pybullet_client.setPhysicsEngineParameter( numSolverIterations=int(self._num_bullet_solver_iterations)) self._pybullet_client.setTimeStep(self._time_step) self._ground_id = self._pybullet_client.loadURDF("%s/plane.urdf" % self._urdf_root) if (self._reflection): self._pybullet_client.changeVisualShape(self._ground_id, -1, rgbaColor=[1, 1, 1, 0.8]) self._pybullet_client.configureDebugVisualizer( self._pybullet_client.COV_ENABLE_PLANAR_REFLECTION, self._ground_id) self._pybullet_client.setGravity(0, 0, -10) acc_motor = self._accurate_motor_model_enabled motor_protect = self._motor_overheat_protection if self._urdf_version not in MINIATUR_URDF_VERSION_MAP: raise ValueError("%s is not a supported urdf_version." % self._urdf_version) else: self.minitaur = (MINIATUR_URDF_VERSION_MAP[self._urdf_version]( pybullet_client=self._pybullet_client, action_repeat=self._action_repeat, 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, remove_default_joint_damping=self._remove_default_joint_damping, motor_kp=self._motor_kp, motor_kd=self._motor_kd, control_latency=self._control_latency, pd_latency=self._pd_latency, observation_noise_stdev=self._observation_noise_stdev, torque_control_enabled=self._torque_control_enabled, motor_overheat_protection=motor_protect, on_rack=self._on_rack)) self.minitaur.Reset(reload_urdf=False, default_motor_angles=initial_motor_angles, reset_time=reset_duration) # Loop over all env randomizers. for env_randomizer in self._env_randomizers: env_randomizer.randomize_env(self) self._pybullet_client.setPhysicsEngineParameter(enableConeFriction=0) 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.configureDebugVisualizer(self._pybullet_client.COV_ENABLE_RENDERING, 1) return self._get_observation()
def reset( self, initial_motor_angles=None, reset_duration=1.0, reset_visualization_camera=True, ): """Resets the robot's position in the world or rebuild the sim world. The simulation world will be rebuilt if self._hard_reset is True. Args: initial_motor_angles: A list of Floats. The desired joint angles after reset. If None, the robot will use its built-in value. reset_duration: Float. The time (in seconds) needed to rotate all motors to the desired initial values. reset_visualization_camera: Whether to reset debug visualization camera on reset. Returns: A numpy array contains the initial observation after reset. """ self._env_step_counter = 0 self._sim_step_counter = 0 self._last_reset_time = self._clock() self._metric_logger.reset_episode() # Clear the simulation world and rebuild the robot interface. if self._hard_reset: self._load() # Resets the scene self._scene.reset() # Resets the robot with the provided init parameters. if self._use_new_robot_class: self._robot.reset() else: self._robot.Reset(reload_urdf=False, default_motor_angles=initial_motor_angles, reset_time=reset_duration) # Flush the logs to disc and reinitialize the logging system. if self._log_path is not None: self._logging.save_episode(self._episode_proto) self._episode_proto = minitaur_logging_pb2.MinitaurEpisode() minitaur_logging.preallocate_episode_proto(self._episode_proto, _LOG_BUFFER_LENGTH, self._robot) # TODO(b/152161124): Move this part to the renderer module. if reset_visualization_camera: self._pybullet_client.resetDebugVisualizerCamera( self._camera_dist, self._camera_yaw, self._camera_pitch, [0, 0, 0]) # Create an example last action based on the type of action space. self._last_action = space_utils.create_constant_action( self.action_space) for s in self.all_sensors(): s.on_reset(self) if self._task and hasattr(self._task, 'reset'): self._task.reset(self) # Loop over all env randomizers. for env_randomizer in self._env_randomizers: env_randomizer.randomize_env(self) for obj in self._dynamic_objects(): obj.reset() # Initialize the robot base position. if self._use_new_robot_class: self._last_base_position = self._robot.base_position else: self._last_base_position = self._robot.GetBasePosition() # Resets the observations again, since randomizers might change the env. for s in self.all_sensors(): s.on_reset(self) self._last_reset_time = self._clock() return self._get_observation()