diff --git a/contrib/ros/envs/example_launchers/trpo_gazebo_sawyer_pnp.py b/contrib/ros/envs/example_launchers/trpo_gazebo_sawyer_pnp.py index 0f269077c..1f2b6f202 100644 --- a/contrib/ros/envs/example_launchers/trpo_gazebo_sawyer_pnp.py +++ b/contrib/ros/envs/example_launchers/trpo_gazebo_sawyer_pnp.py @@ -1,3 +1,5 @@ +import rospy + from rllab.baselines.linear_feature_baseline import LinearFeatureBaseline from rllab.envs.normalized_env import normalize from rllab.misc.instrument import run_experiment_lite @@ -10,6 +12,8 @@ def run_task(*_): + rospy.init_node('trpo_sim_sawyer_pnp_exp', anonymous=True) + env = TfEnv(normalize(PickAndPlaceEnv())) policy = GaussianMLPPolicy( diff --git a/contrib/ros/envs/example_launchers/trpo_gazebo_sawyer_push.py b/contrib/ros/envs/example_launchers/trpo_gazebo_sawyer_push.py index 96f1608be..f4520a9cc 100644 --- a/contrib/ros/envs/example_launchers/trpo_gazebo_sawyer_push.py +++ b/contrib/ros/envs/example_launchers/trpo_gazebo_sawyer_push.py @@ -1,3 +1,5 @@ +import rospy + from rllab.baselines.linear_feature_baseline import LinearFeatureBaseline from rllab.envs.normalized_env import normalize from rllab.misc.instrument import run_experiment_lite @@ -10,6 +12,8 @@ def run_task(*_): + rospy.init_node('trpo_sim_sawyer_push_exp', anonymous=True) + env = TfEnv(normalize(PushEnv())) policy = GaussianMLPPolicy( diff --git a/contrib/ros/envs/sawyer_env.py b/contrib/ros/envs/sawyer_env.py index 51e79fec2..f0586bc8f 100644 --- a/contrib/ros/envs/sawyer_env.py +++ b/contrib/ros/envs/sawyer_env.py @@ -79,7 +79,6 @@ def __init__(self, Serializable.quick_init(self, locals()) RosEnv.__init__(self) - rospy.init_node('SawyerEnv', anonymous=True) # Verify robot is enabled self._robot = Sawyer(