Skip to content

Commit

Permalink
fix: remove singleton anti-pattern
Browse files Browse the repository at this point in the history
This commit removes the singleton pattern used in the package since
it is considered bad practice and resulted in some complex errors.
  • Loading branch information
rickstaa committed Aug 16, 2023
1 parent 2080fc3 commit 22d0e2e
Show file tree
Hide file tree
Showing 3 changed files with 13 additions and 44 deletions.
1 change: 0 additions & 1 deletion src/ros_gazebo_gym/common/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,4 +3,3 @@
"""

from ros_gazebo_gym.common.euler_angles import EulerAngles
from ros_gazebo_gym.common.singleton import Singleton
41 changes: 0 additions & 41 deletions src/ros_gazebo_gym/common/singleton.py

This file was deleted.

15 changes: 13 additions & 2 deletions src/ros_gazebo_gym/task_envs/panda/panda_reach.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@
import tf2_geometry_msgs
from geometry_msgs.msg import Pose, PoseStamped, Quaternion, Vector3
from gym import spaces, utils
from ros_gazebo_gym.common import Singleton
from ros_gazebo_gym.common.functions import (
flatten_list,
gripper_width_2_finger_joints_positions,
Expand Down Expand Up @@ -86,7 +85,7 @@
#################################################
# Panda reach environment class #################
#################################################
class PandaReachEnv(PandaEnv, utils.EzPickle, metaclass=Singleton):
class PandaReachEnv(PandaEnv, utils.EzPickle):
"""Class that provides all the methods used for the algorithm training.
Attributes:
Expand All @@ -95,6 +94,8 @@ class PandaReachEnv(PandaEnv, utils.EzPickle, metaclass=Singleton):
goal (:obj:`geometry_msgs.PoseStamped`): The current goal.
"""

_instance_count = 0 # Counts the number of instances that were created.

def __init__( # noqa: C901
self,
control_type="effort",
Expand Down Expand Up @@ -127,6 +128,16 @@ def __init__( # noqa: C901
easily extended to work with multiple waypoints by modifying the
:obj:`PandaReachEnv~._create_action_space` method.
"""
self.__class__._instance_count += 1
if self.__class__._instance_count > 1:
rospy.logwarn(
"You are trying to create multiple instances of the "
f"{self.__class__.__name__} class. Unfortunately, this is not yet "
"been implemented and will cause unexpected behaviour. As a result, "
"the script will be shut down. Feel free to open a pull request if "
"you want to implement this functionality."
)

utils.EzPickle.__init__(
**locals()
) # Makes sure the env is pickable when it wraps C++ code.
Expand Down

0 comments on commit 22d0e2e

Please sign in to comment.