def main(_): robot = ROBOT_CLASS_MAP[FLAGS.robot_type] motor_control_mode = MOTOR_CONTROL_MODE_MAP[FLAGS.motor_control_mode] env = env_builder.build_regular_env(robot, motor_control_mode=motor_control_mode, enable_rendering=True, on_rack=FLAGS.on_rack, wrap_trajectory_generator=False) action_low, action_high = env.action_space.low, env.action_space.high action_median = (action_low + action_high) / 2. dim_action = action_low.shape[0] action_selector_ids = [] for dim in range(dim_action): action_selector_id = p.addUserDebugParameter( paramName='dim{}'.format(dim), rangeMin=action_low[dim], rangeMax=action_high[dim], startValue=action_median[dim]) action_selector_ids.append(action_selector_id) if FLAGS.video_dir: log_id = p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4, FLAGS.video_dir) for _ in tqdm(range(800)): action = np.zeros(dim_action) for dim in range(dim_action): action[dim] = env.pybullet_client.readUserDebugParameter( action_selector_ids[dim]) env.step(action) if FLAGS.video_dir: p.stopStateLogging(log_id)
def main(_): logging.info( "WARNING: this code executes low-level controller on the robot.") logging.info("Make sure the robot is hang on rack before proceeding.") input("Press enter to continue...") # Construct sim env and real robot sim_env = env_builder.build_regular_env( robot_class=a1.A1, motor_control_mode=robot_config.MotorControlMode.POSITION, on_rack=True, enable_rendering=True, wrap_trajectory_generator=False) real_env = env_builder.build_regular_env( robot_class=a1_robot.A1Robot, motor_control_mode=robot_config.MotorControlMode.POSITION, on_rack=False, enable_rendering=False, wrap_trajectory_generator=False) # Add debug sliders action_low, action_high = sim_env.action_space.low, sim_env.action_space.high dim_action = action_low.shape[0] action_selector_ids = [] robot_motor_angles = real_env.robot.GetMotorAngles() for dim in range(dim_action): action_selector_id = p.addUserDebugParameter( paramName='dim{}'.format(dim), rangeMin=action_low[dim], rangeMax=action_high[dim], startValue=robot_motor_angles[dim]) action_selector_ids.append(action_selector_id) # Visualize debug slider in sim for _ in range(10000): # Get user action input action = np.zeros(dim_action) for dim in range(dim_action): action[dim] = sim_env.pybullet_client.readUserDebugParameter( action_selector_ids[dim]) real_env.step(action) sim_env.step(action) real_env.Terminate()
def __init__(self, action_limit=(0.75, 0.75, 0.75), render=False, on_rack=False): self._env = env_builder.build_regular_env( a1.A1, motor_control_mode=robot_config.MotorControlMode.POSITION, enable_rendering=render, action_limit=action_limit, on_rack=on_rack) self.observation_space = self._env.observation_space self.action_space = self._env.action_space
def main(_): robot = ROBOT_CLASS_MAP[FLAGS.robot_type] motor_control_mode = MOTOR_CONTROL_MODE_MAP[FLAGS.motor_control_mode] env = env_builder.build_regular_env(robot, motor_control_mode=motor_control_mode, enable_rendering=True, on_rack=FLAGS.on_rack) env.reset() for _ in tqdm(range(1000)): _, _, done, _ = env.step(env.action_space.sample()) if done: break
def main(_): robot = ROBOT_CLASS_MAP[FLAGS.robot_type] motor_control_mode = MOTOR_CONTROL_MODE_MAP[FLAGS.motor_control_mode] env = env_builder.build_regular_env(robot, motor_control_mode=motor_control_mode, enable_rendering=True, on_rack=FLAGS.on_rack, wrap_trajectory_generator=False) action_low, action_high = env.action_space.low/3., env.action_space.high/3. action_median = (action_low + action_high) / 2. dim_action = action_low.shape[0] action_selector_ids = [] for dim in range(dim_action): action_selector_id = p.addUserDebugParameter(paramName='dim{}'.format(dim), rangeMin=action_low[dim], rangeMax=action_high[dim], startValue=action_median[dim]) action_selector_ids.append(action_selector_id) action_selector_id = p.addUserDebugParameter(paramName='height', rangeMin=0, rangeMax=2, startValue=1) action_selector_ids.append(action_selector_id) action_selector_id = p.addUserDebugParameter(paramName='angle', rangeMin=-3.14/2, rangeMax=3.14/2, startValue=0) action_selector_ids.append(action_selector_id) if FLAGS.video_dir: log_id = p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4, FLAGS.video_dir) #for _ in tqdm(range(800)): last_state_vec = [] while True: state_vec = [] rot = Rotation.from_euler('zxy', [0,0,env.pybullet_client.readUserDebugParameter( action_selector_ids[-1])]) base = Rotation.from_quat([0.5,0.5,0.5,0.5]) final_quat = (rot*base).as_quat() final_pos = [0,0,env.pybullet_client.readUserDebugParameter( action_selector_ids[-2])] env.moveRack(final_pos, final_quat) state_vec.extend(final_pos) state_vec.extend(final_quat) action = np.zeros(dim_action) for dim in range(dim_action): action[dim] = env.pybullet_client.readUserDebugParameter( action_selector_ids[dim]) state_vec.append(action[dim]) env.step(action) if last_state_vec != state_vec: print(state_vec) last_state_vec = state_vec if FLAGS.video_dir: p.stopStateLogging(log_id)