GymEnv¶
The GymEnv is a prepared environment for training and testing various robotic tasks. Visualized as a gym, it contains several specialized Workspaces, where the training can take place. * baskets, collabtable, darts, drawer, football, fridge, maze, stairs, table, verticalmaze
-
class
myGym.envs.gym_env.
GymEnv
(workspace='table', object_sampling_area=None, dimension_velocity=0.05, used_objects=None, num_objects_range=None, action_repeat=1, color_dict=None, robot='kuka', robot_position=[0.0, 0.0, 0.0], robot_orientation=[0, 0, 0], robot_action='step', robot_init_joint_poses=[], task_type='reach', num_subgoals=0, task_objects=['virtual_cube_holes'], reward_type='gt', reward='distance', distance_type='euclidean', active_cameras=None, dataset=False, obs_space=None, visualize=0, visgym=1, logdir=None, vae_path=None, yolact_path=None, yolact_config=None, **kwargs)[source]¶ Environment class for particular environment based on myGym basic environment classes
- Parameters:
- param workspace
(string) Workspace in gym, where training takes place (collabtable, maze, drawer, …)
- param object_sampling_area
(list of floats) Volume in the scene where objects can appear ([x,x,y,y,z,z])
- param dimension_velocity
(float) Maximum allowed velocity for robot movements in individual x,y,z axis
- param used_objects
(list of strings) Names of extra objects (not task objects) that can appear in the scene
- param num_objects_range
(list of ints) Minimum and maximum number of extra objects that may appear in the scene
- param action_repeat
(int) Amount of steps the robot takes between the simulation steps (updates)
- param color_dict
(dict) Dictionary of specified colors for chosen objects, Key: object name, Value: RGB color
- param robot
(string) Type of robot to train in the environment (kuka, panda, ur3, …)
- param robot_position
(list) Position of the robot’s base link in the coordinate frame of the environment ([x,y,z])
- param robot_orientation
(list) Orientation of the robot’s base link in the coordinate frame of the environment (Euler angles [x,y,z])
- param robot_action
(string) Mechanism of robot control (absolute, step, joints)
- param robot_init_joint_poses
(list) Configuration in which robot will be initialized in the environment. Specified either in joint space as list of joint poses or in the end-effector space as [x,y,z] coordinates.
- param task_type
(string) Type of learned task (reach, push, …)
- param num_subgoals
(int) Number of subgoals in task
- param task_objects
(list of strings) Objects that are relevant for performing the task
- param reward_type
(string) Type of reward signal source (gt, 3dvs, 2dvu)
- param reward
(string) Defines how to compute the reward
- param distance_type
(string) Way of calculating distances (euclidean, manhattan)
- param active_cameras
(int) The number of camera used to render and record images
- param dataset
(bool) Whether this environment serves for image dataset generation
- param obs_space
(string) Type of observation data. Specify “dict” for usage of HER training algorithm.
- param visualize
(bool) Whether to show helping visualization during training and testing of environment
- param visgym
(bool) Whether to visualize whole gym building and other tasks (final visualization)
- param logdir
(string) Directory for logging
- param vae_path
(string) Path to a trained VAE in 2dvu reward type
- param yolact_path
(string) Path to a trained Yolact in 3dvu reward type
- param yolact_config
(string) Path to saved Yolact config obj or name of an existing one in the data/Config script or None for autodetection
-
reset
(random_pos=True, hard=False, random_robot=False)[source]¶ Environment reset called at the beginning of an episode. Reset state of objects, robot, task and reward.
- Parameters:
- param random_pos
(bool) Whether to initiate objects to random locations in the scene
- param hard
(bool) Whether to do hard reset (resets whole pybullet scene)
- param random_robot
(bool) Whether to initiate robot in random pose
- Returns:
- return self._observation
(list) Observation data of the environment
-
get_observation
()[source]¶ Get observation data from the environment
- Returns:
- return observation
(array) Represented position of task relevant objects
-
step
(action)[source]¶ Environment step in simulation
- Parameters:
- param actions
(list) Action data to send to robot to perform movement in this step
- Returns:
- return self._observation
(list) Observation data from the environment after this step
- return reward
(float) Reward value assigned to this step
- return done
(bool) Whether this stop is episode’s final
- return info
(dict) Additional information about step