add yapf style and apply yapf to format all Python files
This recreates pull request #2192
This commit is contained in:
@@ -5,6 +5,3 @@ from pybullet_envs.minitaur.envs.minitaur_reactive_env import MinitaurReactiveEn
|
||||
from pybullet_envs.minitaur.envs.minitaur_stand_gym_env import MinitaurStandGymEnv
|
||||
from pybullet_envs.minitaur.envs.minitaur_trotting_env import MinitaurTrottingEnv
|
||||
from pybullet_envs.minitaur.envs.minitaur_four_leg_stand_env import MinitaurFourLegStandEnv
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -42,9 +42,13 @@ class BulletClient(object):
|
||||
attribute = getattr(pybullet, name)
|
||||
if inspect.isbuiltin(attribute):
|
||||
if name not in [
|
||||
"invertTransform", "multiplyTransforms", "getMatrixFromQuaternion",
|
||||
"getEulerFromQuaternion", "computeViewMatrixFromYawPitchRoll",
|
||||
"computeProjectionMatrixFOV", "getQuaternionFromEuler",
|
||||
"invertTransform",
|
||||
"multiplyTransforms",
|
||||
"getMatrixFromQuaternion",
|
||||
"getEulerFromQuaternion",
|
||||
"computeViewMatrixFromYawPitchRoll",
|
||||
"computeProjectionMatrixFOV",
|
||||
"getQuaternionFromEuler",
|
||||
]: # A temporary hack for now.
|
||||
attribute = functools.partial(attribute, physicsClientId=self._client)
|
||||
return attribute
|
||||
|
||||
@@ -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,
|
||||
|
||||
@@ -2,10 +2,10 @@
|
||||
|
||||
"""
|
||||
|
||||
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))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
import collections
|
||||
import copy
|
||||
@@ -24,9 +24,8 @@ OVERHEAT_SHUTDOWN_TORQUE = 2.45
|
||||
OVERHEAT_SHUTDOWN_TIME = 1.0
|
||||
LEG_POSITION = ["front_left", "back_left", "front_right", "back_right"]
|
||||
MOTOR_NAMES = [
|
||||
"motor_front_leftL_joint", "motor_front_leftR_joint",
|
||||
"motor_back_leftL_joint", "motor_back_leftR_joint",
|
||||
"motor_front_rightL_joint", "motor_front_rightR_joint",
|
||||
"motor_front_leftL_joint", "motor_front_leftR_joint", "motor_back_leftL_joint",
|
||||
"motor_back_leftR_joint", "motor_front_rightL_joint", "motor_front_rightR_joint",
|
||||
"motor_back_rightL_joint", "motor_back_rightR_joint"
|
||||
]
|
||||
_CHASSIS_NAME_PATTERN = re.compile(r"chassis\D*center")
|
||||
@@ -141,10 +140,9 @@ class Minitaur(object):
|
||||
if self._accurate_motor_model_enabled:
|
||||
self._kp = motor_kp
|
||||
self._kd = motor_kd
|
||||
self._motor_model = motor.MotorModel(
|
||||
torque_control_enabled=self._torque_control_enabled,
|
||||
kp=self._kp,
|
||||
kd=self._kd)
|
||||
self._motor_model = motor.MotorModel(torque_control_enabled=self._torque_control_enabled,
|
||||
kp=self._kp,
|
||||
kd=self._kd)
|
||||
elif self._pd_control_enabled:
|
||||
self._kp = 8
|
||||
self._kd = 0.3
|
||||
@@ -188,17 +186,14 @@ class Minitaur(object):
|
||||
self._link_urdf = []
|
||||
num_bodies = self._pybullet_client.getNumJoints(self.quadruped)
|
||||
for body_id in range(-1, num_bodies): # -1 is for the base link.
|
||||
inertia = self._pybullet_client.getDynamicsInfo(self.quadruped,
|
||||
body_id)[2]
|
||||
inertia = self._pybullet_client.getDynamicsInfo(self.quadruped, body_id)[2]
|
||||
self._link_urdf.append(inertia)
|
||||
# We need to use id+1 to index self._link_urdf because it has the base
|
||||
# (index = -1) at the first element.
|
||||
self._base_inertia_urdf = [
|
||||
self._link_urdf[chassis_id + 1] for chassis_id in self._chassis_link_ids
|
||||
]
|
||||
self._leg_inertia_urdf = [
|
||||
self._link_urdf[leg_id + 1] for leg_id in self._leg_link_ids
|
||||
]
|
||||
self._leg_inertia_urdf = [self._link_urdf[leg_id + 1] for leg_id in self._leg_link_ids]
|
||||
self._leg_inertia_urdf.extend(
|
||||
[self._link_urdf[motor_id + 1] for motor_id in self._motor_link_ids])
|
||||
|
||||
@@ -239,13 +234,10 @@ class Minitaur(object):
|
||||
num_joints = self._pybullet_client.getNumJoints(self.quadruped)
|
||||
for i in range(num_joints):
|
||||
joint_info = self._pybullet_client.getJointInfo(self.quadruped, i)
|
||||
self._pybullet_client.changeDynamics(
|
||||
joint_info[0], -1, linearDamping=0, angularDamping=0)
|
||||
self._pybullet_client.changeDynamics(joint_info[0], -1, linearDamping=0, angularDamping=0)
|
||||
|
||||
def _BuildMotorIdList(self):
|
||||
self._motor_id_list = [
|
||||
self._joint_name_to_id[motor_name] for motor_name in MOTOR_NAMES
|
||||
]
|
||||
self._motor_id_list = [self._joint_name_to_id[motor_name] for motor_name in MOTOR_NAMES]
|
||||
|
||||
def IsObservationValid(self):
|
||||
"""Whether the observation is valid for the current time step.
|
||||
@@ -284,10 +276,10 @@ class Minitaur(object):
|
||||
useFixedBase=self._on_rack,
|
||||
flags=self._pybullet_client.URDF_USE_SELF_COLLISION)
|
||||
else:
|
||||
self.quadruped = self._pybullet_client.loadURDF(
|
||||
"%s/quadruped/minitaur.urdf" % self._urdf_root,
|
||||
init_position,
|
||||
useFixedBase=self._on_rack)
|
||||
self.quadruped = self._pybullet_client.loadURDF("%s/quadruped/minitaur.urdf" %
|
||||
self._urdf_root,
|
||||
init_position,
|
||||
useFixedBase=self._on_rack)
|
||||
self._BuildJointNameToIdDict()
|
||||
self._BuildUrdfIds()
|
||||
if self._remove_default_joint_damping:
|
||||
@@ -297,10 +289,9 @@ class Minitaur(object):
|
||||
self._RecordInertiaInfoFromURDF()
|
||||
self.ResetPose(add_constraint=True)
|
||||
else:
|
||||
self._pybullet_client.resetBasePositionAndOrientation(
|
||||
self.quadruped, init_position, INIT_ORIENTATION)
|
||||
self._pybullet_client.resetBaseVelocity(self.quadruped, [0, 0, 0],
|
||||
[0, 0, 0])
|
||||
self._pybullet_client.resetBasePositionAndOrientation(self.quadruped, init_position,
|
||||
INIT_ORIENTATION)
|
||||
self._pybullet_client.resetBaseVelocity(self.quadruped, [0, 0, 0], [0, 0, 0])
|
||||
self.ResetPose(add_constraint=False)
|
||||
self._overheat_counter = np.zeros(self.num_motors)
|
||||
self._motor_enabled_list = [True] * self.num_motors
|
||||
@@ -325,25 +316,22 @@ class Minitaur(object):
|
||||
self.ReceiveObservation()
|
||||
|
||||
def _SetMotorTorqueById(self, motor_id, torque):
|
||||
self._pybullet_client.setJointMotorControl2(
|
||||
bodyIndex=self.quadruped,
|
||||
jointIndex=motor_id,
|
||||
controlMode=self._pybullet_client.TORQUE_CONTROL,
|
||||
force=torque)
|
||||
self._pybullet_client.setJointMotorControl2(bodyIndex=self.quadruped,
|
||||
jointIndex=motor_id,
|
||||
controlMode=self._pybullet_client.TORQUE_CONTROL,
|
||||
force=torque)
|
||||
|
||||
def _SetDesiredMotorAngleById(self, motor_id, desired_angle):
|
||||
self._pybullet_client.setJointMotorControl2(
|
||||
bodyIndex=self.quadruped,
|
||||
jointIndex=motor_id,
|
||||
controlMode=self._pybullet_client.POSITION_CONTROL,
|
||||
targetPosition=desired_angle,
|
||||
positionGain=self._kp,
|
||||
velocityGain=self._kd,
|
||||
force=self._max_force)
|
||||
self._pybullet_client.setJointMotorControl2(bodyIndex=self.quadruped,
|
||||
jointIndex=motor_id,
|
||||
controlMode=self._pybullet_client.POSITION_CONTROL,
|
||||
targetPosition=desired_angle,
|
||||
positionGain=self._kp,
|
||||
velocityGain=self._kd,
|
||||
force=self._max_force)
|
||||
|
||||
def _SetDesiredMotorAngleByName(self, motor_name, desired_angle):
|
||||
self._SetDesiredMotorAngleById(self._joint_name_to_id[motor_name],
|
||||
desired_angle)
|
||||
self._SetDesiredMotorAngleById(self._joint_name_to_id[motor_name], desired_angle)
|
||||
|
||||
def ResetPose(self, add_constraint):
|
||||
"""Reset the pose of the minitaur.
|
||||
@@ -367,59 +355,53 @@ class Minitaur(object):
|
||||
knee_angle = -2.1834
|
||||
|
||||
leg_position = LEG_POSITION[leg_id]
|
||||
self._pybullet_client.resetJointState(
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["motor_" + leg_position + "L_joint"],
|
||||
self._motor_direction[2 * leg_id] * half_pi,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position + "L_link"],
|
||||
self._motor_direction[2 * leg_id] * knee_angle,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["motor_" + leg_position + "R_joint"],
|
||||
self._motor_direction[2 * leg_id + 1] * half_pi,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position + "R_link"],
|
||||
self._motor_direction[2 * leg_id + 1] * knee_angle,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(self.quadruped,
|
||||
self._joint_name_to_id["motor_" + leg_position +
|
||||
"L_joint"],
|
||||
self._motor_direction[2 * leg_id] * half_pi,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position +
|
||||
"L_link"],
|
||||
self._motor_direction[2 * leg_id] * knee_angle,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(self.quadruped,
|
||||
self._joint_name_to_id["motor_" + leg_position +
|
||||
"R_joint"],
|
||||
self._motor_direction[2 * leg_id + 1] * half_pi,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position +
|
||||
"R_link"],
|
||||
self._motor_direction[2 * leg_id + 1] * knee_angle,
|
||||
targetVelocity=0)
|
||||
if add_constraint:
|
||||
self._pybullet_client.createConstraint(
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position + "R_link"],
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position + "L_link"],
|
||||
self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0],
|
||||
KNEE_CONSTRAINT_POINT_RIGHT, KNEE_CONSTRAINT_POINT_LEFT)
|
||||
self.quadruped, self._joint_name_to_id["knee_" + leg_position + "R_link"],
|
||||
self.quadruped, self._joint_name_to_id["knee_" + leg_position + "L_link"],
|
||||
self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0], KNEE_CONSTRAINT_POINT_RIGHT,
|
||||
KNEE_CONSTRAINT_POINT_LEFT)
|
||||
|
||||
if self._accurate_motor_model_enabled or self._pd_control_enabled:
|
||||
# Disable the default motor in pybullet.
|
||||
self._pybullet_client.setJointMotorControl2(
|
||||
bodyIndex=self.quadruped,
|
||||
jointIndex=(
|
||||
self._joint_name_to_id["motor_" + leg_position + "L_joint"]),
|
||||
jointIndex=(self._joint_name_to_id["motor_" + leg_position + "L_joint"]),
|
||||
controlMode=self._pybullet_client.VELOCITY_CONTROL,
|
||||
targetVelocity=0,
|
||||
force=knee_friction_force)
|
||||
self._pybullet_client.setJointMotorControl2(
|
||||
bodyIndex=self.quadruped,
|
||||
jointIndex=(
|
||||
self._joint_name_to_id["motor_" + leg_position + "R_joint"]),
|
||||
jointIndex=(self._joint_name_to_id["motor_" + leg_position + "R_joint"]),
|
||||
controlMode=self._pybullet_client.VELOCITY_CONTROL,
|
||||
targetVelocity=0,
|
||||
force=knee_friction_force)
|
||||
|
||||
else:
|
||||
self._SetDesiredMotorAngleByName(
|
||||
"motor_" + leg_position + "L_joint",
|
||||
self._motor_direction[2 * leg_id] * half_pi)
|
||||
self._SetDesiredMotorAngleByName(
|
||||
"motor_" + leg_position + "R_joint",
|
||||
self._motor_direction[2 * leg_id + 1] * half_pi)
|
||||
self._SetDesiredMotorAngleByName("motor_" + leg_position + "L_joint",
|
||||
self._motor_direction[2 * leg_id] * half_pi)
|
||||
self._SetDesiredMotorAngleByName("motor_" + leg_position + "R_joint",
|
||||
self._motor_direction[2 * leg_id + 1] * half_pi)
|
||||
|
||||
self._pybullet_client.setJointMotorControl2(
|
||||
bodyIndex=self.quadruped,
|
||||
@@ -440,8 +422,7 @@ class Minitaur(object):
|
||||
Returns:
|
||||
The position of minitaur's base.
|
||||
"""
|
||||
position, _ = (
|
||||
self._pybullet_client.getBasePositionAndOrientation(self.quadruped))
|
||||
position, _ = (self._pybullet_client.getBasePositionAndOrientation(self.quadruped))
|
||||
return position
|
||||
|
||||
def GetTrueBaseRollPitchYaw(self):
|
||||
@@ -464,10 +445,9 @@ class Minitaur(object):
|
||||
"""
|
||||
delayed_orientation = np.array(
|
||||
self._control_observation[3 * self.num_motors:3 * self.num_motors + 4])
|
||||
delayed_roll_pitch_yaw = self._pybullet_client.getEulerFromQuaternion(
|
||||
delayed_orientation)
|
||||
roll_pitch_yaw = self._AddSensorNoise(
|
||||
np.array(delayed_roll_pitch_yaw), self._observation_noise_stdev[3])
|
||||
delayed_roll_pitch_yaw = self._pybullet_client.getEulerFromQuaternion(delayed_orientation)
|
||||
roll_pitch_yaw = self._AddSensorNoise(np.array(delayed_roll_pitch_yaw),
|
||||
self._observation_noise_stdev[3])
|
||||
return roll_pitch_yaw
|
||||
|
||||
def GetTrueMotorAngles(self):
|
||||
@@ -492,9 +472,8 @@ class Minitaur(object):
|
||||
Returns:
|
||||
Motor angles polluted by noise and latency, mapped to [-pi, pi].
|
||||
"""
|
||||
motor_angles = self._AddSensorNoise(
|
||||
np.array(self._control_observation[0:self.num_motors]),
|
||||
self._observation_noise_stdev[0])
|
||||
motor_angles = self._AddSensorNoise(np.array(self._control_observation[0:self.num_motors]),
|
||||
self._observation_noise_stdev[0])
|
||||
return MapToMinusPiToPi(motor_angles)
|
||||
|
||||
def GetTrueMotorVelocities(self):
|
||||
@@ -518,8 +497,7 @@ class Minitaur(object):
|
||||
Velocities of all eight motors polluted by noise and latency.
|
||||
"""
|
||||
return self._AddSensorNoise(
|
||||
np.array(
|
||||
self._control_observation[self.num_motors:2 * self.num_motors]),
|
||||
np.array(self._control_observation[self.num_motors:2 * self.num_motors]),
|
||||
self._observation_noise_stdev[1])
|
||||
|
||||
def GetTrueMotorTorques(self):
|
||||
@@ -546,8 +524,7 @@ class Minitaur(object):
|
||||
Motor torques of all eight motors polluted by noise and latency.
|
||||
"""
|
||||
return self._AddSensorNoise(
|
||||
np.array(
|
||||
self._control_observation[2 * self.num_motors:3 * self.num_motors]),
|
||||
np.array(self._control_observation[2 * self.num_motors:3 * self.num_motors]),
|
||||
self._observation_noise_stdev[2])
|
||||
|
||||
def GetTrueBaseOrientation(self):
|
||||
@@ -556,8 +533,7 @@ class Minitaur(object):
|
||||
Returns:
|
||||
The orientation of minitaur's base.
|
||||
"""
|
||||
_, orientation = (
|
||||
self._pybullet_client.getBasePositionAndOrientation(self.quadruped))
|
||||
_, orientation = (self._pybullet_client.getBasePositionAndOrientation(self.quadruped))
|
||||
return orientation
|
||||
|
||||
def GetBaseOrientation(self):
|
||||
@@ -567,8 +543,7 @@ class Minitaur(object):
|
||||
Returns:
|
||||
The orientation of minitaur's base polluted by noise and latency.
|
||||
"""
|
||||
return self._pybullet_client.getQuaternionFromEuler(
|
||||
self.GetBaseRollPitchYaw())
|
||||
return self._pybullet_client.getQuaternionFromEuler(self.GetBaseRollPitchYaw())
|
||||
|
||||
def GetTrueBaseRollPitchYawRate(self):
|
||||
"""Get the rate of orientation change of the minitaur's base in euler angle.
|
||||
@@ -588,8 +563,7 @@ class Minitaur(object):
|
||||
and latency.
|
||||
"""
|
||||
return self._AddSensorNoise(
|
||||
np.array(self._control_observation[3 * self.num_motors + 4:
|
||||
3 * self.num_motors + 7]),
|
||||
np.array(self._control_observation[3 * self.num_motors + 4:3 * self.num_motors + 7]),
|
||||
self._observation_noise_stdev[4])
|
||||
|
||||
def GetActionDimension(self):
|
||||
@@ -618,12 +592,9 @@ class Minitaur(object):
|
||||
"""
|
||||
if self._motor_velocity_limit < np.inf:
|
||||
current_motor_angle = self.GetTrueMotorAngles()
|
||||
motor_commands_max = (
|
||||
current_motor_angle + self.time_step * self._motor_velocity_limit)
|
||||
motor_commands_min = (
|
||||
current_motor_angle - self.time_step * self._motor_velocity_limit)
|
||||
motor_commands = np.clip(motor_commands, motor_commands_min,
|
||||
motor_commands_max)
|
||||
motor_commands_max = (current_motor_angle + self.time_step * self._motor_velocity_limit)
|
||||
motor_commands_min = (current_motor_angle - self.time_step * self._motor_velocity_limit)
|
||||
motor_commands = np.clip(motor_commands, motor_commands_min, motor_commands_max)
|
||||
# Set the kp and kd for all the motors if not provided as an argument.
|
||||
if motor_kps is None:
|
||||
motor_kps = np.full(8, self._kp)
|
||||
@@ -642,8 +613,7 @@ class Minitaur(object):
|
||||
self._overheat_counter[i] += 1
|
||||
else:
|
||||
self._overheat_counter[i] = 0
|
||||
if (self._overheat_counter[i] >
|
||||
OVERHEAT_SHUTDOWN_TIME / self.time_step):
|
||||
if (self._overheat_counter[i] > OVERHEAT_SHUTDOWN_TIME / self.time_step):
|
||||
self._motor_enabled_list[i] = False
|
||||
|
||||
# The torque is already in the observation space because we use
|
||||
@@ -651,19 +621,17 @@ class Minitaur(object):
|
||||
self._observed_motor_torques = observed_torque
|
||||
|
||||
# Transform into the motor space when applying the torque.
|
||||
self._applied_motor_torque = np.multiply(actual_torque,
|
||||
self._motor_direction)
|
||||
self._applied_motor_torque = np.multiply(actual_torque, self._motor_direction)
|
||||
|
||||
for motor_id, motor_torque, motor_enabled in zip(
|
||||
self._motor_id_list, self._applied_motor_torque,
|
||||
self._motor_enabled_list):
|
||||
for motor_id, motor_torque, motor_enabled in zip(self._motor_id_list,
|
||||
self._applied_motor_torque,
|
||||
self._motor_enabled_list):
|
||||
if motor_enabled:
|
||||
self._SetMotorTorqueById(motor_id, motor_torque)
|
||||
else:
|
||||
self._SetMotorTorqueById(motor_id, 0)
|
||||
else:
|
||||
torque_commands = -1 * motor_kps * (
|
||||
q - motor_commands) - motor_kds * qdot
|
||||
torque_commands = -1 * motor_kps * (q - motor_commands) - motor_kds * qdot
|
||||
|
||||
# The torque is already in the observation space because we use
|
||||
# GetMotorAngles and GetMotorVelocities.
|
||||
@@ -673,14 +641,12 @@ class Minitaur(object):
|
||||
self._applied_motor_torques = np.multiply(self._observed_motor_torques,
|
||||
self._motor_direction)
|
||||
|
||||
for motor_id, motor_torque in zip(self._motor_id_list,
|
||||
self._applied_motor_torques):
|
||||
for motor_id, motor_torque in zip(self._motor_id_list, self._applied_motor_torques):
|
||||
self._SetMotorTorqueById(motor_id, motor_torque)
|
||||
else:
|
||||
motor_commands_with_direction = np.multiply(motor_commands,
|
||||
self._motor_direction)
|
||||
for motor_id, motor_command_with_direction in zip(
|
||||
self._motor_id_list, motor_commands_with_direction):
|
||||
motor_commands_with_direction = np.multiply(motor_commands, self._motor_direction)
|
||||
for motor_id, motor_command_with_direction in zip(self._motor_id_list,
|
||||
motor_commands_with_direction):
|
||||
self._SetDesiredMotorAngleById(motor_id, motor_command_with_direction)
|
||||
|
||||
def ConvertFromLegModel(self, actions):
|
||||
@@ -698,13 +664,13 @@ class Minitaur(object):
|
||||
quater_pi = math.pi / 4
|
||||
for i in range(self.num_motors):
|
||||
action_idx = int(i // 2)
|
||||
forward_backward_component = (-scale_for_singularity * quater_pi * (
|
||||
actions[action_idx + half_num_motors] + offset_for_singularity))
|
||||
forward_backward_component = (
|
||||
-scale_for_singularity * quater_pi *
|
||||
(actions[action_idx + half_num_motors] + offset_for_singularity))
|
||||
extension_component = (-1)**i * quater_pi * actions[action_idx]
|
||||
if i >= half_num_motors:
|
||||
extension_component = -extension_component
|
||||
motor_angle[i] = (
|
||||
math.pi + forward_backward_component + extension_component)
|
||||
motor_angle[i] = (math.pi + forward_backward_component + extension_component)
|
||||
return motor_angle
|
||||
|
||||
def GetBaseMassesFromURDF(self):
|
||||
@@ -734,12 +700,10 @@ class Minitaur(object):
|
||||
the length of self._chassis_link_ids.
|
||||
"""
|
||||
if len(base_mass) != len(self._chassis_link_ids):
|
||||
raise ValueError(
|
||||
"The length of base_mass {} and self._chassis_link_ids {} are not "
|
||||
"the same.".format(len(base_mass), len(self._chassis_link_ids)))
|
||||
raise ValueError("The length of base_mass {} and self._chassis_link_ids {} are not "
|
||||
"the same.".format(len(base_mass), len(self._chassis_link_ids)))
|
||||
for chassis_id, chassis_mass in zip(self._chassis_link_ids, base_mass):
|
||||
self._pybullet_client.changeDynamics(
|
||||
self.quadruped, chassis_id, mass=chassis_mass)
|
||||
self._pybullet_client.changeDynamics(self.quadruped, chassis_id, mass=chassis_mass)
|
||||
|
||||
def SetLegMasses(self, leg_masses):
|
||||
"""Set the mass of the legs.
|
||||
@@ -759,12 +723,10 @@ class Minitaur(object):
|
||||
raise ValueError("The number of values passed to SetLegMasses are "
|
||||
"different than number of leg links and motors.")
|
||||
for leg_id, leg_mass in zip(self._leg_link_ids, leg_masses):
|
||||
self._pybullet_client.changeDynamics(
|
||||
self.quadruped, leg_id, mass=leg_mass)
|
||||
self._pybullet_client.changeDynamics(self.quadruped, leg_id, mass=leg_mass)
|
||||
motor_masses = leg_masses[len(self._leg_link_ids):]
|
||||
for link_id, motor_mass in zip(self._motor_link_ids, motor_masses):
|
||||
self._pybullet_client.changeDynamics(
|
||||
self.quadruped, link_id, mass=motor_mass)
|
||||
self._pybullet_client.changeDynamics(self.quadruped, link_id, mass=motor_mass)
|
||||
|
||||
def SetBaseInertias(self, base_inertias):
|
||||
"""Set the inertias of minitaur's base.
|
||||
@@ -779,17 +741,15 @@ class Minitaur(object):
|
||||
negative values.
|
||||
"""
|
||||
if len(base_inertias) != len(self._chassis_link_ids):
|
||||
raise ValueError(
|
||||
"The length of base_inertias {} and self._chassis_link_ids {} are "
|
||||
"not the same.".format(
|
||||
len(base_inertias), len(self._chassis_link_ids)))
|
||||
for chassis_id, chassis_inertia in zip(self._chassis_link_ids,
|
||||
base_inertias):
|
||||
raise ValueError("The length of base_inertias {} and self._chassis_link_ids {} are "
|
||||
"not the same.".format(len(base_inertias), len(self._chassis_link_ids)))
|
||||
for chassis_id, chassis_inertia in zip(self._chassis_link_ids, base_inertias):
|
||||
for inertia_value in chassis_inertia:
|
||||
if (np.asarray(inertia_value) < 0).any():
|
||||
raise ValueError("Values in inertia matrix should be non-negative.")
|
||||
self._pybullet_client.changeDynamics(
|
||||
self.quadruped, chassis_id, localInertiaDiagonal=chassis_inertia)
|
||||
self._pybullet_client.changeDynamics(self.quadruped,
|
||||
chassis_id,
|
||||
localInertiaDiagonal=chassis_inertia)
|
||||
|
||||
def SetLegInertias(self, leg_inertias):
|
||||
"""Set the inertias of the legs.
|
||||
@@ -813,16 +773,18 @@ class Minitaur(object):
|
||||
for inertia_value in leg_inertias:
|
||||
if (np.asarray(inertia_value) < 0).any():
|
||||
raise ValueError("Values in inertia matrix should be non-negative.")
|
||||
self._pybullet_client.changeDynamics(
|
||||
self.quadruped, leg_id, localInertiaDiagonal=leg_inertia)
|
||||
self._pybullet_client.changeDynamics(self.quadruped,
|
||||
leg_id,
|
||||
localInertiaDiagonal=leg_inertia)
|
||||
|
||||
motor_inertias = leg_inertias[len(self._leg_link_ids):]
|
||||
for link_id, motor_inertia in zip(self._motor_link_ids, motor_inertias):
|
||||
for inertia_value in motor_inertias:
|
||||
if (np.asarray(inertia_value) < 0).any():
|
||||
raise ValueError("Values in inertia matrix should be non-negative.")
|
||||
self._pybullet_client.changeDynamics(
|
||||
self.quadruped, link_id, localInertiaDiagonal=motor_inertia)
|
||||
self._pybullet_client.changeDynamics(self.quadruped,
|
||||
link_id,
|
||||
localInertiaDiagonal=motor_inertia)
|
||||
|
||||
def SetFootFriction(self, foot_friction):
|
||||
"""Set the lateral friction of the feet.
|
||||
@@ -832,8 +794,7 @@ class Minitaur(object):
|
||||
shared by all four feet.
|
||||
"""
|
||||
for link_id in self._foot_link_ids:
|
||||
self._pybullet_client.changeDynamics(
|
||||
self.quadruped, link_id, lateralFriction=foot_friction)
|
||||
self._pybullet_client.changeDynamics(self.quadruped, link_id, lateralFriction=foot_friction)
|
||||
|
||||
# TODO(b/73748980): Add more API's to set other contact parameters.
|
||||
def SetFootRestitution(self, foot_restitution):
|
||||
@@ -844,8 +805,7 @@ class Minitaur(object):
|
||||
This value is shared by all four feet.
|
||||
"""
|
||||
for link_id in self._foot_link_ids:
|
||||
self._pybullet_client.changeDynamics(
|
||||
self.quadruped, link_id, restitution=foot_restitution)
|
||||
self._pybullet_client.changeDynamics(self.quadruped, link_id, restitution=foot_restitution)
|
||||
|
||||
def SetJointFriction(self, joint_frictions):
|
||||
for knee_joint_id, friction in zip(self._foot_link_ids, joint_frictions):
|
||||
@@ -901,9 +861,8 @@ class Minitaur(object):
|
||||
return self._observation_history[-1]
|
||||
remaining_latency = latency - n_steps_ago * self.time_step
|
||||
blend_alpha = remaining_latency / self.time_step
|
||||
observation = (
|
||||
(1.0 - blend_alpha) * np.array(self._observation_history[n_steps_ago])
|
||||
+ blend_alpha * np.array(self._observation_history[n_steps_ago + 1]))
|
||||
observation = ((1.0 - blend_alpha) * np.array(self._observation_history[n_steps_ago]) +
|
||||
blend_alpha * np.array(self._observation_history[n_steps_ago + 1]))
|
||||
return observation
|
||||
|
||||
def _GetPDObservation(self):
|
||||
@@ -913,15 +872,13 @@ class Minitaur(object):
|
||||
return (np.array(q), np.array(qdot))
|
||||
|
||||
def _GetControlObservation(self):
|
||||
control_delayed_observation = self._GetDelayedObservation(
|
||||
self._control_latency)
|
||||
control_delayed_observation = self._GetDelayedObservation(self._control_latency)
|
||||
return control_delayed_observation
|
||||
|
||||
def _AddSensorNoise(self, sensor_values, noise_stdev):
|
||||
if noise_stdev <= 0:
|
||||
return sensor_values
|
||||
observation = sensor_values + np.random.normal(
|
||||
scale=noise_stdev, size=sensor_values.shape)
|
||||
observation = sensor_values + np.random.normal(scale=noise_stdev, size=sensor_values.shape)
|
||||
return observation
|
||||
|
||||
def SetControlLatency(self, latency):
|
||||
|
||||
@@ -3,10 +3,10 @@
|
||||
"""
|
||||
import math
|
||||
|
||||
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))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
from gym import spaces
|
||||
import numpy as np
|
||||
@@ -31,10 +31,7 @@ class MinitaurAlternatingLegsEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
expenditure.
|
||||
|
||||
"""
|
||||
metadata = {
|
||||
"render.modes": ["human", "rgb_array"],
|
||||
"video.frames_per_second": 66
|
||||
}
|
||||
metadata = {"render.modes": ["human", "rgb_array"], "video.frames_per_second": 66}
|
||||
|
||||
def __init__(self,
|
||||
urdf_version=None,
|
||||
@@ -81,23 +78,23 @@ class MinitaurAlternatingLegsEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
# _swing_offset and _extension_offset is to mimick the bent legs.
|
||||
self._swing_offset = np.zeros(NUM_LEGS)
|
||||
self._extension_offset = np.zeros(NUM_LEGS)
|
||||
super(MinitaurAlternatingLegsEnv, self).__init__(
|
||||
urdf_version=urdf_version,
|
||||
accurate_motor_model_enabled=True,
|
||||
motor_overheat_protection=True,
|
||||
hard_reset=False,
|
||||
motor_kp=motor_kp,
|
||||
motor_kd=motor_kd,
|
||||
remove_default_joint_damping=remove_default_joint_damping,
|
||||
control_latency=control_latency,
|
||||
pd_latency=pd_latency,
|
||||
on_rack=on_rack,
|
||||
render=render,
|
||||
num_steps_to_log=num_steps_to_log,
|
||||
env_randomizer=env_randomizer,
|
||||
log_path=log_path,
|
||||
control_time_step=control_time_step,
|
||||
action_repeat=action_repeat)
|
||||
super(MinitaurAlternatingLegsEnv,
|
||||
self).__init__(urdf_version=urdf_version,
|
||||
accurate_motor_model_enabled=True,
|
||||
motor_overheat_protection=True,
|
||||
hard_reset=False,
|
||||
motor_kp=motor_kp,
|
||||
motor_kd=motor_kd,
|
||||
remove_default_joint_damping=remove_default_joint_damping,
|
||||
control_latency=control_latency,
|
||||
pd_latency=pd_latency,
|
||||
on_rack=on_rack,
|
||||
render=render,
|
||||
num_steps_to_log=num_steps_to_log,
|
||||
env_randomizer=env_randomizer,
|
||||
log_path=log_path,
|
||||
control_time_step=control_time_step,
|
||||
action_repeat=action_repeat)
|
||||
|
||||
action_dim = 8
|
||||
action_high = np.array([0.1] * action_dim)
|
||||
@@ -113,33 +110,29 @@ class MinitaurAlternatingLegsEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
# [swing leg 1, swing leg 2, swing leg 3, swing leg 4,
|
||||
# extension leg 1, extension leg 2, extension leg 3, extension leg 4]
|
||||
init_pose = [
|
||||
INIT_SWING_POS + self._swing_offset[0],
|
||||
INIT_SWING_POS + self._swing_offset[1],
|
||||
INIT_SWING_POS + self._swing_offset[2],
|
||||
INIT_SWING_POS + self._swing_offset[3],
|
||||
INIT_SWING_POS + self._swing_offset[0], INIT_SWING_POS + self._swing_offset[1],
|
||||
INIT_SWING_POS + self._swing_offset[2], INIT_SWING_POS + self._swing_offset[3],
|
||||
INIT_EXTENSION_POS + self._extension_offset[0],
|
||||
INIT_EXTENSION_POS + self._extension_offset[1],
|
||||
INIT_EXTENSION_POS + self._extension_offset[2],
|
||||
INIT_EXTENSION_POS + self._extension_offset[3]
|
||||
]
|
||||
initial_motor_angles = self._convert_from_leg_model(init_pose)
|
||||
super(MinitaurAlternatingLegsEnv, self).reset(
|
||||
initial_motor_angles=initial_motor_angles, reset_duration=0.5)
|
||||
super(MinitaurAlternatingLegsEnv, self).reset(initial_motor_angles=initial_motor_angles,
|
||||
reset_duration=0.5)
|
||||
return self._get_observation()
|
||||
|
||||
def _convert_from_leg_model(self, leg_pose):
|
||||
motor_pose = np.zeros(NUM_MOTORS)
|
||||
for i in range(NUM_LEGS):
|
||||
motor_pose[2 * i] = leg_pose[NUM_LEGS + i] - (-1)**(i / 2) * leg_pose[i]
|
||||
motor_pose[2 * i
|
||||
+ 1] = leg_pose[NUM_LEGS + i] + (-1)**(i / 2) * leg_pose[i]
|
||||
motor_pose[2 * i + 1] = leg_pose[NUM_LEGS + i] + (-1)**(i / 2) * leg_pose[i]
|
||||
return motor_pose
|
||||
|
||||
def _signal(self, t):
|
||||
initial_pose = np.array([
|
||||
INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS,
|
||||
INIT_EXTENSION_POS, INIT_EXTENSION_POS, INIT_EXTENSION_POS,
|
||||
INIT_EXTENSION_POS
|
||||
INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS, INIT_EXTENSION_POS,
|
||||
INIT_EXTENSION_POS, INIT_EXTENSION_POS, INIT_EXTENSION_POS
|
||||
])
|
||||
amplitude = STEP_AMPLITUDE
|
||||
period = STEP_PERIOD
|
||||
|
||||
@@ -3,10 +3,10 @@
|
||||
"""
|
||||
import time
|
||||
|
||||
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))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
import os
|
||||
import numpy as np
|
||||
@@ -50,13 +50,11 @@ def hand_tuned_agent(observation, timestamp):
|
||||
pitch_compensation = pitch_gain * pitch + pitch_dot_gain * pitch_dot
|
||||
|
||||
first_leg = [
|
||||
0, -pitch_compensation, -pitch_compensation, 0, 0,
|
||||
-pitch_compensation - roll_compensation,
|
||||
0, -pitch_compensation, -pitch_compensation, 0, 0, -pitch_compensation - roll_compensation,
|
||||
pitch_compensation + roll_compensation, 0
|
||||
]
|
||||
second_leg = [
|
||||
-pitch_compensation, 0, 0, -pitch_compensation,
|
||||
pitch_compensation - roll_compensation, 0, 0,
|
||||
-pitch_compensation, 0, 0, -pitch_compensation, pitch_compensation - roll_compensation, 0, 0,
|
||||
-pitch_compensation + roll_compensation
|
||||
]
|
||||
if (timestamp // minitaur_alternating_legs_env.STEP_PERIOD) % 2:
|
||||
@@ -94,8 +92,7 @@ def hand_tuned_balance_example(log_path=None):
|
||||
for _ in range(steps):
|
||||
# Sleep to prevent serial buffer overflow on microcontroller.
|
||||
time.sleep(0.002)
|
||||
action = hand_tuned_agent(observation,
|
||||
environment.minitaur.GetTimeSinceReset())
|
||||
action = hand_tuned_agent(observation, environment.minitaur.GetTimeSinceReset())
|
||||
observation, reward, done, _ = environment.step(action)
|
||||
sum_reward += reward
|
||||
if done:
|
||||
|
||||
@@ -4,10 +4,10 @@
|
||||
import math
|
||||
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))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
from gym import spaces
|
||||
import numpy as np
|
||||
@@ -52,61 +52,52 @@ class MinitaurBallGymEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
that its walking gait is clearer to visualize.
|
||||
render: Whether to render the simulation.
|
||||
"""
|
||||
super(MinitaurBallGymEnv, self).__init__(
|
||||
urdf_root=urdf_root,
|
||||
self_collision_enabled=self_collision_enabled,
|
||||
pd_control_enabled=pd_control_enabled,
|
||||
leg_model_enabled=leg_model_enabled,
|
||||
on_rack=on_rack,
|
||||
render=render)
|
||||
super(MinitaurBallGymEnv, self).__init__(urdf_root=urdf_root,
|
||||
self_collision_enabled=self_collision_enabled,
|
||||
pd_control_enabled=pd_control_enabled,
|
||||
leg_model_enabled=leg_model_enabled,
|
||||
on_rack=on_rack,
|
||||
render=render)
|
||||
self._cam_dist = 2.0
|
||||
self._cam_yaw = -70
|
||||
self._cam_pitch = -30
|
||||
self.action_space = spaces.Box(np.array([-1]), np.array([1]))
|
||||
self.observation_space = spaces.Box(np.array([-math.pi, 0]),
|
||||
np.array([math.pi, 100]))
|
||||
self.observation_space = spaces.Box(np.array([-math.pi, 0]), np.array([math.pi, 100]))
|
||||
|
||||
def reset(self):
|
||||
self._ball_id = 0
|
||||
super(MinitaurBallGymEnv, self).reset()
|
||||
self._init_ball_theta = random.uniform(-INIT_BALL_ANGLE, INIT_BALL_ANGLE)
|
||||
self._init_ball_distance = INIT_BALL_DISTANCE
|
||||
self._ball_pos = [self._init_ball_distance *
|
||||
math.cos(self._init_ball_theta),
|
||||
self._init_ball_distance *
|
||||
math.sin(self._init_ball_theta), 1]
|
||||
self._ball_pos = [
|
||||
self._init_ball_distance * math.cos(self._init_ball_theta),
|
||||
self._init_ball_distance * math.sin(self._init_ball_theta), 1
|
||||
]
|
||||
self._ball_id = self._pybullet_client.loadURDF(
|
||||
"%s/sphere_with_restitution.urdf" % self._urdf_root, self._ball_pos)
|
||||
return self._get_observation()
|
||||
|
||||
def _get_observation(self):
|
||||
world_translation_minitaur, world_rotation_minitaur = (
|
||||
self._pybullet_client.getBasePositionAndOrientation(
|
||||
self.minitaur.quadruped))
|
||||
self._pybullet_client.getBasePositionAndOrientation(self.minitaur.quadruped))
|
||||
world_translation_ball, world_rotation_ball = (
|
||||
self._pybullet_client.getBasePositionAndOrientation(self._ball_id))
|
||||
minitaur_translation_world, minitaur_rotation_world = (
|
||||
self._pybullet_client.invertTransform(world_translation_minitaur,
|
||||
world_rotation_minitaur))
|
||||
minitaur_translation_ball, _ = (
|
||||
self._pybullet_client.multiplyTransforms(minitaur_translation_world,
|
||||
minitaur_rotation_world,
|
||||
world_translation_ball,
|
||||
world_rotation_ball))
|
||||
distance = math.sqrt(minitaur_translation_ball[0]**2 +
|
||||
minitaur_translation_ball[1]**2)
|
||||
angle = math.atan2(minitaur_translation_ball[0],
|
||||
minitaur_translation_ball[1])
|
||||
minitaur_translation_world, minitaur_rotation_world = (self._pybullet_client.invertTransform(
|
||||
world_translation_minitaur, world_rotation_minitaur))
|
||||
minitaur_translation_ball, _ = (self._pybullet_client.multiplyTransforms(
|
||||
minitaur_translation_world, minitaur_rotation_world, world_translation_ball,
|
||||
world_rotation_ball))
|
||||
distance = math.sqrt(minitaur_translation_ball[0]**2 + minitaur_translation_ball[1]**2)
|
||||
angle = math.atan2(minitaur_translation_ball[0], minitaur_translation_ball[1])
|
||||
self._observation = [angle - math.pi / 2, distance]
|
||||
return self._observation
|
||||
|
||||
def _transform_action_to_motor_command(self, action):
|
||||
if self._leg_model_enabled:
|
||||
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))
|
||||
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))
|
||||
action = self._apply_steering_to_locomotion(action)
|
||||
action = self.minitaur.ConvertFromLegModel(action)
|
||||
return action
|
||||
@@ -126,15 +117,12 @@ class MinitaurBallGymEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
return action
|
||||
|
||||
def _distance_to_ball(self):
|
||||
world_translation_minitaur, _ = (
|
||||
self._pybullet_client.getBasePositionAndOrientation(
|
||||
self.minitaur.quadruped))
|
||||
world_translation_ball, _ = (
|
||||
self._pybullet_client.getBasePositionAndOrientation(
|
||||
self._ball_id))
|
||||
distance = math.sqrt(
|
||||
(world_translation_ball[0] - world_translation_minitaur[0])**2 +
|
||||
(world_translation_ball[1] - world_translation_minitaur[1])**2)
|
||||
world_translation_minitaur, _ = (self._pybullet_client.getBasePositionAndOrientation(
|
||||
self.minitaur.quadruped))
|
||||
world_translation_ball, _ = (self._pybullet_client.getBasePositionAndOrientation(
|
||||
self._ball_id))
|
||||
distance = math.sqrt((world_translation_ball[0] - world_translation_minitaur[0])**2 +
|
||||
(world_translation_ball[1] - world_translation_minitaur[1])**2)
|
||||
return distance
|
||||
|
||||
def _goal_state(self):
|
||||
|
||||
@@ -31,4 +31,4 @@ def main():
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
||||
main()
|
||||
|
||||
@@ -6,13 +6,13 @@ It is the result of first pass system identification for the derpy robot. The
|
||||
"""
|
||||
import math
|
||||
|
||||
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))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
import numpy as np
|
||||
from pybullet_envs.minitaur.envs import minitaur
|
||||
from pybullet_envs.minitaur.envs import minitaur
|
||||
|
||||
KNEE_CONSTRAINT_POINT_LONG = [0, 0.0055, 0.088]
|
||||
KNEE_CONSTRAINT_POINT_SHORT = [0, 0.0055, 0.100]
|
||||
@@ -46,13 +46,12 @@ class MinitaurDerpy(minitaur.Minitaur):
|
||||
"%s/quadruped/minitaur_derpy.urdf" % self._urdf_root,
|
||||
init_position,
|
||||
useFixedBase=self._on_rack,
|
||||
flags=(
|
||||
self._pybullet_client.URDF_USE_SELF_COLLISION_EXCLUDE_PARENT))
|
||||
flags=(self._pybullet_client.URDF_USE_SELF_COLLISION_EXCLUDE_PARENT))
|
||||
else:
|
||||
self.quadruped = self._pybullet_client.loadURDF(
|
||||
"%s/quadruped/minitaur_derpy.urdf" % self._urdf_root,
|
||||
init_position,
|
||||
useFixedBase=self._on_rack)
|
||||
self.quadruped = self._pybullet_client.loadURDF("%s/quadruped/minitaur_derpy.urdf" %
|
||||
self._urdf_root,
|
||||
init_position,
|
||||
useFixedBase=self._on_rack)
|
||||
self._BuildJointNameToIdDict()
|
||||
self._BuildUrdfIds()
|
||||
if self._remove_default_joint_damping:
|
||||
@@ -62,10 +61,9 @@ class MinitaurDerpy(minitaur.Minitaur):
|
||||
self._RecordInertiaInfoFromURDF()
|
||||
self.ResetPose(add_constraint=True)
|
||||
else:
|
||||
self._pybullet_client.resetBasePositionAndOrientation(
|
||||
self.quadruped, init_position, minitaur.INIT_ORIENTATION)
|
||||
self._pybullet_client.resetBaseVelocity(self.quadruped, [0, 0, 0],
|
||||
[0, 0, 0])
|
||||
self._pybullet_client.resetBasePositionAndOrientation(self.quadruped, init_position,
|
||||
minitaur.INIT_ORIENTATION)
|
||||
self._pybullet_client.resetBaseVelocity(self.quadruped, [0, 0, 0], [0, 0, 0])
|
||||
self.ResetPose(add_constraint=False)
|
||||
|
||||
self._overheat_counter = np.zeros(self.num_motors)
|
||||
@@ -103,68 +101,60 @@ class MinitaurDerpy(minitaur.Minitaur):
|
||||
knee_angle = -2.1834
|
||||
|
||||
leg_position = minitaur.LEG_POSITION[leg_id]
|
||||
self._pybullet_client.resetJointState(
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["motor_" + leg_position + "L_joint"],
|
||||
self._motor_direction[2 * leg_id] * half_pi,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position + "L_joint"],
|
||||
self._motor_direction[2 * leg_id] * knee_angle,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["motor_" + leg_position + "R_joint"],
|
||||
self._motor_direction[2 * leg_id + 1] * half_pi,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position + "R_joint"],
|
||||
self._motor_direction[2 * leg_id + 1] * knee_angle,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(self.quadruped,
|
||||
self._joint_name_to_id["motor_" + leg_position +
|
||||
"L_joint"],
|
||||
self._motor_direction[2 * leg_id] * half_pi,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position +
|
||||
"L_joint"],
|
||||
self._motor_direction[2 * leg_id] * knee_angle,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(self.quadruped,
|
||||
self._joint_name_to_id["motor_" + leg_position +
|
||||
"R_joint"],
|
||||
self._motor_direction[2 * leg_id + 1] * half_pi,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position +
|
||||
"R_joint"],
|
||||
self._motor_direction[2 * leg_id + 1] * knee_angle,
|
||||
targetVelocity=0)
|
||||
if add_constraint:
|
||||
if leg_id < 2:
|
||||
self._pybullet_client.createConstraint(
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position + "R_joint"],
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position + "L_joint"],
|
||||
self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0],
|
||||
KNEE_CONSTRAINT_POINT_SHORT, KNEE_CONSTRAINT_POINT_LONG)
|
||||
self.quadruped, self._joint_name_to_id["knee_" + leg_position + "R_joint"],
|
||||
self.quadruped, self._joint_name_to_id["knee_" + leg_position + "L_joint"],
|
||||
self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0], KNEE_CONSTRAINT_POINT_SHORT,
|
||||
KNEE_CONSTRAINT_POINT_LONG)
|
||||
else:
|
||||
self._pybullet_client.createConstraint(
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position + "R_joint"],
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position + "L_joint"],
|
||||
self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0],
|
||||
KNEE_CONSTRAINT_POINT_LONG, KNEE_CONSTRAINT_POINT_SHORT)
|
||||
self.quadruped, self._joint_name_to_id["knee_" + leg_position + "R_joint"],
|
||||
self.quadruped, self._joint_name_to_id["knee_" + leg_position + "L_joint"],
|
||||
self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0], KNEE_CONSTRAINT_POINT_LONG,
|
||||
KNEE_CONSTRAINT_POINT_SHORT)
|
||||
|
||||
if self._accurate_motor_model_enabled or self._pd_control_enabled:
|
||||
# Disable the default motor in pybullet.
|
||||
self._pybullet_client.setJointMotorControl2(
|
||||
bodyIndex=self.quadruped,
|
||||
jointIndex=(
|
||||
self._joint_name_to_id["motor_" + leg_position + "L_joint"]),
|
||||
jointIndex=(self._joint_name_to_id["motor_" + leg_position + "L_joint"]),
|
||||
controlMode=self._pybullet_client.VELOCITY_CONTROL,
|
||||
targetVelocity=0,
|
||||
force=knee_friction_force)
|
||||
self._pybullet_client.setJointMotorControl2(
|
||||
bodyIndex=self.quadruped,
|
||||
jointIndex=(
|
||||
self._joint_name_to_id["motor_" + leg_position + "R_joint"]),
|
||||
jointIndex=(self._joint_name_to_id["motor_" + leg_position + "R_joint"]),
|
||||
controlMode=self._pybullet_client.VELOCITY_CONTROL,
|
||||
targetVelocity=0,
|
||||
force=knee_friction_force)
|
||||
|
||||
else:
|
||||
self._SetDesiredMotorAngleByName(
|
||||
"motor_" + leg_position + "L_joint",
|
||||
self._motor_direction[2 * leg_id] * half_pi)
|
||||
self._SetDesiredMotorAngleByName(
|
||||
"motor_" + leg_position + "R_joint",
|
||||
self._motor_direction[2 * leg_id + 1] * half_pi)
|
||||
self._SetDesiredMotorAngleByName("motor_" + leg_position + "L_joint",
|
||||
self._motor_direction[2 * leg_id] * half_pi)
|
||||
self._SetDesiredMotorAngleByName("motor_" + leg_position + "R_joint",
|
||||
self._motor_direction[2 * leg_id + 1] * half_pi)
|
||||
|
||||
self._pybullet_client.setJointMotorControl2(
|
||||
bodyIndex=self.quadruped,
|
||||
|
||||
@@ -32,10 +32,7 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
action to zero and the height of the robot base. It prefers a similar pose to
|
||||
the signal while keeping balance.
|
||||
"""
|
||||
metadata = {
|
||||
"render.modes": ["human", "rgb_array"],
|
||||
"video.frames_per_second": 166
|
||||
}
|
||||
metadata = {"render.modes": ["human", "rgb_array"], "video.frames_per_second": 166}
|
||||
|
||||
def __init__(self,
|
||||
urdf_version=None,
|
||||
@@ -101,23 +98,23 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
self._extension_offset = np.zeros(NUM_LEGS)
|
||||
self._use_angular_velocity_in_observation = use_motor_angle_in_observation
|
||||
self._use_motor_angle_in_observation = use_motor_angle_in_observation
|
||||
super(MinitaurFourLegStandEnv, self).__init__(
|
||||
urdf_version=urdf_version,
|
||||
control_time_step=control_time_step,
|
||||
action_repeat=action_repeat,
|
||||
remove_default_joint_damping=remove_default_joint_damping,
|
||||
accurate_motor_model_enabled=True,
|
||||
motor_overheat_protection=True,
|
||||
hard_reset=hard_reset,
|
||||
motor_kp=motor_kp,
|
||||
motor_kd=motor_kd,
|
||||
control_latency=control_latency,
|
||||
pd_latency=pd_latency,
|
||||
on_rack=on_rack,
|
||||
render=render,
|
||||
env_randomizer=env_randomizer,
|
||||
reflection = False,
|
||||
log_path=log_path)
|
||||
super(MinitaurFourLegStandEnv,
|
||||
self).__init__(urdf_version=urdf_version,
|
||||
control_time_step=control_time_step,
|
||||
action_repeat=action_repeat,
|
||||
remove_default_joint_damping=remove_default_joint_damping,
|
||||
accurate_motor_model_enabled=True,
|
||||
motor_overheat_protection=True,
|
||||
hard_reset=hard_reset,
|
||||
motor_kp=motor_kp,
|
||||
motor_kd=motor_kd,
|
||||
control_latency=control_latency,
|
||||
pd_latency=pd_latency,
|
||||
on_rack=on_rack,
|
||||
render=render,
|
||||
env_randomizer=env_randomizer,
|
||||
reflection=False,
|
||||
log_path=log_path)
|
||||
|
||||
action_dim = 4
|
||||
action_low = np.array([-1.0] * action_dim)
|
||||
@@ -138,20 +135,17 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
# [swing leg 1, swing leg 2, swing leg 3, swing leg 4,
|
||||
# extension leg 1, extension leg 2, extension leg 3, extension leg 4]
|
||||
init_pose = [
|
||||
INIT_SWING_POS + self._swing_offset[0],
|
||||
INIT_SWING_POS + self._swing_offset[1],
|
||||
INIT_SWING_POS + self._swing_offset[2],
|
||||
INIT_SWING_POS + self._swing_offset[3],
|
||||
INIT_SWING_POS + self._swing_offset[0], INIT_SWING_POS + self._swing_offset[1],
|
||||
INIT_SWING_POS + self._swing_offset[2], INIT_SWING_POS + self._swing_offset[3],
|
||||
INIT_EXTENSION_POS + self._extension_offset[0],
|
||||
INIT_EXTENSION_POS + self._extension_offset[1],
|
||||
INIT_EXTENSION_POS + self._extension_offset[2],
|
||||
INIT_EXTENSION_POS + self._extension_offset[3]
|
||||
]
|
||||
initial_motor_angles = self._convert_from_leg_model(init_pose)
|
||||
self._pybullet_client.resetBasePositionAndOrientation(
|
||||
0, [0, 0, 0], [0, 0, 0, 1])
|
||||
super(MinitaurFourLegStandEnv, self).reset(
|
||||
initial_motor_angles=initial_motor_angles, reset_duration=0.5)
|
||||
self._pybullet_client.resetBasePositionAndOrientation(0, [0, 0, 0], [0, 0, 0, 1])
|
||||
super(MinitaurFourLegStandEnv, self).reset(initial_motor_angles=initial_motor_angles,
|
||||
reset_duration=0.5)
|
||||
return self._get_observation()
|
||||
|
||||
def step(self, action):
|
||||
@@ -180,10 +174,8 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
time.sleep(time_to_sleep)
|
||||
base_pos = self.minitaur.GetBasePosition()
|
||||
# Keep the previous orientation of the camera set by the user.
|
||||
[yaw, pitch,
|
||||
dist] = self._pybullet_client.getDebugVisualizerCamera()[8:11]
|
||||
self._pybullet_client.resetDebugVisualizerCamera(dist, yaw, pitch,
|
||||
base_pos)
|
||||
[yaw, pitch, dist] = self._pybullet_client.getDebugVisualizerCamera()[8:11]
|
||||
self._pybullet_client.resetDebugVisualizerCamera(dist, yaw, pitch, base_pos)
|
||||
action = self._transform_action_to_motor_command(action)
|
||||
t = self._env_step_counter % MOVING_FLOOR_TOTAL_STEP
|
||||
if t == 0:
|
||||
@@ -197,8 +189,8 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
t = float(float(t) / float(MOVING_FLOOR_TOTAL_STEP))
|
||||
ori = map(operator.add, [x * (1.0 - t) for x in self._cur_ori],
|
||||
[x * t for x in self._goal_ori])
|
||||
ori=list(ori)
|
||||
print("ori=",ori)
|
||||
ori = list(ori)
|
||||
print("ori=", ori)
|
||||
self._pybullet_client.resetBasePositionAndOrientation(0, [0, 0, 0], ori)
|
||||
if self._env_step_counter % PERTURBATION_TOTAL_STEP == 0:
|
||||
self._perturbation_magnitude = random.uniform(0.0, 0.0)
|
||||
@@ -218,8 +210,8 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
obs = self._get_true_observation()
|
||||
reward = self._reward()
|
||||
if self._log_path is not None:
|
||||
minitaur_logging.update_episode_proto(self._episode_proto, self.minitaur,
|
||||
action, self._env_step_counter)
|
||||
minitaur_logging.update_episode_proto(self._episode_proto, self.minitaur, action,
|
||||
self._env_step_counter)
|
||||
if done:
|
||||
self.minitaur.Terminate()
|
||||
return np.array(self._get_observation()), reward, done, {}
|
||||
@@ -228,15 +220,13 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
motor_pose = np.zeros(NUM_MOTORS)
|
||||
for i in range(NUM_LEGS):
|
||||
motor_pose[2 * i] = leg_pose[NUM_LEGS + i] - (-1)**(i / 2) * leg_pose[i]
|
||||
motor_pose[2 * i
|
||||
+ 1] = leg_pose[NUM_LEGS + i] + (-1)**(i / 2) * leg_pose[i]
|
||||
motor_pose[2 * i + 1] = leg_pose[NUM_LEGS + i] + (-1)**(i / 2) * leg_pose[i]
|
||||
return motor_pose
|
||||
|
||||
def _signal(self, t):
|
||||
initial_pose = np.array([
|
||||
INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS,
|
||||
INIT_EXTENSION_POS, INIT_EXTENSION_POS, INIT_EXTENSION_POS,
|
||||
INIT_EXTENSION_POS
|
||||
INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS, INIT_EXTENSION_POS,
|
||||
INIT_EXTENSION_POS, INIT_EXTENSION_POS, INIT_EXTENSION_POS
|
||||
])
|
||||
signal = initial_pose
|
||||
return signal
|
||||
@@ -268,8 +258,7 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
rot_mat = self._pybullet_client.getMatrixFromQuaternion(orientation)
|
||||
local_up = rot_mat[6:]
|
||||
_, _, height = self.minitaur.GetBasePosition()
|
||||
local_global_up_dot_product = np.dot(
|
||||
np.asarray([0, 0, 1]), np.asarray(local_up))
|
||||
local_global_up_dot_product = np.dot(np.asarray([0, 0, 1]), np.asarray(local_up))
|
||||
return local_global_up_dot_product < 0.85 or height < 0.15
|
||||
|
||||
def _reward(self):
|
||||
|
||||
@@ -5,7 +5,6 @@ import numpy as np
|
||||
import tensorflow as tf
|
||||
from pybullet_envs.minitaur.envs import minitaur_four_leg_stand_env
|
||||
|
||||
|
||||
FLAGS = tf.flags.FLAGS
|
||||
tf.flags.DEFINE_string("log_path", None, "The directory to write the log file.")
|
||||
NUM_LEGS = 4
|
||||
|
||||
@@ -4,10 +4,10 @@
|
||||
import math
|
||||
import time
|
||||
|
||||
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))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
import gym
|
||||
from gym import spaces
|
||||
@@ -64,10 +64,7 @@ class MinitaurGymEnv(gym.Env):
|
||||
expenditure.
|
||||
|
||||
"""
|
||||
metadata = {
|
||||
"render.modes": ["human", "rgb_array"],
|
||||
"video.frames_per_second": 100
|
||||
}
|
||||
metadata = {"render.modes": ["human", "rgb_array"], "video.frames_per_second": 100}
|
||||
|
||||
def __init__(self,
|
||||
urdf_root=pybullet_data.getDataPath(),
|
||||
@@ -184,17 +181,14 @@ class MinitaurGymEnv(gym.Env):
|
||||
self._action_repeat = 1
|
||||
self.control_time_step = self._time_step * self._action_repeat
|
||||
# TODO(b/73829334): Fix the value of self._num_bullet_solver_iterations.
|
||||
self._num_bullet_solver_iterations = int(
|
||||
NUM_SIMULATION_ITERATION_STEPS / self._action_repeat)
|
||||
self._num_bullet_solver_iterations = int(NUM_SIMULATION_ITERATION_STEPS / self._action_repeat)
|
||||
self._urdf_root = urdf_root
|
||||
self._self_collision_enabled = self_collision_enabled
|
||||
self._motor_velocity_limit = motor_velocity_limit
|
||||
self._observation = []
|
||||
self._true_observation = []
|
||||
self._objectives = []
|
||||
self._objective_weights = [
|
||||
distance_weight, energy_weight, drift_weight, shake_weight
|
||||
]
|
||||
self._objective_weights = [distance_weight, energy_weight, drift_weight, shake_weight]
|
||||
self._env_step_counter = 0
|
||||
self._num_steps_to_log = num_steps_to_log
|
||||
self._is_render = render
|
||||
@@ -226,12 +220,10 @@ class MinitaurGymEnv(gym.Env):
|
||||
self._urdf_version = urdf_version
|
||||
self._ground_id = None
|
||||
self._reflection = reflection
|
||||
self._env_randomizers = convert_to_list(
|
||||
env_randomizer) if env_randomizer else []
|
||||
self._env_randomizers = convert_to_list(env_randomizer) if env_randomizer else []
|
||||
self._episode_proto = minitaur_logging_pb2.MinitaurEpisode()
|
||||
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()
|
||||
if self._urdf_version is None:
|
||||
@@ -249,7 +241,7 @@ class MinitaurGymEnv(gym.Env):
|
||||
self._hard_reset = hard_reset # This assignment need to be after reset()
|
||||
|
||||
def close(self):
|
||||
if self._env_step_counter>0:
|
||||
if self._env_step_counter > 0:
|
||||
self.logging.save_episode(self._episode_proto)
|
||||
self.minitaur.Terminate()
|
||||
|
||||
@@ -257,53 +249,48 @@ class MinitaurGymEnv(gym.Env):
|
||||
self._env_randomizers.append(env_randomizer)
|
||||
|
||||
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._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)
|
||||
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)
|
||||
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.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)
|
||||
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)
|
||||
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:
|
||||
@@ -313,10 +300,9 @@ class MinitaurGymEnv(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.configureDebugVisualizer(
|
||||
self._pybullet_client.COV_ENABLE_RENDERING, 1)
|
||||
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 seed(self, seed=None):
|
||||
@@ -328,8 +314,7 @@ class MinitaurGymEnv(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
|
||||
|
||||
@@ -361,10 +346,8 @@ class MinitaurGymEnv(gym.Env):
|
||||
time.sleep(time_to_sleep)
|
||||
base_pos = self.minitaur.GetBasePosition()
|
||||
# Keep the previous orientation of the camera set by the user.
|
||||
[yaw, pitch,
|
||||
dist] = self._pybullet_client.getDebugVisualizerCamera()[8:11]
|
||||
self._pybullet_client.resetDebugVisualizerCamera(dist, yaw, pitch,
|
||||
base_pos)
|
||||
[yaw, pitch, dist] = self._pybullet_client.getDebugVisualizerCamera()[8:11]
|
||||
self._pybullet_client.resetDebugVisualizerCamera(dist, yaw, pitch, base_pos)
|
||||
|
||||
for env_randomizer in self._env_randomizers:
|
||||
env_randomizer.randomize_step(self)
|
||||
@@ -374,8 +357,8 @@ class MinitaurGymEnv(gym.Env):
|
||||
reward = self._reward()
|
||||
done = self._termination()
|
||||
if self._log_path is not None:
|
||||
minitaur_logging.update_episode_proto(self._episode_proto, self.minitaur,
|
||||
action, self._env_step_counter)
|
||||
minitaur_logging.update_episode_proto(self._episode_proto, self.minitaur, action,
|
||||
self._env_step_counter)
|
||||
self._env_step_counter += 1
|
||||
if done:
|
||||
self.minitaur.Terminate()
|
||||
@@ -392,11 +375,11 @@ class MinitaurGymEnv(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)
|
||||
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,
|
||||
@@ -413,9 +396,8 @@ class MinitaurGymEnv(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.
|
||||
@@ -424,8 +406,8 @@ class MinitaurGymEnv(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.
|
||||
@@ -434,8 +416,8 @@ class MinitaurGymEnv(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.
|
||||
@@ -459,8 +441,7 @@ class MinitaurGymEnv(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()
|
||||
@@ -483,9 +464,7 @@ class MinitaurGymEnv(gym.Env):
|
||||
np.dot(self.minitaur.GetMotorTorques(),
|
||||
self.minitaur.GetMotorVelocities())) * self._time_step
|
||||
objectives = [forward_reward, energy_reward, drift_reward, shake_reward]
|
||||
weighted_objectives = [
|
||||
o * w for o, w in zip(objectives, self._objective_weights)
|
||||
]
|
||||
weighted_objectives = [o * w for o, w in zip(objectives, self._objective_weights)]
|
||||
reward = sum(weighted_objectives)
|
||||
self._objectives.append(objectives)
|
||||
return reward
|
||||
@@ -552,10 +531,8 @@ class MinitaurGymEnv(gym.Env):
|
||||
upper_bound = np.zeros(self._get_observation_dimension())
|
||||
num_motors = self.minitaur.num_motors
|
||||
upper_bound[0:num_motors] = math.pi # Joint angle.
|
||||
upper_bound[num_motors:2 * num_motors] = (
|
||||
motor.MOTOR_SPEED_LIMIT) # Joint velocity.
|
||||
upper_bound[2 * num_motors:3 * num_motors] = (
|
||||
motor.OBSERVED_TORQUE_LIMIT) # Joint torque.
|
||||
upper_bound[num_motors:2 * num_motors] = (motor.MOTOR_SPEED_LIMIT) # Joint velocity.
|
||||
upper_bound[2 * num_motors:3 * num_motors] = (motor.OBSERVED_TORQUE_LIMIT) # Joint torque.
|
||||
upper_bound[3 * num_motors:] = 1.0 # Quaternion of base orientation.
|
||||
return upper_bound
|
||||
|
||||
@@ -577,7 +554,6 @@ class MinitaurGymEnv(gym.Env):
|
||||
_seed = seed
|
||||
_step = step
|
||||
|
||||
|
||||
def set_time_step(self, control_step, simulation_step=0.001):
|
||||
"""Sets the time step of the environment.
|
||||
|
||||
@@ -591,18 +567,15 @@ class MinitaurGymEnv(gym.Env):
|
||||
ValueError: If the control step is smaller than the simulation step.
|
||||
"""
|
||||
if control_step < simulation_step:
|
||||
raise ValueError(
|
||||
"Control step should be larger than or equal to simulation step.")
|
||||
raise ValueError("Control step should be larger than or equal to simulation step.")
|
||||
self.control_time_step = control_step
|
||||
self._time_step = simulation_step
|
||||
self._action_repeat = int(round(control_step / simulation_step))
|
||||
self._num_bullet_solver_iterations = (
|
||||
NUM_SIMULATION_ITERATION_STEPS / self._action_repeat)
|
||||
self._num_bullet_solver_iterations = (NUM_SIMULATION_ITERATION_STEPS / self._action_repeat)
|
||||
self._pybullet_client.setPhysicsEngineParameter(
|
||||
numSolverIterations=self._num_bullet_solver_iterations)
|
||||
self._pybullet_client.setTimeStep(self._time_step)
|
||||
self.minitaur.SetTimeSteps(
|
||||
action_repeat=self._action_repeat, simulation_step=self._time_step)
|
||||
self.minitaur.SetTimeSteps(action_repeat=self._action_repeat, simulation_step=self._time_step)
|
||||
|
||||
@property
|
||||
def pybullet_client(self):
|
||||
|
||||
@@ -8,8 +8,8 @@ import os
|
||||
import inspect
|
||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
parentdir = os.path.dirname(os.path.dirname(os.path.dirname(currentdir)))
|
||||
print("parentdir=",parentdir)
|
||||
os.sys.path.insert(0,parentdir)
|
||||
print("parentdir=", parentdir)
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
import argparse
|
||||
import numpy as np
|
||||
@@ -17,7 +17,6 @@ import tensorflow as tf
|
||||
from pybullet_envs.minitaur.envs import minitaur_gym_env
|
||||
import time
|
||||
|
||||
|
||||
#FLAGS = flags.FLAGS
|
||||
#flags.DEFINE_enum(
|
||||
# "example_name", "sine", ["sine", "reset", "stand", "overheat"],
|
||||
@@ -60,7 +59,7 @@ def ResetPoseExample(log_path=None):
|
||||
action = [math.pi / 2] * 8
|
||||
for _ in range(steps):
|
||||
_, _, done, _ = environment.step(action)
|
||||
time.sleep(1./100.)
|
||||
time.sleep(1. / 100.)
|
||||
if done:
|
||||
break
|
||||
|
||||
@@ -104,7 +103,7 @@ def MotorOverheatExample(log_path=None):
|
||||
observation, _, _, _ = environment.step(action)
|
||||
current_row.extend(observation.tolist())
|
||||
actions_and_observations.append(current_row)
|
||||
time.sleep(1./100.)
|
||||
time.sleep(1. / 100.)
|
||||
|
||||
if FLAGS.output_filename is not None:
|
||||
WriteToCSV(FLAGS.output_filename, actions_and_observations)
|
||||
@@ -151,7 +150,7 @@ def SineStandExample(log_path=None):
|
||||
observation, _, _, _ = environment.step(action)
|
||||
current_row.extend(observation.tolist())
|
||||
actions_and_observations.append(current_row)
|
||||
time.sleep(1./100.)
|
||||
time.sleep(1. / 100.)
|
||||
|
||||
if FLAGS.output_filename is not None:
|
||||
WriteToCSV(FLAGS.output_filename, actions_and_observations)
|
||||
@@ -199,7 +198,7 @@ def SinePolicyExample(log_path=None):
|
||||
a4 = math.sin(t * speed + math.pi) * amplitude2
|
||||
action = [a1, a2, a2, a1, a3, a4, a4, a3]
|
||||
_, reward, done, _ = environment.step(action)
|
||||
time.sleep(1./100.)
|
||||
time.sleep(1. / 100.)
|
||||
|
||||
sum_reward += reward
|
||||
if done:
|
||||
@@ -207,14 +206,15 @@ def SinePolicyExample(log_path=None):
|
||||
environment.reset()
|
||||
|
||||
|
||||
|
||||
|
||||
def main():
|
||||
parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
|
||||
parser.add_argument('--env', help='environment ID (0==sine, 1==stand, 2=reset, 3=overheat)',type=int, default=0)
|
||||
parser.add_argument('--env',
|
||||
help='environment ID (0==sine, 1==stand, 2=reset, 3=overheat)',
|
||||
type=int,
|
||||
default=0)
|
||||
args = parser.parse_args()
|
||||
print("--env=" + str(args.env))
|
||||
|
||||
|
||||
if (args.env == 0):
|
||||
SinePolicyExample()
|
||||
if (args.env == 1):
|
||||
@@ -224,6 +224,6 @@ def main():
|
||||
if (args.env == 3):
|
||||
MotorOverheatExample()
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
||||
|
||||
@@ -10,10 +10,10 @@ 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))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
import datetime
|
||||
import os
|
||||
@@ -74,9 +74,8 @@ def update_episode_proto(episode_proto, minitaur, action, step):
|
||||
"""
|
||||
max_num_steps = len(episode_proto.state_action)
|
||||
if step >= max_num_steps:
|
||||
tf.logging.warning(
|
||||
"{}th step is not recorded in the logging since only {} steps were "
|
||||
"pre-allocated.".format(step, max_num_steps))
|
||||
tf.logging.warning("{}th step is not recorded in the logging since only {} steps were "
|
||||
"pre-allocated.".format(step, max_num_steps))
|
||||
return
|
||||
step_log = episode_proto.state_action[step]
|
||||
step_log.info_valid = minitaur.IsObservationValid()
|
||||
@@ -95,8 +94,7 @@ def update_episode_proto(episode_proto, minitaur, action, step):
|
||||
|
||||
_update_base_state(step_log.base_position, minitaur.GetBasePosition())
|
||||
_update_base_state(step_log.base_orientation, minitaur.GetBaseRollPitchYaw())
|
||||
_update_base_state(step_log.base_angular_vel,
|
||||
minitaur.GetBaseRollPitchYawRate())
|
||||
_update_base_state(step_log.base_angular_vel, minitaur.GetBaseRollPitchYawRate())
|
||||
|
||||
|
||||
class MinitaurLogging(object):
|
||||
@@ -124,10 +122,8 @@ class MinitaurLogging(object):
|
||||
if not tf.gfile.Exists(self._log_path):
|
||||
tf.gfile.MakeDirs(self._log_path)
|
||||
ts = time.time()
|
||||
time_stamp = datetime.datetime.fromtimestamp(ts).strftime(
|
||||
"%Y-%m-%d-%H%M%S")
|
||||
log_path = os.path.join(self._log_path,
|
||||
"minitaur_log_{}".format(time_stamp))
|
||||
time_stamp = datetime.datetime.fromtimestamp(ts).strftime("%Y-%m-%d-%H%M%S")
|
||||
log_path = os.path.join(self._log_path, "minitaur_log_{}".format(time_stamp))
|
||||
with tf.gfile.Open(log_path, "w") as f:
|
||||
f.write(episode_proto.SerializeToString())
|
||||
return log_path
|
||||
|
||||
@@ -3,12 +3,12 @@
|
||||
|
||||
import sys
|
||||
|
||||
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))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))
|
||||
_b = sys.version_info[0] < 3 and (lambda x: x) or (lambda x: x.encode('latin1'))
|
||||
from google.protobuf import descriptor as _descriptor
|
||||
from google.protobuf import message as _message
|
||||
from google.protobuf import reflection as _reflection
|
||||
@@ -18,168 +18,271 @@ from google.protobuf import descriptor_pb2
|
||||
|
||||
_sym_db = _symbol_database.Default()
|
||||
|
||||
|
||||
from pybullet_envs.minitaur.envs import timestamp_pb2 as timestamp__pb2
|
||||
from pybullet_envs.minitaur.envs import vector_pb2 as vector__pb2
|
||||
|
||||
|
||||
DESCRIPTOR = _descriptor.FileDescriptor(
|
||||
name='minitaur_logging.proto',
|
||||
package='robotics.reinforcement_learning.minitaur.envs',
|
||||
syntax='proto3',
|
||||
serialized_pb=_b('\n\x16minitaur_logging.proto\x12-robotics.reinforcement_learning.minitaur.envs\x1a\x0ftimestamp.proto\x1a\x0cvector.proto\"k\n\x0fMinitaurEpisode\x12X\n\x0cstate_action\x18\x01 \x03(\x0b\x32\x42.robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction\"U\n\x12MinitaurMotorState\x12\r\n\x05\x61ngle\x18\x01 \x01(\x01\x12\x10\n\x08velocity\x18\x02 \x01(\x01\x12\x0e\n\x06torque\x18\x03 \x01(\x01\x12\x0e\n\x06\x61\x63tion\x18\x04 \x01(\x01\"\xce\x02\n\x13MinitaurStateAction\x12\x12\n\ninfo_valid\x18\x06 \x01(\x08\x12(\n\x04time\x18\x01 \x01(\x0b\x32\x1a.google.protobuf.Timestamp\x12\x32\n\rbase_position\x18\x02 \x01(\x0b\x32\x1b.robotics.messages.Vector3d\x12\x35\n\x10\x62\x61se_orientation\x18\x03 \x01(\x0b\x32\x1b.robotics.messages.Vector3d\x12\x35\n\x10\x62\x61se_angular_vel\x18\x04 \x01(\x0b\x32\x1b.robotics.messages.Vector3d\x12W\n\x0cmotor_states\x18\x05 \x03(\x0b\x32\x41.robotics.reinforcement_learning.minitaur.envs.MinitaurMotorStateb\x06proto3')
|
||||
,
|
||||
dependencies=[timestamp__pb2.DESCRIPTOR,vector__pb2.DESCRIPTOR,])
|
||||
|
||||
|
||||
|
||||
name='minitaur_logging.proto',
|
||||
package='robotics.reinforcement_learning.minitaur.envs',
|
||||
syntax='proto3',
|
||||
serialized_pb=_b(
|
||||
'\n\x16minitaur_logging.proto\x12-robotics.reinforcement_learning.minitaur.envs\x1a\x0ftimestamp.proto\x1a\x0cvector.proto\"k\n\x0fMinitaurEpisode\x12X\n\x0cstate_action\x18\x01 \x03(\x0b\x32\x42.robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction\"U\n\x12MinitaurMotorState\x12\r\n\x05\x61ngle\x18\x01 \x01(\x01\x12\x10\n\x08velocity\x18\x02 \x01(\x01\x12\x0e\n\x06torque\x18\x03 \x01(\x01\x12\x0e\n\x06\x61\x63tion\x18\x04 \x01(\x01\"\xce\x02\n\x13MinitaurStateAction\x12\x12\n\ninfo_valid\x18\x06 \x01(\x08\x12(\n\x04time\x18\x01 \x01(\x0b\x32\x1a.google.protobuf.Timestamp\x12\x32\n\rbase_position\x18\x02 \x01(\x0b\x32\x1b.robotics.messages.Vector3d\x12\x35\n\x10\x62\x61se_orientation\x18\x03 \x01(\x0b\x32\x1b.robotics.messages.Vector3d\x12\x35\n\x10\x62\x61se_angular_vel\x18\x04 \x01(\x0b\x32\x1b.robotics.messages.Vector3d\x12W\n\x0cmotor_states\x18\x05 \x03(\x0b\x32\x41.robotics.reinforcement_learning.minitaur.envs.MinitaurMotorStateb\x06proto3'
|
||||
),
|
||||
dependencies=[
|
||||
timestamp__pb2.DESCRIPTOR,
|
||||
vector__pb2.DESCRIPTOR,
|
||||
])
|
||||
|
||||
_MINITAUREPISODE = _descriptor.Descriptor(
|
||||
name='MinitaurEpisode',
|
||||
full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurEpisode',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(
|
||||
name='state_action', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurEpisode.state_action', index=0,
|
||||
number=1, type=11, cpp_type=10, label=3,
|
||||
has_default_value=False, default_value=[],
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[
|
||||
],
|
||||
nested_types=[],
|
||||
enum_types=[
|
||||
],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=104,
|
||||
serialized_end=211,
|
||||
name='MinitaurEpisode',
|
||||
full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurEpisode',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(
|
||||
name='state_action',
|
||||
full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurEpisode.state_action',
|
||||
index=0,
|
||||
number=1,
|
||||
type=11,
|
||||
cpp_type=10,
|
||||
label=3,
|
||||
has_default_value=False,
|
||||
default_value=[],
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[],
|
||||
nested_types=[],
|
||||
enum_types=[],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[],
|
||||
serialized_start=104,
|
||||
serialized_end=211,
|
||||
)
|
||||
|
||||
|
||||
_MINITAURMOTORSTATE = _descriptor.Descriptor(
|
||||
name='MinitaurMotorState',
|
||||
full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(
|
||||
name='angle', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState.angle', index=0,
|
||||
number=1, type=1, cpp_type=5, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='velocity', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState.velocity', index=1,
|
||||
number=2, type=1, cpp_type=5, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='torque', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState.torque', index=2,
|
||||
number=3, type=1, cpp_type=5, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='action', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState.action', index=3,
|
||||
number=4, type=1, cpp_type=5, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[
|
||||
],
|
||||
nested_types=[],
|
||||
enum_types=[
|
||||
],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=213,
|
||||
serialized_end=298,
|
||||
name='MinitaurMotorState',
|
||||
full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(
|
||||
name='angle',
|
||||
full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState.angle',
|
||||
index=0,
|
||||
number=1,
|
||||
type=1,
|
||||
cpp_type=5,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='velocity',
|
||||
full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState.velocity',
|
||||
index=1,
|
||||
number=2,
|
||||
type=1,
|
||||
cpp_type=5,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='torque',
|
||||
full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState.torque',
|
||||
index=2,
|
||||
number=3,
|
||||
type=1,
|
||||
cpp_type=5,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='action',
|
||||
full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState.action',
|
||||
index=3,
|
||||
number=4,
|
||||
type=1,
|
||||
cpp_type=5,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[],
|
||||
nested_types=[],
|
||||
enum_types=[],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[],
|
||||
serialized_start=213,
|
||||
serialized_end=298,
|
||||
)
|
||||
|
||||
|
||||
_MINITAURSTATEACTION = _descriptor.Descriptor(
|
||||
name='MinitaurStateAction',
|
||||
full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(
|
||||
name='info_valid', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.info_valid', index=0,
|
||||
number=6, type=8, cpp_type=7, label=1,
|
||||
has_default_value=False, default_value=False,
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='time', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.time', index=1,
|
||||
number=1, type=11, cpp_type=10, label=1,
|
||||
has_default_value=False, default_value=None,
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='base_position', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.base_position', index=2,
|
||||
number=2, type=11, cpp_type=10, label=1,
|
||||
has_default_value=False, default_value=None,
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='base_orientation', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.base_orientation', index=3,
|
||||
number=3, type=11, cpp_type=10, label=1,
|
||||
has_default_value=False, default_value=None,
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='base_angular_vel', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.base_angular_vel', index=4,
|
||||
number=4, type=11, cpp_type=10, label=1,
|
||||
has_default_value=False, default_value=None,
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='motor_states', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.motor_states', index=5,
|
||||
number=5, type=11, cpp_type=10, label=3,
|
||||
has_default_value=False, default_value=[],
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[
|
||||
],
|
||||
nested_types=[],
|
||||
enum_types=[
|
||||
],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=301,
|
||||
serialized_end=635,
|
||||
name='MinitaurStateAction',
|
||||
full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(
|
||||
name='info_valid',
|
||||
full_name=
|
||||
'robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.info_valid',
|
||||
index=0,
|
||||
number=6,
|
||||
type=8,
|
||||
cpp_type=7,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=False,
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='time',
|
||||
full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.time',
|
||||
index=1,
|
||||
number=1,
|
||||
type=11,
|
||||
cpp_type=10,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=None,
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='base_position',
|
||||
full_name=
|
||||
'robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.base_position',
|
||||
index=2,
|
||||
number=2,
|
||||
type=11,
|
||||
cpp_type=10,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=None,
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='base_orientation',
|
||||
full_name=
|
||||
'robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.base_orientation',
|
||||
index=3,
|
||||
number=3,
|
||||
type=11,
|
||||
cpp_type=10,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=None,
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='base_angular_vel',
|
||||
full_name=
|
||||
'robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.base_angular_vel',
|
||||
index=4,
|
||||
number=4,
|
||||
type=11,
|
||||
cpp_type=10,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=None,
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='motor_states',
|
||||
full_name=
|
||||
'robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.motor_states',
|
||||
index=5,
|
||||
number=5,
|
||||
type=11,
|
||||
cpp_type=10,
|
||||
label=3,
|
||||
has_default_value=False,
|
||||
default_value=[],
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[],
|
||||
nested_types=[],
|
||||
enum_types=[],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[],
|
||||
serialized_start=301,
|
||||
serialized_end=635,
|
||||
)
|
||||
|
||||
_MINITAUREPISODE.fields_by_name['state_action'].message_type = _MINITAURSTATEACTION
|
||||
@@ -193,26 +296,34 @@ DESCRIPTOR.message_types_by_name['MinitaurMotorState'] = _MINITAURMOTORSTATE
|
||||
DESCRIPTOR.message_types_by_name['MinitaurStateAction'] = _MINITAURSTATEACTION
|
||||
_sym_db.RegisterFileDescriptor(DESCRIPTOR)
|
||||
|
||||
MinitaurEpisode = _reflection.GeneratedProtocolMessageType('MinitaurEpisode', (_message.Message,), dict(
|
||||
DESCRIPTOR = _MINITAUREPISODE,
|
||||
__module__ = 'minitaur_logging_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.reinforcement_learning.minitaur.envs.MinitaurEpisode)
|
||||
))
|
||||
MinitaurEpisode = _reflection.GeneratedProtocolMessageType(
|
||||
'MinitaurEpisode',
|
||||
(_message.Message,),
|
||||
dict(
|
||||
DESCRIPTOR=_MINITAUREPISODE,
|
||||
__module__='minitaur_logging_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.reinforcement_learning.minitaur.envs.MinitaurEpisode)
|
||||
))
|
||||
_sym_db.RegisterMessage(MinitaurEpisode)
|
||||
|
||||
MinitaurMotorState = _reflection.GeneratedProtocolMessageType('MinitaurMotorState', (_message.Message,), dict(
|
||||
DESCRIPTOR = _MINITAURMOTORSTATE,
|
||||
__module__ = 'minitaur_logging_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState)
|
||||
))
|
||||
MinitaurMotorState = _reflection.GeneratedProtocolMessageType(
|
||||
'MinitaurMotorState',
|
||||
(_message.Message,),
|
||||
dict(
|
||||
DESCRIPTOR=_MINITAURMOTORSTATE,
|
||||
__module__='minitaur_logging_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState)
|
||||
))
|
||||
_sym_db.RegisterMessage(MinitaurMotorState)
|
||||
|
||||
MinitaurStateAction = _reflection.GeneratedProtocolMessageType('MinitaurStateAction', (_message.Message,), dict(
|
||||
DESCRIPTOR = _MINITAURSTATEACTION,
|
||||
__module__ = 'minitaur_logging_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction)
|
||||
))
|
||||
MinitaurStateAction = _reflection.GeneratedProtocolMessageType(
|
||||
'MinitaurStateAction',
|
||||
(_message.Message,),
|
||||
dict(
|
||||
DESCRIPTOR=_MINITAURSTATEACTION,
|
||||
__module__='minitaur_logging_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction)
|
||||
))
|
||||
_sym_db.RegisterMessage(MinitaurStateAction)
|
||||
|
||||
|
||||
# @@protoc_insertion_point(module_scope)
|
||||
|
||||
@@ -15,13 +15,13 @@ fields = episode.ListFields()
|
||||
recs = []
|
||||
|
||||
for rec in fields[0][1]:
|
||||
#print(rec.time)
|
||||
for motorState in rec.motor_states:
|
||||
#print("motorState.angle=",motorState.angle)
|
||||
#print("motorState.velocity=",motorState.velocity)
|
||||
#print("motorState.action=",motorState.action)
|
||||
#print("motorState.torque=",motorState.torque)
|
||||
recs.append([motorState.angle,motorState.velocity,motorState.action,motorState.torque])
|
||||
|
||||
#print(rec.time)
|
||||
for motorState in rec.motor_states:
|
||||
#print("motorState.angle=",motorState.angle)
|
||||
#print("motorState.velocity=",motorState.velocity)
|
||||
#print("motorState.action=",motorState.action)
|
||||
#print("motorState.torque=",motorState.torque)
|
||||
recs.append([motorState.angle, motorState.velocity, motorState.action, motorState.torque])
|
||||
|
||||
a = numpy.array(recs)
|
||||
numpy.savetxt("motorq_qdot_action_torque.csv", a, delimiter=",")
|
||||
numpy.savetxt("motorq_qdot_action_torque.csv", a, delimiter=",")
|
||||
|
||||
@@ -17,8 +17,8 @@ DIAGONAL_LEG_PAIR_2 = (1, 2)
|
||||
|
||||
class BehaviorParameters(
|
||||
collections.namedtuple("BehaviorParameters", [
|
||||
"stance_duration", "desired_forward_speed", "turning_speed",
|
||||
"standing_height", "desired_incline_angle"
|
||||
"stance_duration", "desired_forward_speed", "turning_speed", "standing_height",
|
||||
"desired_incline_angle"
|
||||
])):
|
||||
__slots__ = ()
|
||||
|
||||
@@ -28,18 +28,16 @@ class BehaviorParameters(
|
||||
turning_speed=0,
|
||||
standing_height=0.21,
|
||||
desired_incline_angle=0):
|
||||
return super(BehaviorParameters, cls).__new__(
|
||||
cls, stance_duration, desired_forward_speed, turning_speed,
|
||||
standing_height, desired_incline_angle)
|
||||
return super(BehaviorParameters,
|
||||
cls).__new__(cls, stance_duration, desired_forward_speed, turning_speed,
|
||||
standing_height, desired_incline_angle)
|
||||
|
||||
|
||||
def motor_angles_to_leg_pose(motor_angles):
|
||||
leg_pose = np.zeros(_NUM_MOTORS)
|
||||
for i in range(_NUM_LEGS):
|
||||
leg_pose[i] = 0.5 * (-1)**(i // 2) * (
|
||||
motor_angles[2 * i + 1] - motor_angles[2 * i])
|
||||
leg_pose[_NUM_LEGS + i] = 0.5 * (
|
||||
motor_angles[2 * i] + motor_angles[2 * i + 1])
|
||||
leg_pose[i] = 0.5 * (-1)**(i // 2) * (motor_angles[2 * i + 1] - motor_angles[2 * i])
|
||||
leg_pose[_NUM_LEGS + i] = 0.5 * (motor_angles[2 * i] + motor_angles[2 * i + 1])
|
||||
return leg_pose
|
||||
|
||||
|
||||
@@ -47,8 +45,7 @@ def leg_pose_to_motor_angles(leg_pose):
|
||||
motor_pose = np.zeros(_NUM_MOTORS)
|
||||
for i in range(_NUM_LEGS):
|
||||
motor_pose[2 * i] = leg_pose[_NUM_LEGS + i] - (-1)**(i // 2) * leg_pose[i]
|
||||
motor_pose[2 * i + 1] = (
|
||||
leg_pose[_NUM_LEGS + i] + (-1)**(i // 2) * leg_pose[i])
|
||||
motor_pose[2 * i + 1] = (leg_pose[_NUM_LEGS + i] + (-1)**(i // 2) * leg_pose[i])
|
||||
return motor_pose
|
||||
|
||||
|
||||
@@ -85,8 +82,7 @@ def foot_position_to_leg_pose(foot_position):
|
||||
ext = math.acos(cos_ext)
|
||||
|
||||
hip_toe = math.sqrt(hip_toe_sqr)
|
||||
cos_theta = (hip_toe_sqr + hip_ankle_sqr -
|
||||
(l3 - l2)**2) / (2 * hip_ankle * hip_toe)
|
||||
cos_theta = (hip_toe_sqr + hip_ankle_sqr - (l3 - l2)**2) / (2 * hip_ankle * hip_toe)
|
||||
|
||||
assert cos_theta > 0
|
||||
theta = math.acos(cos_theta)
|
||||
@@ -94,8 +90,7 @@ def foot_position_to_leg_pose(foot_position):
|
||||
return (-sw, ext)
|
||||
|
||||
|
||||
def foot_horizontal_position_to_leg_swing(foot_horizontal_position,
|
||||
leg_extension):
|
||||
def foot_horizontal_position_to_leg_swing(foot_horizontal_position, leg_extension):
|
||||
"""Computes the target leg swing.
|
||||
|
||||
Sometimes it is more convenient to plan in the hybrid space.
|
||||
@@ -119,8 +114,7 @@ def foot_horizontal_position_to_leg_swing(foot_horizontal_position,
|
||||
|
||||
# Cap the foot horizontal (projected) position so the target leg pose is
|
||||
# always feasible.
|
||||
foot_position = max(
|
||||
min(toe_hip_len * 0.8, foot_horizontal_position), -toe_hip_len * 0.5)
|
||||
foot_position = max(min(toe_hip_len * 0.8, foot_horizontal_position), -toe_hip_len * 0.5)
|
||||
|
||||
sw_and_theta = math.asin(foot_position / toe_hip_len)
|
||||
|
||||
@@ -171,9 +165,7 @@ def generate_swing_trajectory(phase, init_pose, end_pose):
|
||||
|
||||
b = (phi * phi * delta_2 - delta_1) / delta_p
|
||||
|
||||
delta = (
|
||||
a * normalized_phase * normalized_phase + b * normalized_phase +
|
||||
init_delta)
|
||||
delta = (a * normalized_phase * normalized_phase + b * normalized_phase + init_delta)
|
||||
|
||||
l1 = _UPPER_LEG_LEN
|
||||
l2 = _LOWER_SHORT_LEG_LEN
|
||||
@@ -209,10 +201,9 @@ class RaibertSwingLegController(object):
|
||||
leg_pose_set = []
|
||||
for i in raibiert_controller.swing_set:
|
||||
target_foot_horizontal_position = (
|
||||
raibiert_controller.behavior_parameters.stance_duration / 2 *
|
||||
current_speed + self._speed_gain *
|
||||
(current_speed -
|
||||
raibiert_controller.behavior_parameters.desired_forward_speed))
|
||||
raibiert_controller.behavior_parameters.stance_duration / 2 * current_speed +
|
||||
self._speed_gain *
|
||||
(current_speed - raibiert_controller.behavior_parameters.desired_forward_speed))
|
||||
|
||||
# Use the swing phase [0, 1] to track the foot. The idea is
|
||||
# straightforward:
|
||||
@@ -221,19 +212,19 @@ class RaibertSwingLegController(object):
|
||||
# 3) Find the next leg pose on the curve based on how much time left.
|
||||
|
||||
# 1) Convert the target foot
|
||||
target_leg_extension = (
|
||||
raibiert_controller.nominal_leg_extension -
|
||||
self._leg_extension_clearance)
|
||||
target_leg_swing = foot_horizontal_position_to_leg_swing(
|
||||
target_foot_horizontal_position, leg_extension=target_leg_extension)
|
||||
target_leg_extension = (raibiert_controller.nominal_leg_extension -
|
||||
self._leg_extension_clearance)
|
||||
target_leg_swing = foot_horizontal_position_to_leg_swing(target_foot_horizontal_position,
|
||||
leg_extension=target_leg_extension)
|
||||
|
||||
target_leg_pose = (target_leg_swing, target_leg_extension)
|
||||
|
||||
# 2) Generates the curve from the current leg pose to the target leg pose.
|
||||
# and Find the next leg pose on the curve based on current swing phase.
|
||||
|
||||
desired_leg_pose = self._leg_trajectory_generator(
|
||||
phase, raibiert_controller.swing_start_leg_pose, target_leg_pose)
|
||||
desired_leg_pose = self._leg_trajectory_generator(phase,
|
||||
raibiert_controller.swing_start_leg_pose,
|
||||
target_leg_pose)
|
||||
|
||||
leg_pose_set.append(desired_leg_pose)
|
||||
|
||||
@@ -244,9 +235,7 @@ class RaibertSwingLegController(object):
|
||||
|
||||
class RaibertStanceLegController(object):
|
||||
|
||||
def __init__(self,
|
||||
speed_gain=0.1,
|
||||
leg_trajectory_generator=generate_stance_trajectory):
|
||||
def __init__(self, speed_gain=0.1, leg_trajectory_generator=generate_stance_trajectory):
|
||||
self._speed_gain = speed_gain
|
||||
self._leg_trajectory_generator = leg_trajectory_generator
|
||||
|
||||
@@ -255,20 +244,18 @@ class RaibertStanceLegController(object):
|
||||
current_speed = raibiert_controller.estimate_base_velocity()
|
||||
leg_pose_set = []
|
||||
for i in raibiert_controller.stance_set:
|
||||
desired_forward_speed = (
|
||||
raibiert_controller.behavior_parameters.desired_forward_speed)
|
||||
target_foot_position = -(
|
||||
raibiert_controller.behavior_parameters.stance_duration / 2 *
|
||||
current_speed - self._speed_gain *
|
||||
(current_speed - desired_forward_speed))
|
||||
desired_forward_speed = (raibiert_controller.behavior_parameters.desired_forward_speed)
|
||||
target_foot_position = -(raibiert_controller.behavior_parameters.stance_duration / 2 *
|
||||
current_speed - self._speed_gain *
|
||||
(current_speed - desired_forward_speed))
|
||||
|
||||
target_leg_pose = (foot_horizontal_position_to_leg_swing(
|
||||
target_foot_position,
|
||||
leg_extension=raibiert_controller.nominal_leg_extension),
|
||||
target_foot_position, leg_extension=raibiert_controller.nominal_leg_extension),
|
||||
raibiert_controller.nominal_leg_extension)
|
||||
|
||||
desired_leg_pose = self._leg_trajectory_generator(
|
||||
phase, raibiert_controller.stance_start_leg_pose, target_leg_pose)
|
||||
desired_leg_pose = self._leg_trajectory_generator(phase,
|
||||
raibiert_controller.stance_start_leg_pose,
|
||||
target_leg_pose)
|
||||
|
||||
leg_pose_set.append(desired_leg_pose)
|
||||
|
||||
@@ -288,8 +275,7 @@ class MinitaurRaibertTrottingController(object):
|
||||
self._robot = robot
|
||||
self._behavior_parameters = behavior_parameters
|
||||
|
||||
nominal_leg_pose = foot_position_to_leg_pose(
|
||||
(0, -self._behavior_parameters.standing_height))
|
||||
nominal_leg_pose = foot_position_to_leg_pose((0, -self._behavior_parameters.standing_height))
|
||||
self._nominal_leg_extension = nominal_leg_pose[1]
|
||||
|
||||
self._swing_leg_controller = swing_leg_controller
|
||||
@@ -337,8 +323,7 @@ class MinitaurRaibertTrottingController(object):
|
||||
# extract the swing leg pose from the current_leg_pose
|
||||
leg_pose = []
|
||||
for index in leg_indices:
|
||||
leg_pose.append(
|
||||
[current_leg_pose[index], current_leg_pose[index + _NUM_LEGS]])
|
||||
leg_pose.append([current_leg_pose[index], current_leg_pose[index + _NUM_LEGS]])
|
||||
|
||||
leg_pose = np.array(leg_pose)
|
||||
return np.mean(leg_pose, axis=0)
|
||||
@@ -353,13 +338,13 @@ class MinitaurRaibertTrottingController(object):
|
||||
|
||||
def get_phase(self):
|
||||
"""Compute the current stance/swing phase."""
|
||||
return math.fmod(self._time, self._behavior_parameters.stance_duration
|
||||
) / self._behavior_parameters.stance_duration
|
||||
return math.fmod(
|
||||
self._time,
|
||||
self._behavior_parameters.stance_duration) / self._behavior_parameters.stance_duration
|
||||
|
||||
def update_swing_stance_set(self):
|
||||
"""Switch the set of swing/stance legs based on timing."""
|
||||
swing_stance_phase = math.fmod(
|
||||
self._time, 2 * self._behavior_parameters.stance_duration)
|
||||
swing_stance_phase = math.fmod(self._time, 2 * self._behavior_parameters.stance_duration)
|
||||
if swing_stance_phase < self._behavior_parameters.stance_duration:
|
||||
return (DIAGONAL_LEG_PAIR_1, DIAGONAL_LEG_PAIR_2)
|
||||
return (DIAGONAL_LEG_PAIR_2, DIAGONAL_LEG_PAIR_1)
|
||||
@@ -387,8 +372,8 @@ class MinitaurRaibertTrottingController(object):
|
||||
toe_hip_len = math.sqrt(x**2 + y**2)
|
||||
horizontal_dist = toe_hip_len * delta_sw
|
||||
phase = self.get_phase()
|
||||
speed = 0 if phase < 0.1 else horizontal_dist / (
|
||||
self._behavior_parameters.stance_duration * phase)
|
||||
speed = 0 if phase < 0.1 else horizontal_dist / (self._behavior_parameters.stance_duration *
|
||||
phase)
|
||||
return speed
|
||||
|
||||
def get_swing_leg_action(self):
|
||||
|
||||
@@ -1,6 +1,5 @@
|
||||
#The example to run the raibert controller in a Minitaur gym env.
|
||||
|
||||
|
||||
from __future__ import absolute_import
|
||||
from __future__ import division
|
||||
from __future__ import print_function
|
||||
@@ -9,8 +8,7 @@ import os
|
||||
import inspect
|
||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
parentdir = os.path.dirname(os.path.dirname(os.path.dirname(currentdir)))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
import tensorflow as tf
|
||||
from pybullet_envs.minitaur.envs import minitaur_raibert_controller
|
||||
@@ -21,9 +19,8 @@ FLAGS = tf.app.flags.FLAGS
|
||||
|
||||
flags.DEFINE_float("motor_kp", 1.0, "The position gain of the motor.")
|
||||
flags.DEFINE_float("motor_kd", 0.015, "The speed gain of the motor.")
|
||||
flags.DEFINE_float(
|
||||
"control_latency", 0.02, "The latency between sensor measurement and action"
|
||||
" execution the robot.")
|
||||
flags.DEFINE_float("control_latency", 0.02, "The latency between sensor measurement and action"
|
||||
" execution the robot.")
|
||||
flags.DEFINE_string("log_path", None, "The directory to write the log file.")
|
||||
|
||||
|
||||
@@ -55,20 +52,18 @@ def main(argv):
|
||||
log_path=FLAGS.log_path)
|
||||
env.reset()
|
||||
|
||||
controller = minitaur_raibert_controller.MinitaurRaibertTrottingController(
|
||||
env.minitaur)
|
||||
controller = minitaur_raibert_controller.MinitaurRaibertTrottingController(env.minitaur)
|
||||
|
||||
tstart = env.minitaur.GetTimeSinceReset()
|
||||
for _ in range(1000):
|
||||
t = env.minitaur.GetTimeSinceReset() - tstart
|
||||
controller.behavior_parameters = (
|
||||
minitaur_raibert_controller.BehaviorParameters(
|
||||
desired_forward_speed=speed(t)))
|
||||
controller.behavior_parameters = (minitaur_raibert_controller.BehaviorParameters(
|
||||
desired_forward_speed=speed(t)))
|
||||
controller.update(t)
|
||||
env.step(controller.get_action())
|
||||
finally:
|
||||
env.close()
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
tf.app.run(main)
|
||||
|
||||
|
||||
@@ -4,10 +4,10 @@ It is the result of first pass system identification for the rainbow dash robot.
|
||||
|
||||
"""
|
||||
|
||||
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))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
import math
|
||||
|
||||
@@ -46,13 +46,12 @@ class MinitaurRainbowDash(minitaur.Minitaur):
|
||||
"%s/quadruped/minitaur_rainbow_dash.urdf" % self._urdf_root,
|
||||
init_position,
|
||||
useFixedBase=self._on_rack,
|
||||
flags=(
|
||||
self._pybullet_client.URDF_USE_SELF_COLLISION_EXCLUDE_PARENT))
|
||||
flags=(self._pybullet_client.URDF_USE_SELF_COLLISION_EXCLUDE_PARENT))
|
||||
else:
|
||||
self.quadruped = self._pybullet_client.loadURDF(
|
||||
"%s/quadruped/minitaur_rainbow_dash.urdf" % self._urdf_root,
|
||||
init_position,
|
||||
useFixedBase=self._on_rack)
|
||||
self.quadruped = self._pybullet_client.loadURDF("%s/quadruped/minitaur_rainbow_dash.urdf" %
|
||||
self._urdf_root,
|
||||
init_position,
|
||||
useFixedBase=self._on_rack)
|
||||
self._BuildJointNameToIdDict()
|
||||
self._BuildUrdfIds()
|
||||
if self._remove_default_joint_damping:
|
||||
@@ -62,10 +61,9 @@ class MinitaurRainbowDash(minitaur.Minitaur):
|
||||
self._RecordInertiaInfoFromURDF()
|
||||
self.ResetPose(add_constraint=True)
|
||||
else:
|
||||
self._pybullet_client.resetBasePositionAndOrientation(
|
||||
self.quadruped, init_position, minitaur.INIT_ORIENTATION)
|
||||
self._pybullet_client.resetBaseVelocity(self.quadruped, [0, 0, 0],
|
||||
[0, 0, 0])
|
||||
self._pybullet_client.resetBasePositionAndOrientation(self.quadruped, init_position,
|
||||
minitaur.INIT_ORIENTATION)
|
||||
self._pybullet_client.resetBaseVelocity(self.quadruped, [0, 0, 0], [0, 0, 0])
|
||||
self.ResetPose(add_constraint=False)
|
||||
|
||||
self._overheat_counter = np.zeros(self.num_motors)
|
||||
@@ -103,68 +101,60 @@ class MinitaurRainbowDash(minitaur.Minitaur):
|
||||
knee_angle = -2.1834
|
||||
|
||||
leg_position = minitaur.LEG_POSITION[leg_id]
|
||||
self._pybullet_client.resetJointState(
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["motor_" + leg_position + "L_joint"],
|
||||
self._motor_direction[2 * leg_id] * half_pi,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position + "L_joint"],
|
||||
self._motor_direction[2 * leg_id] * knee_angle,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["motor_" + leg_position + "R_joint"],
|
||||
self._motor_direction[2 * leg_id + 1] * half_pi,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position + "R_joint"],
|
||||
self._motor_direction[2 * leg_id + 1] * knee_angle,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(self.quadruped,
|
||||
self._joint_name_to_id["motor_" + leg_position +
|
||||
"L_joint"],
|
||||
self._motor_direction[2 * leg_id] * half_pi,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position +
|
||||
"L_joint"],
|
||||
self._motor_direction[2 * leg_id] * knee_angle,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(self.quadruped,
|
||||
self._joint_name_to_id["motor_" + leg_position +
|
||||
"R_joint"],
|
||||
self._motor_direction[2 * leg_id + 1] * half_pi,
|
||||
targetVelocity=0)
|
||||
self._pybullet_client.resetJointState(self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position +
|
||||
"R_joint"],
|
||||
self._motor_direction[2 * leg_id + 1] * knee_angle,
|
||||
targetVelocity=0)
|
||||
if add_constraint:
|
||||
if leg_id < 2:
|
||||
self._pybullet_client.createConstraint(
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position + "R_joint"],
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position + "L_joint"],
|
||||
self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0],
|
||||
KNEE_CONSTRAINT_POINT_SHORT, KNEE_CONSTRAINT_POINT_LONG)
|
||||
self.quadruped, self._joint_name_to_id["knee_" + leg_position + "R_joint"],
|
||||
self.quadruped, self._joint_name_to_id["knee_" + leg_position + "L_joint"],
|
||||
self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0], KNEE_CONSTRAINT_POINT_SHORT,
|
||||
KNEE_CONSTRAINT_POINT_LONG)
|
||||
else:
|
||||
self._pybullet_client.createConstraint(
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position + "R_joint"],
|
||||
self.quadruped,
|
||||
self._joint_name_to_id["knee_" + leg_position + "L_joint"],
|
||||
self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0],
|
||||
KNEE_CONSTRAINT_POINT_LONG, KNEE_CONSTRAINT_POINT_SHORT)
|
||||
self.quadruped, self._joint_name_to_id["knee_" + leg_position + "R_joint"],
|
||||
self.quadruped, self._joint_name_to_id["knee_" + leg_position + "L_joint"],
|
||||
self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0], KNEE_CONSTRAINT_POINT_LONG,
|
||||
KNEE_CONSTRAINT_POINT_SHORT)
|
||||
|
||||
if self._accurate_motor_model_enabled or self._pd_control_enabled:
|
||||
# Disable the default motor in pybullet.
|
||||
self._pybullet_client.setJointMotorControl2(
|
||||
bodyIndex=self.quadruped,
|
||||
jointIndex=(
|
||||
self._joint_name_to_id["motor_" + leg_position + "L_joint"]),
|
||||
jointIndex=(self._joint_name_to_id["motor_" + leg_position + "L_joint"]),
|
||||
controlMode=self._pybullet_client.VELOCITY_CONTROL,
|
||||
targetVelocity=0,
|
||||
force=knee_friction_force)
|
||||
self._pybullet_client.setJointMotorControl2(
|
||||
bodyIndex=self.quadruped,
|
||||
jointIndex=(
|
||||
self._joint_name_to_id["motor_" + leg_position + "R_joint"]),
|
||||
jointIndex=(self._joint_name_to_id["motor_" + leg_position + "R_joint"]),
|
||||
controlMode=self._pybullet_client.VELOCITY_CONTROL,
|
||||
targetVelocity=0,
|
||||
force=knee_friction_force)
|
||||
|
||||
else:
|
||||
self._SetDesiredMotorAngleByName(
|
||||
"motor_" + leg_position + "L_joint",
|
||||
self._motor_direction[2 * leg_id] * half_pi)
|
||||
self._SetDesiredMotorAngleByName(
|
||||
"motor_" + leg_position + "R_joint",
|
||||
self._motor_direction[2 * leg_id + 1] * half_pi)
|
||||
self._SetDesiredMotorAngleByName("motor_" + leg_position + "L_joint",
|
||||
self._motor_direction[2 * leg_id] * half_pi)
|
||||
self._SetDesiredMotorAngleByName("motor_" + leg_position + "R_joint",
|
||||
self._motor_direction[2 * leg_id + 1] * half_pi)
|
||||
|
||||
self._pybullet_client.setJointMotorControl2(
|
||||
bodyIndex=self.quadruped,
|
||||
|
||||
@@ -42,20 +42,17 @@ class MinitaurRandomizeTerrainGymEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
fileName=terrain_file_name,
|
||||
flags=1,
|
||||
meshScale=[0.5, 0.5, 0.5])
|
||||
self._pybullet_client.createMultiBody(terrain_mass,
|
||||
terrain_collision_shape_id,
|
||||
terrain_visual_shape_id,
|
||||
terrain_position,
|
||||
self._pybullet_client.createMultiBody(terrain_mass, terrain_collision_shape_id,
|
||||
terrain_visual_shape_id, terrain_position,
|
||||
terrain_orientation)
|
||||
self._pybullet_client.setGravity(0, 0, -10)
|
||||
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,
|
||||
on_rack=self._on_rack))
|
||||
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,
|
||||
on_rack=self._on_rack))
|
||||
self._last_base_position = [0, 0, 0]
|
||||
for _ in xrange(100):
|
||||
if self._pd_control_enabled:
|
||||
@@ -78,6 +75,5 @@ class MinitaurRandomizeTerrainGymEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
asset_source = os.path.join(terrain_dir, terrain_file_name)
|
||||
asset_destination = os.path.join(FLAGS.storage_dir, terrain_file_name)
|
||||
gfile.Copy(asset_source, asset_destination, overwrite=True)
|
||||
terrain_file_name_complete = os.path.join(FLAGS.storage_dir,
|
||||
terrain_file_name)
|
||||
terrain_file_name_complete = os.path.join(FLAGS.storage_dir, terrain_file_name)
|
||||
return terrain_file_name_complete
|
||||
|
||||
@@ -21,10 +21,7 @@ def ResetTerrainExample():
|
||||
num_reset = 10
|
||||
steps = 100
|
||||
env = minitaur_randomize_terrain_gym_env.MinitaurRandomizeTerrainGymEnv(
|
||||
render=True,
|
||||
leg_model_enabled=False,
|
||||
motor_velocity_limit=np.inf,
|
||||
pd_control_enabled=True)
|
||||
render=True, leg_model_enabled=False, motor_velocity_limit=np.inf, pd_control_enabled=True)
|
||||
action = [math.pi / 2] * 8
|
||||
for _ in xrange(num_reset):
|
||||
env.reset()
|
||||
@@ -37,10 +34,7 @@ def ResetTerrainExample():
|
||||
def SinePolicyExample():
|
||||
"""An example of minitaur walking with a sine gait."""
|
||||
env = minitaur_randomize_terrain_gym_env.MinitaurRandomizeTerrainGymEnv(
|
||||
render=True,
|
||||
motor_velocity_limit=np.inf,
|
||||
pd_control_enabled=True,
|
||||
on_rack=False)
|
||||
render=True, motor_velocity_limit=np.inf, pd_control_enabled=True, on_rack=False)
|
||||
sum_reward = 0
|
||||
steps = 200
|
||||
amplitude_1_bound = 0.5
|
||||
|
||||
@@ -2,10 +2,10 @@
|
||||
|
||||
"""
|
||||
|
||||
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))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
import collections
|
||||
import math
|
||||
@@ -19,8 +19,7 @@ NUM_LEGS = 4
|
||||
NUM_MOTORS = 2 * NUM_LEGS
|
||||
|
||||
MinitaurPose = collections.namedtuple(
|
||||
"MinitaurPose",
|
||||
"swing_angle_1, swing_angle_2, swing_angle_3, swing_angle_4, "
|
||||
"MinitaurPose", "swing_angle_1, swing_angle_2, swing_angle_3, swing_angle_4, "
|
||||
"extension_angle_1, extension_angle_2, extension_angle_3, "
|
||||
"extension_angle_4")
|
||||
|
||||
@@ -35,10 +34,7 @@ class MinitaurReactiveEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
expenditure.
|
||||
|
||||
"""
|
||||
metadata = {
|
||||
"render.modes": ["human", "rgb_array"],
|
||||
"video.frames_per_second": 166
|
||||
}
|
||||
metadata = {"render.modes": ["human", "rgb_array"], "video.frames_per_second": 166}
|
||||
|
||||
def __init__(self,
|
||||
urdf_version=None,
|
||||
@@ -96,24 +92,24 @@ class MinitaurReactiveEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
"""
|
||||
self._use_angle_in_observation = use_angle_in_observation
|
||||
|
||||
super(MinitaurReactiveEnv, self).__init__(
|
||||
urdf_version=urdf_version,
|
||||
energy_weight=energy_weight,
|
||||
accurate_motor_model_enabled=accurate_motor_model_enabled,
|
||||
motor_overheat_protection=True,
|
||||
motor_kp=motor_kp,
|
||||
motor_kd=motor_kd,
|
||||
remove_default_joint_damping=remove_default_joint_damping,
|
||||
control_latency=control_latency,
|
||||
pd_latency=pd_latency,
|
||||
on_rack=on_rack,
|
||||
render=render,
|
||||
hard_reset=hard_reset,
|
||||
num_steps_to_log=num_steps_to_log,
|
||||
env_randomizer=env_randomizer,
|
||||
log_path=log_path,
|
||||
control_time_step=control_time_step,
|
||||
action_repeat=action_repeat)
|
||||
super(MinitaurReactiveEnv,
|
||||
self).__init__(urdf_version=urdf_version,
|
||||
energy_weight=energy_weight,
|
||||
accurate_motor_model_enabled=accurate_motor_model_enabled,
|
||||
motor_overheat_protection=True,
|
||||
motor_kp=motor_kp,
|
||||
motor_kd=motor_kd,
|
||||
remove_default_joint_damping=remove_default_joint_damping,
|
||||
control_latency=control_latency,
|
||||
pd_latency=pd_latency,
|
||||
on_rack=on_rack,
|
||||
render=render,
|
||||
hard_reset=hard_reset,
|
||||
num_steps_to_log=num_steps_to_log,
|
||||
env_randomizer=env_randomizer,
|
||||
log_path=log_path,
|
||||
control_time_step=control_time_step,
|
||||
action_repeat=action_repeat)
|
||||
|
||||
action_dim = 8
|
||||
action_low = np.array([-0.5] * action_dim)
|
||||
@@ -126,34 +122,31 @@ class MinitaurReactiveEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
def reset(self):
|
||||
# TODO(b/73666007): Use composition instead of inheritance.
|
||||
# (http://go/design-for-testability-no-inheritance).
|
||||
init_pose = MinitaurPose(
|
||||
swing_angle_1=INIT_SWING_POS,
|
||||
swing_angle_2=INIT_SWING_POS,
|
||||
swing_angle_3=INIT_SWING_POS,
|
||||
swing_angle_4=INIT_SWING_POS,
|
||||
extension_angle_1=INIT_EXTENSION_POS,
|
||||
extension_angle_2=INIT_EXTENSION_POS,
|
||||
extension_angle_3=INIT_EXTENSION_POS,
|
||||
extension_angle_4=INIT_EXTENSION_POS)
|
||||
init_pose = MinitaurPose(swing_angle_1=INIT_SWING_POS,
|
||||
swing_angle_2=INIT_SWING_POS,
|
||||
swing_angle_3=INIT_SWING_POS,
|
||||
swing_angle_4=INIT_SWING_POS,
|
||||
extension_angle_1=INIT_EXTENSION_POS,
|
||||
extension_angle_2=INIT_EXTENSION_POS,
|
||||
extension_angle_3=INIT_EXTENSION_POS,
|
||||
extension_angle_4=INIT_EXTENSION_POS)
|
||||
# TODO(b/73734502): Refactor input of _convert_from_leg_model to namedtuple.
|
||||
initial_motor_angles = self._convert_from_leg_model(list(init_pose))
|
||||
super(MinitaurReactiveEnv, self).reset(
|
||||
initial_motor_angles=initial_motor_angles, reset_duration=0.5)
|
||||
super(MinitaurReactiveEnv, self).reset(initial_motor_angles=initial_motor_angles,
|
||||
reset_duration=0.5)
|
||||
return self._get_observation()
|
||||
|
||||
def _convert_from_leg_model(self, leg_pose):
|
||||
motor_pose = np.zeros(NUM_MOTORS)
|
||||
for i in range(NUM_LEGS):
|
||||
motor_pose[int(2 * i)] = leg_pose[NUM_LEGS + i] - (-1)**int(i / 2) * leg_pose[i]
|
||||
motor_pose[int(2 * i + 1)] = (
|
||||
leg_pose[NUM_LEGS + i] + (-1)**int(i / 2) * leg_pose[i])
|
||||
motor_pose[int(2 * i + 1)] = (leg_pose[NUM_LEGS + i] + (-1)**int(i / 2) * leg_pose[i])
|
||||
return motor_pose
|
||||
|
||||
def _signal(self, t):
|
||||
initial_pose = np.array([
|
||||
INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS,
|
||||
INIT_EXTENSION_POS, INIT_EXTENSION_POS, INIT_EXTENSION_POS,
|
||||
INIT_EXTENSION_POS
|
||||
INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS, INIT_EXTENSION_POS,
|
||||
INIT_EXTENSION_POS, INIT_EXTENSION_POS, INIT_EXTENSION_POS
|
||||
])
|
||||
return initial_pose
|
||||
|
||||
@@ -214,8 +207,7 @@ class MinitaurReactiveEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
upper_bound_pitch_dot = 2 * math.pi / self._time_step
|
||||
upper_bound_motor_angle = 2 * math.pi
|
||||
upper_bound = [
|
||||
upper_bound_roll, upper_bound_pitch, upper_bound_roll_dot,
|
||||
upper_bound_pitch_dot
|
||||
upper_bound_roll, upper_bound_pitch, upper_bound_roll_dot, upper_bound_pitch_dot
|
||||
]
|
||||
|
||||
if self._use_angle_in_observation:
|
||||
|
||||
@@ -10,17 +10,14 @@ import time
|
||||
import inspect
|
||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
parentdir = os.path.dirname(os.path.dirname(os.path.dirname(currentdir)))
|
||||
print("parentdir=",parentdir)
|
||||
os.sys.path.insert(0,parentdir)
|
||||
|
||||
|
||||
print("parentdir=", parentdir)
|
||||
os.sys.path.insert(0, parentdir)
|
||||
|
||||
import tensorflow as tf
|
||||
from pybullet_envs.minitaur.agents.scripts import utility
|
||||
import pybullet_data
|
||||
from pybullet_envs.minitaur.envs import simple_ppo_agent
|
||||
|
||||
|
||||
flags = tf.app.flags
|
||||
FLAGS = tf.app.flags.FLAGS
|
||||
LOG_DIR = os.path.join(pybullet_data.getDataPath(), "policies/ppo/minitaur_reactive_env")
|
||||
@@ -36,13 +33,12 @@ def main(argv):
|
||||
network = config.network
|
||||
|
||||
with tf.Session() as sess:
|
||||
agent = simple_ppo_agent.SimplePPOPolicy(
|
||||
sess,
|
||||
env,
|
||||
network,
|
||||
policy_layers=policy_layers,
|
||||
value_layers=value_layers,
|
||||
checkpoint=os.path.join(LOG_DIR, CHECKPOINT))
|
||||
agent = simple_ppo_agent.SimplePPOPolicy(sess,
|
||||
env,
|
||||
network,
|
||||
policy_layers=policy_layers,
|
||||
value_layers=value_layers,
|
||||
checkpoint=os.path.join(LOG_DIR, CHECKPOINT))
|
||||
|
||||
sum_reward = 0
|
||||
observation = env.reset()
|
||||
|
||||
@@ -29,10 +29,7 @@ class MinitaurStandGymEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
function is based on how long the minitaur stays standing up.
|
||||
|
||||
"""
|
||||
metadata = {
|
||||
"render.modes": ["human", "rgb_array"],
|
||||
"video.frames_per_second": 50
|
||||
}
|
||||
metadata = {"render.modes": ["human", "rgb_array"], "video.frames_per_second": 50}
|
||||
|
||||
def __init__(self,
|
||||
urdf_root=pybullet_data.getDataPath(),
|
||||
@@ -53,16 +50,15 @@ class MinitaurStandGymEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
pd_control_enabled: Whether to use PD controller for each motor.
|
||||
render: Whether to render the simulation.
|
||||
"""
|
||||
super(MinitaurStandGymEnv, self).__init__(
|
||||
urdf_root=urdf_root,
|
||||
action_repeat=action_repeat,
|
||||
observation_noise_stdev=observation_noise_stdev,
|
||||
self_collision_enabled=self_collision_enabled,
|
||||
motor_velocity_limit=motor_velocity_limit,
|
||||
pd_control_enabled=pd_control_enabled,
|
||||
accurate_motor_model_enabled=True,
|
||||
motor_overheat_protection=True,
|
||||
render=render)
|
||||
super(MinitaurStandGymEnv, self).__init__(urdf_root=urdf_root,
|
||||
action_repeat=action_repeat,
|
||||
observation_noise_stdev=observation_noise_stdev,
|
||||
self_collision_enabled=self_collision_enabled,
|
||||
motor_velocity_limit=motor_velocity_limit,
|
||||
pd_control_enabled=pd_control_enabled,
|
||||
accurate_motor_model_enabled=True,
|
||||
motor_overheat_protection=True,
|
||||
render=render)
|
||||
# Set the action dimension to 1, and reset the action space.
|
||||
action_dim = 1
|
||||
action_high = np.array([self._action_bound] * action_dim)
|
||||
@@ -85,8 +81,8 @@ class MinitaurStandGymEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
for t in range(5000):
|
||||
if self._is_render:
|
||||
base_pos = self.minitaur.GetBasePosition()
|
||||
self._pybullet_client.resetDebugVisualizerCamera(
|
||||
self._cam_dist, self._cam_yaw, self._cam_pitch, base_pos)
|
||||
self._pybullet_client.resetDebugVisualizerCamera(self._cam_dist, self._cam_yaw,
|
||||
self._cam_pitch, base_pos)
|
||||
state = self._get_true_observation()
|
||||
action = self._policy_flip(t, state[24:28])
|
||||
self.minitaur.ApplyAction(action)
|
||||
@@ -226,8 +222,7 @@ class MinitaurStandGymEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
# Lower the signal a little, so that it becomes positive only for a short
|
||||
# amount time.
|
||||
lower_signal = -0.94
|
||||
signal_unit = math.copysign(intensity,
|
||||
math.sin(time_step * speed) + lower_signal)
|
||||
signal_unit = math.copysign(intensity, math.sin(time_step * speed) + lower_signal)
|
||||
# Only extend the leg, don't shorten.
|
||||
if signal_unit < 0:
|
||||
signal_unit = 0
|
||||
|
||||
@@ -13,9 +13,8 @@ from pybullet_envs.minitaur.envs import minitaur_stand_gym_env
|
||||
def StandUpExample():
|
||||
"""An example that the minitaur stands up."""
|
||||
steps = 1000
|
||||
environment = minitaur_stand_gym_env.MinitaurStandGymEnv(
|
||||
render=True,
|
||||
motor_velocity_limit=np.inf)
|
||||
environment = minitaur_stand_gym_env.MinitaurStandGymEnv(render=True,
|
||||
motor_velocity_limit=np.inf)
|
||||
action = [0.5]
|
||||
_, _, done, _ = environment.step(action)
|
||||
for t in range(steps):
|
||||
|
||||
@@ -24,10 +24,7 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
controller (e.g. a neural network).
|
||||
|
||||
"""
|
||||
metadata = {
|
||||
"render.modes": ["human", "rgb_array"],
|
||||
"video.frames_per_second": 166
|
||||
}
|
||||
metadata = {"render.modes": ["human", "rgb_array"], "video.frames_per_second": 166}
|
||||
|
||||
def __init__(self,
|
||||
urdf_version=None,
|
||||
@@ -103,8 +100,8 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
|
||||
# The reset position.
|
||||
self._init_pose = [
|
||||
init_swing, init_swing, init_swing, init_swing, init_extension,
|
||||
init_extension, init_extension, init_extension
|
||||
init_swing, init_swing, init_swing, init_swing, init_extension, init_extension,
|
||||
init_extension, init_extension
|
||||
]
|
||||
|
||||
self._step_frequency = step_frequency
|
||||
@@ -112,23 +109,23 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
self._swing_amplitude = swing_amplitude
|
||||
self._use_signal_in_observation = use_signal_in_observation
|
||||
self._use_angle_in_observation = use_angle_in_observation
|
||||
super(MinitaurTrottingEnv, self).__init__(
|
||||
urdf_version=urdf_version,
|
||||
accurate_motor_model_enabled=accurate_motor_model_enabled,
|
||||
motor_overheat_protection=True,
|
||||
motor_kp=motor_kp,
|
||||
motor_kd=motor_kd,
|
||||
remove_default_joint_damping=remove_default_joint_damping,
|
||||
control_latency=control_latency,
|
||||
pd_latency=pd_latency,
|
||||
on_rack=on_rack,
|
||||
render=render,
|
||||
hard_reset=hard_reset,
|
||||
num_steps_to_log=num_steps_to_log,
|
||||
env_randomizer=env_randomizer,
|
||||
log_path=log_path,
|
||||
control_time_step=control_time_step,
|
||||
action_repeat=action_repeat)
|
||||
super(MinitaurTrottingEnv,
|
||||
self).__init__(urdf_version=urdf_version,
|
||||
accurate_motor_model_enabled=accurate_motor_model_enabled,
|
||||
motor_overheat_protection=True,
|
||||
motor_kp=motor_kp,
|
||||
motor_kd=motor_kd,
|
||||
remove_default_joint_damping=remove_default_joint_damping,
|
||||
control_latency=control_latency,
|
||||
pd_latency=pd_latency,
|
||||
on_rack=on_rack,
|
||||
render=render,
|
||||
hard_reset=hard_reset,
|
||||
num_steps_to_log=num_steps_to_log,
|
||||
env_randomizer=env_randomizer,
|
||||
log_path=log_path,
|
||||
control_time_step=control_time_step,
|
||||
action_repeat=action_repeat)
|
||||
|
||||
action_dim = NUM_LEGS * 2
|
||||
action_high = np.array([0.25] * action_dim)
|
||||
@@ -144,8 +141,8 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
# [swing leg 1, swing leg 2, swing leg 3, swing leg 4,
|
||||
# extension leg 1, extension leg 2, extension leg 3, extension leg 4]
|
||||
initial_motor_angles = self._convert_from_leg_model(self._init_pose)
|
||||
super(MinitaurTrottingEnv, self).reset(
|
||||
initial_motor_angles=initial_motor_angles, reset_duration=0.5)
|
||||
super(MinitaurTrottingEnv, self).reset(initial_motor_angles=initial_motor_angles,
|
||||
reset_duration=0.5)
|
||||
return self._get_observation()
|
||||
|
||||
def _convert_from_leg_model(self, leg_pose):
|
||||
@@ -161,8 +158,7 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
motor_pose = np.zeros(NUM_MOTORS)
|
||||
for i in range(NUM_LEGS):
|
||||
motor_pose[int(2 * i)] = leg_pose[NUM_LEGS + i] - (-1)**int(i / 2) * leg_pose[i]
|
||||
motor_pose[int(2 * i
|
||||
+ 1)] = leg_pose[NUM_LEGS + i] + (-1)**int(i / 2) * leg_pose[i]
|
||||
motor_pose[int(2 * i + 1)] = leg_pose[NUM_LEGS + i] + (-1)**int(i / 2) * leg_pose[i]
|
||||
return motor_pose
|
||||
|
||||
def _gen_signal(self, t, phase):
|
||||
@@ -179,8 +175,7 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
The desired leg extension and swing angle at the current time.
|
||||
"""
|
||||
period = 1 / self._step_frequency
|
||||
extension = self._extension_amplitude * math.cos(
|
||||
2 * math.pi / period * t + phase)
|
||||
extension = self._extension_amplitude * math.cos(2 * math.pi / period * t + phase)
|
||||
swing = self._swing_amplitude * math.sin(2 * math.pi / period * t + phase)
|
||||
return extension, swing
|
||||
|
||||
@@ -198,8 +193,8 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
ext_second_pair, sw_second_pair = self._gen_signal(t, math.pi)
|
||||
|
||||
trotting_signal = np.array([
|
||||
sw_first_pair, sw_second_pair, sw_second_pair, sw_first_pair,
|
||||
ext_first_pair, ext_second_pair, ext_second_pair, ext_first_pair
|
||||
sw_first_pair, sw_second_pair, sw_second_pair, sw_first_pair, ext_first_pair,
|
||||
ext_second_pair, ext_second_pair, ext_first_pair
|
||||
])
|
||||
signal = np.array(self._init_pose) + trotting_signal
|
||||
return signal
|
||||
@@ -286,8 +281,7 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
|
||||
"""
|
||||
upper_bound = []
|
||||
upper_bound.extend([2 * math.pi] * 2) # Roll, pitch, yaw of the base.
|
||||
upper_bound.extend(
|
||||
[2 * math.pi / self._time_step] * 2) # Roll, pitch, yaw rate.
|
||||
upper_bound.extend([2 * math.pi / self._time_step] * 2) # Roll, pitch, yaw rate.
|
||||
if self._use_signal_in_observation:
|
||||
upper_bound.extend([2 * math.pi] * NUM_MOTORS) # Signal
|
||||
if self._use_angle_in_observation:
|
||||
|
||||
@@ -26,13 +26,12 @@ def main(argv):
|
||||
network = config.network
|
||||
|
||||
with tf.Session() as sess:
|
||||
agent = simple_ppo_agent.SimplePPOPolicy(
|
||||
sess,
|
||||
env,
|
||||
network,
|
||||
policy_layers=policy_layers,
|
||||
value_layers=value_layers,
|
||||
checkpoint=os.path.join(LOG_DIR, CHECKPOINT))
|
||||
agent = simple_ppo_agent.SimplePPOPolicy(sess,
|
||||
env,
|
||||
network,
|
||||
policy_layers=policy_layers,
|
||||
value_layers=value_layers,
|
||||
checkpoint=os.path.join(LOG_DIR, CHECKPOINT))
|
||||
|
||||
sum_reward = 0
|
||||
observation = env.reset()
|
||||
@@ -48,4 +47,3 @@ def main(argv):
|
||||
|
||||
if __name__ == "__main__":
|
||||
tf.app.run(main)
|
||||
|
||||
|
||||
@@ -8,8 +8,7 @@ MOTOR_VOLTAGE = 16.0
|
||||
MOTOR_RESISTANCE = 0.186
|
||||
MOTOR_TORQUE_CONSTANT = 0.0954
|
||||
MOTOR_VISCOUS_DAMPING = 0
|
||||
MOTOR_SPEED_LIMIT = MOTOR_VOLTAGE / (
|
||||
MOTOR_VISCOUS_DAMPING + MOTOR_TORQUE_CONSTANT)
|
||||
MOTOR_SPEED_LIMIT = MOTOR_VOLTAGE / (MOTOR_VISCOUS_DAMPING + MOTOR_TORQUE_CONSTANT)
|
||||
NUM_MOTORS = 8
|
||||
|
||||
|
||||
@@ -124,21 +123,19 @@ class MotorModel(object):
|
||||
observed_torque: The torque observed by the sensor.
|
||||
"""
|
||||
observed_torque = np.clip(
|
||||
self._torque_constant *
|
||||
(np.asarray(pwm) * self._voltage / self._resistance),
|
||||
self._torque_constant * (np.asarray(pwm) * self._voltage / self._resistance),
|
||||
-OBSERVED_TORQUE_LIMIT, OBSERVED_TORQUE_LIMIT)
|
||||
|
||||
# Net voltage is clipped at 50V by diodes on the motor controller.
|
||||
voltage_net = np.clip(
|
||||
np.asarray(pwm) * self._voltage -
|
||||
(self._torque_constant + self._viscous_damping) *
|
||||
np.asarray(true_motor_velocity), -VOLTAGE_CLIPPING, VOLTAGE_CLIPPING)
|
||||
(self._torque_constant + self._viscous_damping) * np.asarray(true_motor_velocity),
|
||||
-VOLTAGE_CLIPPING, VOLTAGE_CLIPPING)
|
||||
current = voltage_net / self._resistance
|
||||
current_sign = np.sign(current)
|
||||
current_magnitude = np.absolute(current)
|
||||
# Saturate torque based on empirical current relation.
|
||||
actual_torque = np.interp(current_magnitude, self._current_table,
|
||||
self._torque_table)
|
||||
actual_torque = np.interp(current_magnitude, self._current_table, self._torque_table)
|
||||
actual_torque = np.multiply(current_sign, actual_torque)
|
||||
actual_torque = np.multiply(self._strength_ratios, actual_torque)
|
||||
return actual_torque, observed_torque
|
||||
|
||||
@@ -4,7 +4,6 @@ from __future__ import absolute_import
|
||||
from __future__ import division
|
||||
from __future__ import print_function
|
||||
|
||||
|
||||
import tensorflow as tf
|
||||
from pybullet_envs.agents.ppo import normalize
|
||||
from pybullet_envs.agents import utility
|
||||
@@ -20,29 +19,25 @@ class SimplePPOPolicy(object):
|
||||
https://cs.corp.google.com/piper///depot/google3/robotics/reinforcement_learning/agents/scripts/visualize.py.
|
||||
"""
|
||||
|
||||
def __init__(self, sess, env, network, policy_layers, value_layers,
|
||||
checkpoint):
|
||||
def __init__(self, sess, env, network, policy_layers, value_layers, checkpoint):
|
||||
self.env = env
|
||||
self.sess = sess
|
||||
observation_size = len(env.observation_space.low)
|
||||
action_size = len(env.action_space.low)
|
||||
self.observation_placeholder = tf.placeholder(
|
||||
tf.float32, [None, observation_size], name="Input")
|
||||
self._observ_filter = normalize.StreamingNormalize(
|
||||
self.observation_placeholder[0],
|
||||
center=True,
|
||||
scale=True,
|
||||
clip=5,
|
||||
name="normalize_observ")
|
||||
self._restore_policy(
|
||||
network,
|
||||
policy_layers=policy_layers,
|
||||
value_layers=value_layers,
|
||||
action_size=action_size,
|
||||
checkpoint=checkpoint)
|
||||
self.observation_placeholder = tf.placeholder(tf.float32, [None, observation_size],
|
||||
name="Input")
|
||||
self._observ_filter = normalize.StreamingNormalize(self.observation_placeholder[0],
|
||||
center=True,
|
||||
scale=True,
|
||||
clip=5,
|
||||
name="normalize_observ")
|
||||
self._restore_policy(network,
|
||||
policy_layers=policy_layers,
|
||||
value_layers=value_layers,
|
||||
action_size=action_size,
|
||||
checkpoint=checkpoint)
|
||||
|
||||
def _restore_policy(self, network, policy_layers, value_layers, action_size,
|
||||
checkpoint):
|
||||
def _restore_policy(self, network, policy_layers, value_layers, action_size, checkpoint):
|
||||
"""Restore the PPO policy from a TensorFlow checkpoint.
|
||||
|
||||
Args:
|
||||
@@ -56,24 +51,21 @@ class SimplePPOPolicy(object):
|
||||
"""
|
||||
observ = self._observ_filter.transform(self.observation_placeholder)
|
||||
with tf.variable_scope("network/rnn"):
|
||||
self.network = network(
|
||||
policy_layers=policy_layers,
|
||||
value_layers=value_layers,
|
||||
action_size=action_size)
|
||||
self.network = network(policy_layers=policy_layers,
|
||||
value_layers=value_layers,
|
||||
action_size=action_size)
|
||||
|
||||
with tf.variable_scope("temporary"):
|
||||
self.last_state = tf.Variable(
|
||||
self.network.zero_state(1, tf.float32), False)
|
||||
self.last_state = tf.Variable(self.network.zero_state(1, tf.float32), False)
|
||||
self.sess.run(self.last_state.initializer)
|
||||
|
||||
with tf.variable_scope("network"):
|
||||
(mean_action, _, _), new_state = tf.nn.dynamic_rnn(
|
||||
self.network,
|
||||
observ[:, None],
|
||||
tf.ones(1),
|
||||
self.last_state,
|
||||
tf.float32,
|
||||
swap_memory=True)
|
||||
(mean_action, _, _), new_state = tf.nn.dynamic_rnn(self.network,
|
||||
observ[:, None],
|
||||
tf.ones(1),
|
||||
self.last_state,
|
||||
tf.float32,
|
||||
swap_memory=True)
|
||||
self.mean_action = mean_action
|
||||
self.update_state = self.last_state.assign(new_state)
|
||||
|
||||
|
||||
@@ -29,8 +29,7 @@ from pybullet_envs.minitaur.agents import simple_ppo_agent
|
||||
|
||||
flags = tf.app.flags
|
||||
FLAGS = tf.app.flags.FLAGS
|
||||
flags.DEFINE_string("logdir", None,
|
||||
"The directory that contains checkpoint and config.")
|
||||
flags.DEFINE_string("logdir", None, "The directory that contains checkpoint and config.")
|
||||
flags.DEFINE_string("checkpoint", None, "The checkpoint file path.")
|
||||
flags.DEFINE_string("log_path", None, "The output path to write log.")
|
||||
|
||||
@@ -44,13 +43,13 @@ def main(argv):
|
||||
network = config.network
|
||||
|
||||
with tf.Session() as sess:
|
||||
agent = simple_ppo_agent.SimplePPOPolicy(
|
||||
sess,
|
||||
env,
|
||||
network,
|
||||
policy_layers=policy_layers,
|
||||
value_layers=value_layers,
|
||||
checkpoint=os.path.join(FLAGS.logdir, FLAGS.checkpoint))
|
||||
agent = simple_ppo_agent.SimplePPOPolicy(sess,
|
||||
env,
|
||||
network,
|
||||
policy_layers=policy_layers,
|
||||
value_layers=value_layers,
|
||||
checkpoint=os.path.join(FLAGS.logdir,
|
||||
FLAGS.checkpoint))
|
||||
|
||||
sum_reward = 0
|
||||
observation = env.reset()
|
||||
|
||||
@@ -2,7 +2,7 @@
|
||||
# source: timestamp.proto
|
||||
|
||||
import sys
|
||||
_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))
|
||||
_b = sys.version_info[0] < 3 and (lambda x: x) or (lambda x: x.encode('latin1'))
|
||||
from google.protobuf import descriptor as _descriptor
|
||||
from google.protobuf import message as _message
|
||||
from google.protobuf import reflection as _reflection
|
||||
@@ -12,65 +12,76 @@ from google.protobuf import descriptor_pb2
|
||||
|
||||
_sym_db = _symbol_database.Default()
|
||||
|
||||
|
||||
|
||||
|
||||
DESCRIPTOR = _descriptor.FileDescriptor(
|
||||
name='timestamp.proto',
|
||||
package='google.protobuf',
|
||||
syntax='proto3',
|
||||
serialized_pb=_b('\n\x0ftimestamp.proto\x12\x0fgoogle.protobuf\"+\n\tTimestamp\x12\x0f\n\x07seconds\x18\x01 \x01(\x03\x12\r\n\x05nanos\x18\x02 \x01(\x05\x62\x06proto3')
|
||||
)
|
||||
|
||||
|
||||
|
||||
name='timestamp.proto',
|
||||
package='google.protobuf',
|
||||
syntax='proto3',
|
||||
serialized_pb=_b(
|
||||
'\n\x0ftimestamp.proto\x12\x0fgoogle.protobuf\"+\n\tTimestamp\x12\x0f\n\x07seconds\x18\x01 \x01(\x03\x12\r\n\x05nanos\x18\x02 \x01(\x05\x62\x06proto3'
|
||||
))
|
||||
|
||||
_TIMESTAMP = _descriptor.Descriptor(
|
||||
name='Timestamp',
|
||||
full_name='google.protobuf.Timestamp',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(
|
||||
name='seconds', full_name='google.protobuf.Timestamp.seconds', index=0,
|
||||
number=1, type=3, cpp_type=2, label=1,
|
||||
has_default_value=False, default_value=0,
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='nanos', full_name='google.protobuf.Timestamp.nanos', index=1,
|
||||
number=2, type=5, cpp_type=1, label=1,
|
||||
has_default_value=False, default_value=0,
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[
|
||||
],
|
||||
nested_types=[],
|
||||
enum_types=[
|
||||
],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=36,
|
||||
serialized_end=79,
|
||||
name='Timestamp',
|
||||
full_name='google.protobuf.Timestamp',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(name='seconds',
|
||||
full_name='google.protobuf.Timestamp.seconds',
|
||||
index=0,
|
||||
number=1,
|
||||
type=3,
|
||||
cpp_type=2,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=0,
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(name='nanos',
|
||||
full_name='google.protobuf.Timestamp.nanos',
|
||||
index=1,
|
||||
number=2,
|
||||
type=5,
|
||||
cpp_type=1,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=0,
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[],
|
||||
nested_types=[],
|
||||
enum_types=[],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[],
|
||||
serialized_start=36,
|
||||
serialized_end=79,
|
||||
)
|
||||
|
||||
DESCRIPTOR.message_types_by_name['Timestamp'] = _TIMESTAMP
|
||||
_sym_db.RegisterFileDescriptor(DESCRIPTOR)
|
||||
|
||||
Timestamp = _reflection.GeneratedProtocolMessageType('Timestamp', (_message.Message,), dict(
|
||||
DESCRIPTOR = _TIMESTAMP,
|
||||
__module__ = 'timestamp_pb2'
|
||||
# @@protoc_insertion_point(class_scope:google.protobuf.Timestamp)
|
||||
))
|
||||
Timestamp = _reflection.GeneratedProtocolMessageType(
|
||||
'Timestamp',
|
||||
(_message.Message,),
|
||||
dict(DESCRIPTOR=_TIMESTAMP,
|
||||
__module__='timestamp_pb2'
|
||||
# @@protoc_insertion_point(class_scope:google.protobuf.Timestamp)
|
||||
))
|
||||
_sym_db.RegisterMessage(Timestamp)
|
||||
|
||||
|
||||
# @@protoc_insertion_point(module_scope)
|
||||
|
||||
@@ -2,7 +2,7 @@
|
||||
# source: vector.proto
|
||||
|
||||
import sys
|
||||
_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))
|
||||
_b = sys.version_info[0] < 3 and (lambda x: x) or (lambda x: x.encode('latin1'))
|
||||
from google.protobuf import descriptor as _descriptor
|
||||
from google.protobuf import message as _message
|
||||
from google.protobuf import reflection as _reflection
|
||||
@@ -12,348 +12,494 @@ from google.protobuf import descriptor_pb2
|
||||
|
||||
_sym_db = _symbol_database.Default()
|
||||
|
||||
|
||||
|
||||
|
||||
DESCRIPTOR = _descriptor.FileDescriptor(
|
||||
name='vector.proto',
|
||||
package='robotics.messages',
|
||||
syntax='proto3',
|
||||
serialized_pb=_b('\n\x0cvector.proto\x12\x11robotics.messages\"6\n\x08Vector4d\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\t\n\x01z\x18\x03 \x01(\x01\x12\t\n\x01w\x18\x04 \x01(\x01\"6\n\x08Vector4f\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\x12\t\n\x01w\x18\x04 \x01(\x02\"+\n\x08Vector3d\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\t\n\x01z\x18\x03 \x01(\x01\"+\n\x08Vector3f\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\" \n\x08Vector2d\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\" \n\x08Vector2f\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\"\x1b\n\x07Vectord\x12\x10\n\x04\x64\x61ta\x18\x01 \x03(\x01\x42\x02\x10\x01\"\x1b\n\x07Vectorf\x12\x10\n\x04\x64\x61ta\x18\x01 \x03(\x02\x42\x02\x10\x01\x62\x06proto3')
|
||||
)
|
||||
|
||||
|
||||
|
||||
name='vector.proto',
|
||||
package='robotics.messages',
|
||||
syntax='proto3',
|
||||
serialized_pb=_b(
|
||||
'\n\x0cvector.proto\x12\x11robotics.messages\"6\n\x08Vector4d\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\t\n\x01z\x18\x03 \x01(\x01\x12\t\n\x01w\x18\x04 \x01(\x01\"6\n\x08Vector4f\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\x12\t\n\x01w\x18\x04 \x01(\x02\"+\n\x08Vector3d\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\t\n\x01z\x18\x03 \x01(\x01\"+\n\x08Vector3f\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\" \n\x08Vector2d\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\" \n\x08Vector2f\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\"\x1b\n\x07Vectord\x12\x10\n\x04\x64\x61ta\x18\x01 \x03(\x01\x42\x02\x10\x01\"\x1b\n\x07Vectorf\x12\x10\n\x04\x64\x61ta\x18\x01 \x03(\x02\x42\x02\x10\x01\x62\x06proto3'
|
||||
))
|
||||
|
||||
_VECTOR4D = _descriptor.Descriptor(
|
||||
name='Vector4d',
|
||||
full_name='robotics.messages.Vector4d',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(
|
||||
name='x', full_name='robotics.messages.Vector4d.x', index=0,
|
||||
number=1, type=1, cpp_type=5, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='y', full_name='robotics.messages.Vector4d.y', index=1,
|
||||
number=2, type=1, cpp_type=5, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='z', full_name='robotics.messages.Vector4d.z', index=2,
|
||||
number=3, type=1, cpp_type=5, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='w', full_name='robotics.messages.Vector4d.w', index=3,
|
||||
number=4, type=1, cpp_type=5, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[
|
||||
],
|
||||
nested_types=[],
|
||||
enum_types=[
|
||||
],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=35,
|
||||
serialized_end=89,
|
||||
name='Vector4d',
|
||||
full_name='robotics.messages.Vector4d',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(name='x',
|
||||
full_name='robotics.messages.Vector4d.x',
|
||||
index=0,
|
||||
number=1,
|
||||
type=1,
|
||||
cpp_type=5,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(name='y',
|
||||
full_name='robotics.messages.Vector4d.y',
|
||||
index=1,
|
||||
number=2,
|
||||
type=1,
|
||||
cpp_type=5,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(name='z',
|
||||
full_name='robotics.messages.Vector4d.z',
|
||||
index=2,
|
||||
number=3,
|
||||
type=1,
|
||||
cpp_type=5,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(name='w',
|
||||
full_name='robotics.messages.Vector4d.w',
|
||||
index=3,
|
||||
number=4,
|
||||
type=1,
|
||||
cpp_type=5,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[],
|
||||
nested_types=[],
|
||||
enum_types=[],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[],
|
||||
serialized_start=35,
|
||||
serialized_end=89,
|
||||
)
|
||||
|
||||
|
||||
_VECTOR4F = _descriptor.Descriptor(
|
||||
name='Vector4f',
|
||||
full_name='robotics.messages.Vector4f',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(
|
||||
name='x', full_name='robotics.messages.Vector4f.x', index=0,
|
||||
number=1, type=2, cpp_type=6, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='y', full_name='robotics.messages.Vector4f.y', index=1,
|
||||
number=2, type=2, cpp_type=6, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='z', full_name='robotics.messages.Vector4f.z', index=2,
|
||||
number=3, type=2, cpp_type=6, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='w', full_name='robotics.messages.Vector4f.w', index=3,
|
||||
number=4, type=2, cpp_type=6, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[
|
||||
],
|
||||
nested_types=[],
|
||||
enum_types=[
|
||||
],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=91,
|
||||
serialized_end=145,
|
||||
name='Vector4f',
|
||||
full_name='robotics.messages.Vector4f',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(name='x',
|
||||
full_name='robotics.messages.Vector4f.x',
|
||||
index=0,
|
||||
number=1,
|
||||
type=2,
|
||||
cpp_type=6,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(name='y',
|
||||
full_name='robotics.messages.Vector4f.y',
|
||||
index=1,
|
||||
number=2,
|
||||
type=2,
|
||||
cpp_type=6,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(name='z',
|
||||
full_name='robotics.messages.Vector4f.z',
|
||||
index=2,
|
||||
number=3,
|
||||
type=2,
|
||||
cpp_type=6,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(name='w',
|
||||
full_name='robotics.messages.Vector4f.w',
|
||||
index=3,
|
||||
number=4,
|
||||
type=2,
|
||||
cpp_type=6,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[],
|
||||
nested_types=[],
|
||||
enum_types=[],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[],
|
||||
serialized_start=91,
|
||||
serialized_end=145,
|
||||
)
|
||||
|
||||
|
||||
_VECTOR3D = _descriptor.Descriptor(
|
||||
name='Vector3d',
|
||||
full_name='robotics.messages.Vector3d',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(
|
||||
name='x', full_name='robotics.messages.Vector3d.x', index=0,
|
||||
number=1, type=1, cpp_type=5, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='y', full_name='robotics.messages.Vector3d.y', index=1,
|
||||
number=2, type=1, cpp_type=5, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='z', full_name='robotics.messages.Vector3d.z', index=2,
|
||||
number=3, type=1, cpp_type=5, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[
|
||||
],
|
||||
nested_types=[],
|
||||
enum_types=[
|
||||
],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=147,
|
||||
serialized_end=190,
|
||||
name='Vector3d',
|
||||
full_name='robotics.messages.Vector3d',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(name='x',
|
||||
full_name='robotics.messages.Vector3d.x',
|
||||
index=0,
|
||||
number=1,
|
||||
type=1,
|
||||
cpp_type=5,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(name='y',
|
||||
full_name='robotics.messages.Vector3d.y',
|
||||
index=1,
|
||||
number=2,
|
||||
type=1,
|
||||
cpp_type=5,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(name='z',
|
||||
full_name='robotics.messages.Vector3d.z',
|
||||
index=2,
|
||||
number=3,
|
||||
type=1,
|
||||
cpp_type=5,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[],
|
||||
nested_types=[],
|
||||
enum_types=[],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[],
|
||||
serialized_start=147,
|
||||
serialized_end=190,
|
||||
)
|
||||
|
||||
|
||||
_VECTOR3F = _descriptor.Descriptor(
|
||||
name='Vector3f',
|
||||
full_name='robotics.messages.Vector3f',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(
|
||||
name='x', full_name='robotics.messages.Vector3f.x', index=0,
|
||||
number=1, type=2, cpp_type=6, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='y', full_name='robotics.messages.Vector3f.y', index=1,
|
||||
number=2, type=2, cpp_type=6, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='z', full_name='robotics.messages.Vector3f.z', index=2,
|
||||
number=3, type=2, cpp_type=6, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[
|
||||
],
|
||||
nested_types=[],
|
||||
enum_types=[
|
||||
],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=192,
|
||||
serialized_end=235,
|
||||
name='Vector3f',
|
||||
full_name='robotics.messages.Vector3f',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(name='x',
|
||||
full_name='robotics.messages.Vector3f.x',
|
||||
index=0,
|
||||
number=1,
|
||||
type=2,
|
||||
cpp_type=6,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(name='y',
|
||||
full_name='robotics.messages.Vector3f.y',
|
||||
index=1,
|
||||
number=2,
|
||||
type=2,
|
||||
cpp_type=6,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(name='z',
|
||||
full_name='robotics.messages.Vector3f.z',
|
||||
index=2,
|
||||
number=3,
|
||||
type=2,
|
||||
cpp_type=6,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[],
|
||||
nested_types=[],
|
||||
enum_types=[],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[],
|
||||
serialized_start=192,
|
||||
serialized_end=235,
|
||||
)
|
||||
|
||||
|
||||
_VECTOR2D = _descriptor.Descriptor(
|
||||
name='Vector2d',
|
||||
full_name='robotics.messages.Vector2d',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(
|
||||
name='x', full_name='robotics.messages.Vector2d.x', index=0,
|
||||
number=1, type=1, cpp_type=5, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='y', full_name='robotics.messages.Vector2d.y', index=1,
|
||||
number=2, type=1, cpp_type=5, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[
|
||||
],
|
||||
nested_types=[],
|
||||
enum_types=[
|
||||
],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=237,
|
||||
serialized_end=269,
|
||||
name='Vector2d',
|
||||
full_name='robotics.messages.Vector2d',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(name='x',
|
||||
full_name='robotics.messages.Vector2d.x',
|
||||
index=0,
|
||||
number=1,
|
||||
type=1,
|
||||
cpp_type=5,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(name='y',
|
||||
full_name='robotics.messages.Vector2d.y',
|
||||
index=1,
|
||||
number=2,
|
||||
type=1,
|
||||
cpp_type=5,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[],
|
||||
nested_types=[],
|
||||
enum_types=[],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[],
|
||||
serialized_start=237,
|
||||
serialized_end=269,
|
||||
)
|
||||
|
||||
|
||||
_VECTOR2F = _descriptor.Descriptor(
|
||||
name='Vector2f',
|
||||
full_name='robotics.messages.Vector2f',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(
|
||||
name='x', full_name='robotics.messages.Vector2f.x', index=0,
|
||||
number=1, type=2, cpp_type=6, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='y', full_name='robotics.messages.Vector2f.y', index=1,
|
||||
number=2, type=2, cpp_type=6, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None, file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[
|
||||
],
|
||||
nested_types=[],
|
||||
enum_types=[
|
||||
],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=271,
|
||||
serialized_end=303,
|
||||
name='Vector2f',
|
||||
full_name='robotics.messages.Vector2f',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(name='x',
|
||||
full_name='robotics.messages.Vector2f.x',
|
||||
index=0,
|
||||
number=1,
|
||||
type=2,
|
||||
cpp_type=6,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
_descriptor.FieldDescriptor(name='y',
|
||||
full_name='robotics.messages.Vector2f.y',
|
||||
index=1,
|
||||
number=2,
|
||||
type=2,
|
||||
cpp_type=6,
|
||||
label=1,
|
||||
has_default_value=False,
|
||||
default_value=float(0),
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=None,
|
||||
file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[],
|
||||
nested_types=[],
|
||||
enum_types=[],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[],
|
||||
serialized_start=271,
|
||||
serialized_end=303,
|
||||
)
|
||||
|
||||
|
||||
_VECTORD = _descriptor.Descriptor(
|
||||
name='Vectord',
|
||||
full_name='robotics.messages.Vectord',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(
|
||||
name='data', full_name='robotics.messages.Vectord.data', index=0,
|
||||
number=1, type=1, cpp_type=5, label=3,
|
||||
has_default_value=False, default_value=[],
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=_descriptor._ParseOptions(descriptor_pb2.FieldOptions(), _b('\020\001')), file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[
|
||||
],
|
||||
nested_types=[],
|
||||
enum_types=[
|
||||
],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=305,
|
||||
serialized_end=332,
|
||||
name='Vectord',
|
||||
full_name='robotics.messages.Vectord',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(name='data',
|
||||
full_name='robotics.messages.Vectord.data',
|
||||
index=0,
|
||||
number=1,
|
||||
type=1,
|
||||
cpp_type=5,
|
||||
label=3,
|
||||
has_default_value=False,
|
||||
default_value=[],
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=_descriptor._ParseOptions(
|
||||
descriptor_pb2.FieldOptions(), _b('\020\001')),
|
||||
file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[],
|
||||
nested_types=[],
|
||||
enum_types=[],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[],
|
||||
serialized_start=305,
|
||||
serialized_end=332,
|
||||
)
|
||||
|
||||
|
||||
_VECTORF = _descriptor.Descriptor(
|
||||
name='Vectorf',
|
||||
full_name='robotics.messages.Vectorf',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(
|
||||
name='data', full_name='robotics.messages.Vectorf.data', index=0,
|
||||
number=1, type=2, cpp_type=6, label=3,
|
||||
has_default_value=False, default_value=[],
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=_descriptor._ParseOptions(descriptor_pb2.FieldOptions(), _b('\020\001')), file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[
|
||||
],
|
||||
nested_types=[],
|
||||
enum_types=[
|
||||
],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=334,
|
||||
serialized_end=361,
|
||||
name='Vectorf',
|
||||
full_name='robotics.messages.Vectorf',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(name='data',
|
||||
full_name='robotics.messages.Vectorf.data',
|
||||
index=0,
|
||||
number=1,
|
||||
type=2,
|
||||
cpp_type=6,
|
||||
label=3,
|
||||
has_default_value=False,
|
||||
default_value=[],
|
||||
message_type=None,
|
||||
enum_type=None,
|
||||
containing_type=None,
|
||||
is_extension=False,
|
||||
extension_scope=None,
|
||||
options=_descriptor._ParseOptions(
|
||||
descriptor_pb2.FieldOptions(), _b('\020\001')),
|
||||
file=DESCRIPTOR),
|
||||
],
|
||||
extensions=[],
|
||||
nested_types=[],
|
||||
enum_types=[],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[],
|
||||
serialized_start=334,
|
||||
serialized_end=361,
|
||||
)
|
||||
|
||||
DESCRIPTOR.message_types_by_name['Vector4d'] = _VECTOR4D
|
||||
@@ -366,65 +512,82 @@ DESCRIPTOR.message_types_by_name['Vectord'] = _VECTORD
|
||||
DESCRIPTOR.message_types_by_name['Vectorf'] = _VECTORF
|
||||
_sym_db.RegisterFileDescriptor(DESCRIPTOR)
|
||||
|
||||
Vector4d = _reflection.GeneratedProtocolMessageType('Vector4d', (_message.Message,), dict(
|
||||
DESCRIPTOR = _VECTOR4D,
|
||||
__module__ = 'vector_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.messages.Vector4d)
|
||||
))
|
||||
Vector4d = _reflection.GeneratedProtocolMessageType(
|
||||
'Vector4d',
|
||||
(_message.Message,),
|
||||
dict(DESCRIPTOR=_VECTOR4D,
|
||||
__module__='vector_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.messages.Vector4d)
|
||||
))
|
||||
_sym_db.RegisterMessage(Vector4d)
|
||||
|
||||
Vector4f = _reflection.GeneratedProtocolMessageType('Vector4f', (_message.Message,), dict(
|
||||
DESCRIPTOR = _VECTOR4F,
|
||||
__module__ = 'vector_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.messages.Vector4f)
|
||||
))
|
||||
Vector4f = _reflection.GeneratedProtocolMessageType(
|
||||
'Vector4f',
|
||||
(_message.Message,),
|
||||
dict(DESCRIPTOR=_VECTOR4F,
|
||||
__module__='vector_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.messages.Vector4f)
|
||||
))
|
||||
_sym_db.RegisterMessage(Vector4f)
|
||||
|
||||
Vector3d = _reflection.GeneratedProtocolMessageType('Vector3d', (_message.Message,), dict(
|
||||
DESCRIPTOR = _VECTOR3D,
|
||||
__module__ = 'vector_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.messages.Vector3d)
|
||||
))
|
||||
Vector3d = _reflection.GeneratedProtocolMessageType(
|
||||
'Vector3d',
|
||||
(_message.Message,),
|
||||
dict(DESCRIPTOR=_VECTOR3D,
|
||||
__module__='vector_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.messages.Vector3d)
|
||||
))
|
||||
_sym_db.RegisterMessage(Vector3d)
|
||||
|
||||
Vector3f = _reflection.GeneratedProtocolMessageType('Vector3f', (_message.Message,), dict(
|
||||
DESCRIPTOR = _VECTOR3F,
|
||||
__module__ = 'vector_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.messages.Vector3f)
|
||||
))
|
||||
Vector3f = _reflection.GeneratedProtocolMessageType(
|
||||
'Vector3f',
|
||||
(_message.Message,),
|
||||
dict(DESCRIPTOR=_VECTOR3F,
|
||||
__module__='vector_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.messages.Vector3f)
|
||||
))
|
||||
_sym_db.RegisterMessage(Vector3f)
|
||||
|
||||
Vector2d = _reflection.GeneratedProtocolMessageType('Vector2d', (_message.Message,), dict(
|
||||
DESCRIPTOR = _VECTOR2D,
|
||||
__module__ = 'vector_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.messages.Vector2d)
|
||||
))
|
||||
Vector2d = _reflection.GeneratedProtocolMessageType(
|
||||
'Vector2d',
|
||||
(_message.Message,),
|
||||
dict(DESCRIPTOR=_VECTOR2D,
|
||||
__module__='vector_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.messages.Vector2d)
|
||||
))
|
||||
_sym_db.RegisterMessage(Vector2d)
|
||||
|
||||
Vector2f = _reflection.GeneratedProtocolMessageType('Vector2f', (_message.Message,), dict(
|
||||
DESCRIPTOR = _VECTOR2F,
|
||||
__module__ = 'vector_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.messages.Vector2f)
|
||||
))
|
||||
Vector2f = _reflection.GeneratedProtocolMessageType(
|
||||
'Vector2f',
|
||||
(_message.Message,),
|
||||
dict(DESCRIPTOR=_VECTOR2F,
|
||||
__module__='vector_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.messages.Vector2f)
|
||||
))
|
||||
_sym_db.RegisterMessage(Vector2f)
|
||||
|
||||
Vectord = _reflection.GeneratedProtocolMessageType('Vectord', (_message.Message,), dict(
|
||||
DESCRIPTOR = _VECTORD,
|
||||
__module__ = 'vector_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.messages.Vectord)
|
||||
))
|
||||
Vectord = _reflection.GeneratedProtocolMessageType(
|
||||
'Vectord',
|
||||
(_message.Message,),
|
||||
dict(DESCRIPTOR=_VECTORD,
|
||||
__module__='vector_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.messages.Vectord)
|
||||
))
|
||||
_sym_db.RegisterMessage(Vectord)
|
||||
|
||||
Vectorf = _reflection.GeneratedProtocolMessageType('Vectorf', (_message.Message,), dict(
|
||||
DESCRIPTOR = _VECTORF,
|
||||
__module__ = 'vector_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.messages.Vectorf)
|
||||
))
|
||||
Vectorf = _reflection.GeneratedProtocolMessageType(
|
||||
'Vectorf',
|
||||
(_message.Message,),
|
||||
dict(DESCRIPTOR=_VECTORF,
|
||||
__module__='vector_pb2'
|
||||
# @@protoc_insertion_point(class_scope:robotics.messages.Vectorf)
|
||||
))
|
||||
_sym_db.RegisterMessage(Vectorf)
|
||||
|
||||
|
||||
_VECTORD.fields_by_name['data'].has_options = True
|
||||
_VECTORD.fields_by_name['data']._options = _descriptor._ParseOptions(descriptor_pb2.FieldOptions(), _b('\020\001'))
|
||||
_VECTORD.fields_by_name['data']._options = _descriptor._ParseOptions(descriptor_pb2.FieldOptions(),
|
||||
_b('\020\001'))
|
||||
_VECTORF.fields_by_name['data'].has_options = True
|
||||
_VECTORF.fields_by_name['data']._options = _descriptor._ParseOptions(descriptor_pb2.FieldOptions(), _b('\020\001'))
|
||||
_VECTORF.fields_by_name['data']._options = _descriptor._ParseOptions(descriptor_pb2.FieldOptions(),
|
||||
_b('\020\001'))
|
||||
# @@protoc_insertion_point(module_scope)
|
||||
|
||||
Reference in New Issue
Block a user