mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-05 01:50:05 +00:00
fixes in PyBullet deep_mimic to allow running in pip version
This commit is contained in:
parent
12e6478689
commit
1bd201eb43
@ -12,4 +12,16 @@ cd pybullet
|
||||
if [ -e pybullet.dylib ]; then
|
||||
ln -f -s pybullet.dylib pybullet.so
|
||||
fi
|
||||
if [ -e pybullet_envs ]; then
|
||||
rm pybullet_envs
|
||||
fi
|
||||
if [ -e pybullet_data ]; then
|
||||
rm pybullet_data
|
||||
fi
|
||||
if [ -e pybullet_utils ]; then
|
||||
rm pybullet_utils
|
||||
fi
|
||||
ln -s ../../../examples/pybullet/gym/pybullet_envs .
|
||||
ln -s ../../../examples/pybullet/gym/pybullet_data .
|
||||
ln -s ../../../examples/pybullet/gym/pybullet_utils .
|
||||
echo "Completed build of Bullet."
|
||||
|
@ -13,8 +13,24 @@ IF(BUILD_PYBULLET_NUMPY)
|
||||
)
|
||||
ENDIF()
|
||||
|
||||
ADD_DEFINITIONS(-DSTATIC_LINK_SPD_PLUGIN)
|
||||
|
||||
SET(pybullet_SRCS
|
||||
pybullet.c
|
||||
../../examples/SharedMemory/plugins/stablePDPlugin/SpAlg.cpp
|
||||
../../examples/SharedMemory/plugins/stablePDPlugin/SpAlg.h
|
||||
../../examples/SharedMemory/plugins/stablePDPlugin/Shape.cpp
|
||||
../../examples/SharedMemory/plugins/stablePDPlugin/Shape.h
|
||||
../../examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.cpp
|
||||
../../examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.h
|
||||
../../examples/SharedMemory/plugins/stablePDPlugin/RBDModel.cpp
|
||||
../../examples/SharedMemory/plugins/stablePDPlugin/RBDModel.h
|
||||
../../examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp
|
||||
../../examples/SharedMemory/plugins/stablePDPlugin/MathUtil.h
|
||||
../../examples/SharedMemory/plugins/stablePDPlugin/KinTree.cpp
|
||||
../../examples/SharedMemory/plugins/stablePDPlugin/KinTree.h
|
||||
../../examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.cpp
|
||||
../../examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.h
|
||||
../../examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp
|
||||
../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp
|
||||
../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h
|
||||
|
@ -1,6 +1,6 @@
|
||||
import json
|
||||
import numpy as np
|
||||
from learning.ppo_agent import PPOAgent
|
||||
from pybullet_envs.deep_mimic.learning.ppo_agent import PPOAgent
|
||||
import pybullet_data
|
||||
|
||||
AGENT_TYPE_KEY = "AgentType"
|
||||
|
@ -1,5 +1,5 @@
|
||||
import tensorflow as tf
|
||||
import learning.tf_util as TFUtil
|
||||
import pybullet_envs.deep_mimic.learning.tf_util as TFUtil
|
||||
|
||||
NAME = "fc_2layers_1024units"
|
||||
|
||||
|
@ -1,4 +1,4 @@
|
||||
import learning.nets.fc_2layers_1024units as fc_2layers_1024units
|
||||
import pybullet_envs.deep_mimic.learning.nets.fc_2layers_1024units as fc_2layers_1024units
|
||||
|
||||
def build_net(net_name, input_tfs, reuse=False):
|
||||
net = None
|
||||
|
@ -2,12 +2,12 @@ import numpy as np
|
||||
import tensorflow as tf
|
||||
import copy
|
||||
|
||||
from learning.tf_agent import TFAgent
|
||||
from learning.solvers.mpi_solver import MPISolver
|
||||
import learning.tf_util as TFUtil
|
||||
import learning.nets.net_builder as NetBuilder
|
||||
from learning.tf_normalizer import TFNormalizer
|
||||
import learning.rl_util as RLUtil
|
||||
from pybullet_envs.deep_mimic.learning.tf_agent import TFAgent
|
||||
from pybullet_envs.deep_mimic.learning.solvers.mpi_solver import MPISolver
|
||||
import pybullet_envs.deep_mimic.learning.tf_util as TFUtil
|
||||
import pybullet_envs.deep_mimic.learning.nets.net_builder as NetBuilder
|
||||
from pybullet_envs.deep_mimic.learning.tf_normalizer import TFNormalizer
|
||||
import pybullet_envs.deep_mimic.learning.rl_util as RLUtil
|
||||
from pybullet_utils.logger import Logger
|
||||
import pybullet_utils.mpi_util as MPIUtil
|
||||
import pybullet_utils.math_util as MathUtil
|
||||
@ -350,4 +350,4 @@ class PGAgent(TFAgent):
|
||||
def _build_replay_buffer(self, buffer_size):
|
||||
super()._build_replay_buffer(buffer_size)
|
||||
self.replay_buffer.add_filter_key(self.EXP_ACTION_FLAG)
|
||||
return
|
||||
return
|
||||
|
@ -2,10 +2,10 @@ import numpy as np
|
||||
import copy as copy
|
||||
import tensorflow as tf
|
||||
|
||||
from learning.pg_agent import PGAgent
|
||||
from learning.solvers.mpi_solver import MPISolver
|
||||
import learning.tf_util as TFUtil
|
||||
import learning.rl_util as RLUtil
|
||||
from pybullet_envs.deep_mimic.learning.pg_agent import PGAgent
|
||||
from pybullet_envs.deep_mimic.learning.solvers.mpi_solver import MPISolver
|
||||
import pybullet_envs.deep_mimic.learning.tf_util as TFUtil
|
||||
import pybullet_envs.deep_mimic.learning.rl_util as RLUtil
|
||||
from pybullet_utils.logger import Logger
|
||||
import pybullet_utils.mpi_util as MPIUtil
|
||||
import pybullet_utils.math_util as MathUtil
|
||||
@ -365,4 +365,4 @@ class PPOAgent(PGAgent):
|
||||
self._actor_stepsize_ph: stepsize,
|
||||
}
|
||||
self.sess.run(self._actor_stepsize_update_op, feed)
|
||||
return
|
||||
return
|
||||
|
@ -6,10 +6,10 @@ import time
|
||||
from abc import ABC, abstractmethod
|
||||
from enum import Enum
|
||||
|
||||
from learning.path import *
|
||||
from learning.exp_params import ExpParams
|
||||
from learning.normalizer import Normalizer
|
||||
from learning.replay_buffer import ReplayBuffer
|
||||
from pybullet_envs.deep_mimic.learning.path import *
|
||||
from pybullet_envs.deep_mimic.learning.exp_params import ExpParams
|
||||
from pybullet_envs.deep_mimic.learning.normalizer import Normalizer
|
||||
from pybullet_envs.deep_mimic.learning.replay_buffer import ReplayBuffer
|
||||
from pybullet_utils.logger import Logger
|
||||
import pybullet_utils.mpi_util as MPIUtil
|
||||
import pybullet_utils.math_util as MathUtil
|
||||
|
@ -1,7 +1,7 @@
|
||||
import numpy as np
|
||||
import learning.agent_builder as AgentBuilder
|
||||
import learning.tf_util as TFUtil
|
||||
from learning.rl_agent import RLAgent
|
||||
import pybullet_envs.deep_mimic.learning.agent_builder as AgentBuilder
|
||||
import pybullet_envs.deep_mimic.learning.tf_util as TFUtil
|
||||
from pybullet_envs.deep_mimic.learning.rl_agent import RLAgent
|
||||
from pybullet_utils.logger import Logger
|
||||
import pybullet_data
|
||||
|
||||
|
@ -1,12 +1,12 @@
|
||||
from mpi4py import MPI
|
||||
import tensorflow as tf
|
||||
import numpy as np
|
||||
import learning.tf_util as TFUtil
|
||||
import pybullet_envs.deep_mimic.learning.tf_util as TFUtil
|
||||
import pybullet_utils.math_util as MathUtil
|
||||
import pybullet_utils.mpi_util as MPIUtil
|
||||
from pybullet_utils.logger import Logger
|
||||
|
||||
from learning.solvers.solver import Solver
|
||||
from pybullet_envs.deep_mimic.learning.solvers.solver import Solver
|
||||
|
||||
class MPISolver(Solver):
|
||||
CHECK_SYNC_ITERS = 1000
|
||||
|
@ -2,9 +2,9 @@ import numpy as np
|
||||
import tensorflow as tf
|
||||
from abc import abstractmethod
|
||||
|
||||
from learning.rl_agent import RLAgent
|
||||
from pybullet_envs.deep_mimic.learning.rl_agent import RLAgent
|
||||
from pybullet_utils.logger import Logger
|
||||
from learning.tf_normalizer import TFNormalizer
|
||||
from pybullet_envs.deep_mimic.learning.tf_normalizer import TFNormalizer
|
||||
|
||||
class TFAgent(RLAgent):
|
||||
RESOURCE_SCOPE = 'resource'
|
||||
|
@ -1,7 +1,7 @@
|
||||
import numpy as np
|
||||
import copy
|
||||
import tensorflow as tf
|
||||
from learning.normalizer import Normalizer
|
||||
from pybullet_envs.deep_mimic.learning.normalizer import Normalizer
|
||||
|
||||
class TFNormalizer(Normalizer):
|
||||
|
||||
|
@ -6,7 +6,7 @@ os.sys.path.insert(0,parentdir)
|
||||
print("parentdir=",parentdir)
|
||||
import json
|
||||
from pybullet_envs.deep_mimic.learning.rl_world import RLWorld
|
||||
from learning.ppo_agent import PPOAgent
|
||||
from pybullet_envs.deep_mimic.learning.ppo_agent import PPOAgent
|
||||
|
||||
import pybullet_data
|
||||
from pybullet_utils.arg_parser import ArgParser
|
||||
|
Loading…
Reference in New Issue
Block a user