add yapf style and apply yapf to format all Python files
This recreates pull request #2192
This commit is contained in:
@@ -4,11 +4,11 @@ The randomization include swing_offset, extension_offset of all legs that mimics
|
||||
bent legs, desired_pitch from user input, battery voltage and motor damping.
|
||||
"""
|
||||
|
||||
import os, inspect
|
||||
import os, inspect
|
||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||
parentdir = os.path.dirname(os.path.dirname(parentdir))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
import numpy as np
|
||||
import tensorflow as tf
|
||||
@@ -20,8 +20,7 @@ BATTERY_VOLTAGE_RANGE = (14.8, 16.8)
|
||||
MOTOR_VISCOUS_DAMPING_RANGE = (0, 0.01)
|
||||
|
||||
|
||||
class MinitaurAlternatingLegsEnvRandomizer(
|
||||
env_randomizer_base.EnvRandomizerBase):
|
||||
class MinitaurAlternatingLegsEnvRandomizer(env_randomizer_base.EnvRandomizerBase):
|
||||
"""A randomizer that changes the minitaur_gym_alternating_leg_env."""
|
||||
|
||||
def __init__(self,
|
||||
@@ -34,23 +33,20 @@ class MinitaurAlternatingLegsEnvRandomizer(
|
||||
self.perturb_desired_pitch_bound = perturb_desired_pitch_bound
|
||||
|
||||
def randomize_env(self, env):
|
||||
perturb_magnitude = np.random.uniform(
|
||||
low=-self.perturb_swing_bound,
|
||||
high=self.perturb_swing_bound,
|
||||
size=NUM_LEGS)
|
||||
perturb_magnitude = np.random.uniform(low=-self.perturb_swing_bound,
|
||||
high=self.perturb_swing_bound,
|
||||
size=NUM_LEGS)
|
||||
env.set_swing_offset(perturb_magnitude)
|
||||
tf.logging.info("swing_offset: {}".format(perturb_magnitude))
|
||||
|
||||
perturb_magnitude = np.random.uniform(
|
||||
low=-self.perturb_extension_bound,
|
||||
high=self.perturb_extension_bound,
|
||||
size=NUM_LEGS)
|
||||
perturb_magnitude = np.random.uniform(low=-self.perturb_extension_bound,
|
||||
high=self.perturb_extension_bound,
|
||||
size=NUM_LEGS)
|
||||
env.set_extension_offset(perturb_magnitude)
|
||||
tf.logging.info("extension_offset: {}".format(perturb_magnitude))
|
||||
|
||||
perturb_magnitude = np.random.uniform(
|
||||
low=-self.perturb_desired_pitch_bound,
|
||||
high=self.perturb_desired_pitch_bound)
|
||||
perturb_magnitude = np.random.uniform(low=-self.perturb_desired_pitch_bound,
|
||||
high=self.perturb_desired_pitch_bound)
|
||||
env.set_desired_pitch(perturb_magnitude)
|
||||
tf.logging.info("desired_pitch: {}".format(perturb_magnitude))
|
||||
|
||||
|
||||
@@ -1,11 +1,11 @@
|
||||
"""Randomize the minitaur_gym_env when reset() is called."""
|
||||
import random
|
||||
|
||||
import os, inspect
|
||||
import os, inspect
|
||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||
parentdir = os.path.dirname(os.path.dirname(parentdir))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
import numpy as np
|
||||
from pybullet_envs.minitaur.envs import env_randomizer_base
|
||||
@@ -52,24 +52,20 @@ class MinitaurEnvRandomizer(env_randomizer_base.EnvRandomizerBase):
|
||||
minitaur.SetBaseMasses(randomized_base_mass)
|
||||
|
||||
leg_masses = minitaur.GetLegMassesFromURDF()
|
||||
leg_masses_lower_bound = np.array(leg_masses) * (
|
||||
1.0 + self._minitaur_leg_mass_err_range[0])
|
||||
leg_masses_upper_bound = np.array(leg_masses) * (
|
||||
1.0 + self._minitaur_leg_mass_err_range[1])
|
||||
leg_masses_lower_bound = np.array(leg_masses) * (1.0 + self._minitaur_leg_mass_err_range[0])
|
||||
leg_masses_upper_bound = np.array(leg_masses) * (1.0 + self._minitaur_leg_mass_err_range[1])
|
||||
randomized_leg_masses = [
|
||||
np.random.uniform(leg_masses_lower_bound[i], leg_masses_upper_bound[i])
|
||||
for i in xrange(len(leg_masses))
|
||||
]
|
||||
minitaur.SetLegMasses(randomized_leg_masses)
|
||||
|
||||
randomized_battery_voltage = random.uniform(BATTERY_VOLTAGE_RANGE[0],
|
||||
BATTERY_VOLTAGE_RANGE[1])
|
||||
randomized_battery_voltage = random.uniform(BATTERY_VOLTAGE_RANGE[0], BATTERY_VOLTAGE_RANGE[1])
|
||||
minitaur.SetBatteryVoltage(randomized_battery_voltage)
|
||||
|
||||
randomized_motor_damping = random.uniform(MOTOR_VISCOUS_DAMPING_RANGE[0],
|
||||
MOTOR_VISCOUS_DAMPING_RANGE[1])
|
||||
minitaur.SetMotorViscousDamping(randomized_motor_damping)
|
||||
|
||||
randomized_foot_friction = random.uniform(MINITAUR_LEG_FRICTION[0],
|
||||
MINITAUR_LEG_FRICTION[1])
|
||||
randomized_foot_friction = random.uniform(MINITAUR_LEG_FRICTION[0], MINITAUR_LEG_FRICTION[1])
|
||||
minitaur.SetFootFriction(randomized_foot_friction)
|
||||
|
||||
@@ -4,7 +4,6 @@ from __future__ import absolute_import
|
||||
from __future__ import division
|
||||
from __future__ import print_function
|
||||
|
||||
|
||||
PARAM_RANGE = {
|
||||
# The following ranges are in percentage. e.g. 0.8 means 80%.
|
||||
"mass": [0.8, 1.2],
|
||||
|
||||
@@ -7,11 +7,11 @@ from __future__ import print_function
|
||||
import functools
|
||||
import random
|
||||
|
||||
import os, inspect
|
||||
import os, inspect
|
||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||
parentdir = os.path.dirname(os.path.dirname(parentdir))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
import numpy as np
|
||||
import tensorflow as tf
|
||||
@@ -32,8 +32,7 @@ class MinitaurEnvRandomizerFromConfig(env_randomizer_base.EnvRandomizerBase):
|
||||
except AttributeError:
|
||||
raise ValueError("Config {} is not found.".format(config))
|
||||
self._randomization_param_dict = config()
|
||||
tf.logging.info("Randomization config is: {}".format(
|
||||
self._randomization_param_dict))
|
||||
tf.logging.info("Randomization config is: {}".format(self._randomization_param_dict))
|
||||
|
||||
def randomize_env(self, env):
|
||||
"""Randomize various physical properties of the environment.
|
||||
@@ -43,35 +42,29 @@ class MinitaurEnvRandomizerFromConfig(env_randomizer_base.EnvRandomizerBase):
|
||||
Args:
|
||||
env: A minitaur gym environment.
|
||||
"""
|
||||
self._randomization_function_dict = self._build_randomization_function_dict(
|
||||
env)
|
||||
self._randomization_function_dict = self._build_randomization_function_dict(env)
|
||||
for param_name, random_range in self._randomization_param_dict.iteritems():
|
||||
self._randomization_function_dict[param_name](
|
||||
lower_bound=random_range[0], upper_bound=random_range[1])
|
||||
self._randomization_function_dict[param_name](lower_bound=random_range[0],
|
||||
upper_bound=random_range[1])
|
||||
|
||||
def _build_randomization_function_dict(self, env):
|
||||
func_dict = {}
|
||||
func_dict["mass"] = functools.partial(
|
||||
self._randomize_masses, minitaur=env.minitaur)
|
||||
func_dict["inertia"] = functools.partial(
|
||||
self._randomize_inertia, minitaur=env.minitaur)
|
||||
func_dict["latency"] = functools.partial(
|
||||
self._randomize_latency, minitaur=env.minitaur)
|
||||
func_dict["joint friction"] = functools.partial(
|
||||
self._randomize_joint_friction, minitaur=env.minitaur)
|
||||
func_dict["motor friction"] = functools.partial(
|
||||
self._randomize_motor_friction, minitaur=env.minitaur)
|
||||
func_dict["restitution"] = functools.partial(
|
||||
self._randomize_contact_restitution, minitaur=env.minitaur)
|
||||
func_dict["lateral friction"] = functools.partial(
|
||||
self._randomize_contact_friction, minitaur=env.minitaur)
|
||||
func_dict["battery"] = functools.partial(
|
||||
self._randomize_battery_level, minitaur=env.minitaur)
|
||||
func_dict["motor strength"] = functools.partial(
|
||||
self._randomize_motor_strength, minitaur=env.minitaur)
|
||||
func_dict["mass"] = functools.partial(self._randomize_masses, minitaur=env.minitaur)
|
||||
func_dict["inertia"] = functools.partial(self._randomize_inertia, minitaur=env.minitaur)
|
||||
func_dict["latency"] = functools.partial(self._randomize_latency, minitaur=env.minitaur)
|
||||
func_dict["joint friction"] = functools.partial(self._randomize_joint_friction,
|
||||
minitaur=env.minitaur)
|
||||
func_dict["motor friction"] = functools.partial(self._randomize_motor_friction,
|
||||
minitaur=env.minitaur)
|
||||
func_dict["restitution"] = functools.partial(self._randomize_contact_restitution,
|
||||
minitaur=env.minitaur)
|
||||
func_dict["lateral friction"] = functools.partial(self._randomize_contact_friction,
|
||||
minitaur=env.minitaur)
|
||||
func_dict["battery"] = functools.partial(self._randomize_battery_level, minitaur=env.minitaur)
|
||||
func_dict["motor strength"] = functools.partial(self._randomize_motor_strength,
|
||||
minitaur=env.minitaur)
|
||||
# Settinmg control step needs access to the environment.
|
||||
func_dict["control step"] = functools.partial(
|
||||
self._randomize_control_step, env=env)
|
||||
func_dict["control step"] = functools.partial(self._randomize_control_step, env=env)
|
||||
return func_dict
|
||||
|
||||
def _randomize_control_step(self, env, lower_bound, upper_bound):
|
||||
@@ -111,8 +104,8 @@ class MinitaurEnvRandomizerFromConfig(env_randomizer_base.EnvRandomizerBase):
|
||||
|
||||
def _randomize_joint_friction(self, minitaur, lower_bound, upper_bound):
|
||||
num_knee_joints = minitaur.GetNumKneeJoints()
|
||||
randomized_joint_frictions = np.random.uniform(
|
||||
[lower_bound] * num_knee_joints, [upper_bound] * num_knee_joints)
|
||||
randomized_joint_frictions = np.random.uniform([lower_bound] * num_knee_joints,
|
||||
[upper_bound] * num_knee_joints)
|
||||
minitaur.SetJointFriction(randomized_joint_frictions)
|
||||
tf.logging.info("joint friction is: {}".format(randomized_joint_frictions))
|
||||
|
||||
@@ -137,9 +130,7 @@ class MinitaurEnvRandomizerFromConfig(env_randomizer_base.EnvRandomizerBase):
|
||||
tf.logging.info("battery voltage is: {}".format(randomized_battery_voltage))
|
||||
|
||||
def _randomize_motor_strength(self, minitaur, lower_bound, upper_bound):
|
||||
randomized_motor_strength_ratios = np.random.uniform(
|
||||
[lower_bound] * minitaur.num_motors,
|
||||
[upper_bound] * minitaur.num_motors)
|
||||
randomized_motor_strength_ratios = np.random.uniform([lower_bound] * minitaur.num_motors,
|
||||
[upper_bound] * minitaur.num_motors)
|
||||
minitaur.SetMotorStrengthRatios(randomized_motor_strength_ratios)
|
||||
tf.logging.info(
|
||||
"motor strength is: {}".format(randomized_motor_strength_ratios))
|
||||
tf.logging.info("motor strength is: {}".format(randomized_motor_strength_ratios))
|
||||
|
||||
@@ -4,11 +4,11 @@ from __future__ import absolute_import
|
||||
from __future__ import division
|
||||
from __future__ import print_function
|
||||
|
||||
import os, inspect
|
||||
import os, inspect
|
||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||
parentdir = os.path.dirname(os.path.dirname(parentdir))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
import math
|
||||
import numpy as np
|
||||
@@ -50,12 +50,10 @@ class MinitaurPushRandomizer(env_randomizer_base.EnvRandomizerBase):
|
||||
self._perturbation_start_step = perturbation_start_step
|
||||
self._perturbation_interval_steps = perturbation_interval_steps
|
||||
self._perturbation_duration_steps = perturbation_duration_steps
|
||||
self._horizontal_force_bound = (
|
||||
horizontal_force_bound if horizontal_force_bound else
|
||||
[_HORIZONTAL_FORCE_LOWER_BOUND, _HORIZONTAL_FORCE_UPPER_BOUND])
|
||||
self._vertical_force_bound = (
|
||||
vertical_force_bound if vertical_force_bound else
|
||||
[_VERTICAL_FORCE_LOWER_BOUND, _VERTICAL_FORCE_UPPER_BOUND])
|
||||
self._horizontal_force_bound = (horizontal_force_bound if horizontal_force_bound else
|
||||
[_HORIZONTAL_FORCE_LOWER_BOUND, _HORIZONTAL_FORCE_UPPER_BOUND])
|
||||
self._vertical_force_bound = (vertical_force_bound if vertical_force_bound else
|
||||
[_VERTICAL_FORCE_LOWER_BOUND, _VERTICAL_FORCE_UPPER_BOUND])
|
||||
|
||||
def randomize_env(self, env):
|
||||
"""Randomizes the simulation environment.
|
||||
@@ -75,23 +73,20 @@ class MinitaurPushRandomizer(env_randomizer_base.EnvRandomizerBase):
|
||||
"""
|
||||
base_link_ids = env.minitaur.chassis_link_ids
|
||||
if env.env_step_counter % self._perturbation_interval_steps == 0:
|
||||
self._applied_link_id = base_link_ids[np.random.randint(
|
||||
0, len(base_link_ids))]
|
||||
horizontal_force_magnitude = np.random.uniform(
|
||||
self._horizontal_force_bound[0], self._horizontal_force_bound[1])
|
||||
self._applied_link_id = base_link_ids[np.random.randint(0, len(base_link_ids))]
|
||||
horizontal_force_magnitude = np.random.uniform(self._horizontal_force_bound[0],
|
||||
self._horizontal_force_bound[1])
|
||||
theta = np.random.uniform(0, 2 * math.pi)
|
||||
vertical_force_magnitude = np.random.uniform(
|
||||
self._vertical_force_bound[0], self._vertical_force_bound[1])
|
||||
vertical_force_magnitude = np.random.uniform(self._vertical_force_bound[0],
|
||||
self._vertical_force_bound[1])
|
||||
self._applied_force = horizontal_force_magnitude * np.array(
|
||||
[math.cos(theta), math.sin(theta), 0]) + np.array(
|
||||
[0, 0, -vertical_force_magnitude])
|
||||
[math.cos(theta), math.sin(theta), 0]) + np.array([0, 0, -vertical_force_magnitude])
|
||||
|
||||
if (env.env_step_counter % self._perturbation_interval_steps <
|
||||
self._perturbation_duration_steps) and (env.env_step_counter >=
|
||||
self._perturbation_start_step):
|
||||
env.pybullet_client.applyExternalForce(
|
||||
objectUniqueId=env.minitaur.quadruped,
|
||||
linkIndex=self._applied_link_id,
|
||||
forceObj=self._applied_force,
|
||||
posObj=[0.0, 0.0, 0.0],
|
||||
flags=env.pybullet_client.LINK_FRAME)
|
||||
env.pybullet_client.applyExternalForce(objectUniqueId=env.minitaur.quadruped,
|
||||
linkIndex=self._applied_link_id,
|
||||
forceObj=self._applied_force,
|
||||
posObj=[0.0, 0.0, 0.0],
|
||||
flags=env.pybullet_client.LINK_FRAME)
|
||||
|
||||
@@ -4,11 +4,11 @@ from __future__ import absolute_import
|
||||
from __future__ import division
|
||||
from __future__ import print_function
|
||||
|
||||
import os, inspect
|
||||
import os, inspect
|
||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||
parentdir = os.path.dirname(os.path.dirname(parentdir))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
import itertools
|
||||
import math
|
||||
@@ -62,8 +62,7 @@ class PoissonDisc2D(object):
|
||||
self._grid = [None] * self._grid_size_x * self._grid_size_y
|
||||
|
||||
# Generate the first sample point and set it as an active site.
|
||||
first_sample = np.array(
|
||||
np.random.random_sample(2)) * [grid_length, grid_width]
|
||||
first_sample = np.array(np.random.random_sample(2)) * [grid_length, grid_width]
|
||||
self._active_list = [first_sample]
|
||||
|
||||
# Also store the sample point in the grid.
|
||||
@@ -114,8 +113,7 @@ class PoissonDisc2D(object):
|
||||
Returns:
|
||||
Whether the point is inside the grid.
|
||||
"""
|
||||
return (0 <= point[0] < self._grid_length) and (0 <= point[1] <
|
||||
self._grid_width)
|
||||
return (0 <= point[0] < self._grid_length) and (0 <= point[1] < self._grid_width)
|
||||
|
||||
def _is_in_range(self, index2d):
|
||||
"""Checks if the cell ID is within the grid.
|
||||
@@ -127,8 +125,7 @@ class PoissonDisc2D(object):
|
||||
Whether the cell (2D index) is inside the grid.
|
||||
"""
|
||||
|
||||
return (0 <= index2d[0] < self._grid_size_x) and (0 <= index2d[1] <
|
||||
self._grid_size_y)
|
||||
return (0 <= index2d[0] < self._grid_size_x) and (0 <= index2d[1] < self._grid_size_y)
|
||||
|
||||
def _is_close_to_existing_points(self, point):
|
||||
"""Checks if the point is close to any already sampled (and stored) points.
|
||||
@@ -142,15 +139,13 @@ class PoissonDisc2D(object):
|
||||
"""
|
||||
px, py = self._point_to_index_2d(point)
|
||||
# Now we can check nearby cells for existing points
|
||||
for neighbor_cell in itertools.product(
|
||||
xrange(px - 1, px + 2), xrange(py - 1, py + 2)):
|
||||
for neighbor_cell in itertools.product(xrange(px - 1, px + 2), xrange(py - 1, py + 2)):
|
||||
|
||||
if not self._is_in_range(neighbor_cell):
|
||||
continue
|
||||
|
||||
maybe_a_point = self._grid[self._index_2d_to_1d(neighbor_cell)]
|
||||
if maybe_a_point is not None and np.linalg.norm(
|
||||
maybe_a_point - point) < self._min_radius:
|
||||
if maybe_a_point is not None and np.linalg.norm(maybe_a_point - point) < self._min_radius:
|
||||
return True
|
||||
|
||||
return False
|
||||
@@ -168,8 +163,8 @@ class PoissonDisc2D(object):
|
||||
random_angle = np.random.uniform(0, 2 * math.pi)
|
||||
|
||||
# The sampled 2D points near the active point
|
||||
sample = random_radius * np.array(
|
||||
[np.cos(random_angle), np.sin(random_angle)]) + active_point
|
||||
sample = random_radius * np.array([np.cos(random_angle),
|
||||
np.sin(random_angle)]) + active_point
|
||||
|
||||
if not self._is_in_grid(sample):
|
||||
continue
|
||||
@@ -214,12 +209,11 @@ class TerrainType(enum.Enum):
|
||||
class MinitaurTerrainRandomizer(env_randomizer_base.EnvRandomizerBase):
|
||||
"""Generates an uneven terrain in the gym env."""
|
||||
|
||||
def __init__(
|
||||
self,
|
||||
terrain_type=TerrainType.TRIANGLE_MESH,
|
||||
mesh_filename="robotics/reinforcement_learning/minitaur/envs/testdata/"
|
||||
"triangle_mesh_terrain/terrain9735.obj",
|
||||
mesh_scale=None):
|
||||
def __init__(self,
|
||||
terrain_type=TerrainType.TRIANGLE_MESH,
|
||||
mesh_filename="robotics/reinforcement_learning/minitaur/envs/testdata/"
|
||||
"triangle_mesh_terrain/terrain9735.obj",
|
||||
mesh_scale=None):
|
||||
"""Initializes the randomizer.
|
||||
|
||||
Args:
|
||||
@@ -261,9 +255,7 @@ class MinitaurTerrainRandomizer(env_randomizer_base.EnvRandomizerBase):
|
||||
flags=1,
|
||||
meshScale=self._mesh_scale)
|
||||
env.ground_id = env.pybullet_client.createMultiBody(
|
||||
baseMass=0,
|
||||
baseCollisionShapeIndex=terrain_collision_shape_id,
|
||||
basePosition=[0, 0, 0])
|
||||
baseMass=0, baseCollisionShapeIndex=terrain_collision_shape_id, basePosition=[0, 0, 0])
|
||||
|
||||
def _generate_convex_blocks(self, env):
|
||||
"""Adds random convex blocks to the flat ground.
|
||||
@@ -277,8 +269,7 @@ class MinitaurTerrainRandomizer(env_randomizer_base.EnvRandomizerBase):
|
||||
|
||||
"""
|
||||
|
||||
poisson_disc = PoissonDisc2D(_GRID_LENGTH, _GRID_WIDTH, _MIN_BLOCK_DISTANCE,
|
||||
_MAX_SAMPLE_SIZE)
|
||||
poisson_disc = PoissonDisc2D(_GRID_LENGTH, _GRID_WIDTH, _MIN_BLOCK_DISTANCE, _MAX_SAMPLE_SIZE)
|
||||
|
||||
block_centers = poisson_disc.generate()
|
||||
|
||||
@@ -289,12 +280,10 @@ class MinitaurTerrainRandomizer(env_randomizer_base.EnvRandomizerBase):
|
||||
# Do not place blocks near the point [0, 0], where the robot will start.
|
||||
if abs(shifted_center[0]) < 1.0 and abs(shifted_center[1]) < 1.0:
|
||||
continue
|
||||
half_length = np.random.uniform(_MIN_BLOCK_LENGTH, _MAX_BLOCK_LENGTH) / (
|
||||
2 * math.sqrt(2))
|
||||
half_length = np.random.uniform(_MIN_BLOCK_LENGTH, _MAX_BLOCK_LENGTH) / (2 * math.sqrt(2))
|
||||
half_height = np.random.uniform(_MIN_BLOCK_HEIGHT, _MAX_BLOCK_HEIGHT) / 2
|
||||
box_id = env.pybullet_client.createCollisionShape(
|
||||
env.pybullet_client.GEOM_BOX,
|
||||
halfExtents=[half_length, half_length, half_height])
|
||||
env.pybullet_client.GEOM_BOX, halfExtents=[half_length, half_length, half_height])
|
||||
env.pybullet_client.createMultiBody(
|
||||
baseMass=0,
|
||||
baseCollisionShapeIndex=box_id,
|
||||
|
||||
Reference in New Issue
Block a user