Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
22 changes: 15 additions & 7 deletions robo_gym/envs/mir100/mir100.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
import gymnasium as gym
from gymnasium import spaces, logger
from gymnasium.utils import seeding
from robo_gym.utils import utils, mir100_utils
from robo_gym.utils import utils, mir100_utils, cmd_utils
from robo_gym.utils.exceptions import InvalidStateError, RobotServerError
import robo_gym_server_modules.robot_server.client as rs_client
from robo_gym.envs.simulation_wrapper import Simulation
Expand Down Expand Up @@ -441,19 +441,21 @@ def _reward(self, rs_state, action):


class NoObstacleNavigationMir100Sim(Simulation, NoObstacleNavigationMir100):
cmd = "roslaunch mir100_robot_server sim_robot_server.launch"

def __init__(
self, ip=None, lower_bound_port=None, upper_bound_port=None, gui=False, **kwargs
):
self.cmd = cmd_utils.construct_roslaunch_command(
module='mir100_robot_server',
launch_file='sim_robot_server.launch'
)

Simulation.__init__(
self, self.cmd, ip, lower_bound_port, upper_bound_port, gui, **kwargs
)
NoObstacleNavigationMir100.__init__(
self, rs_address=self.robot_server_ip, **kwargs
)


class NoObstacleNavigationMir100Rob(NoObstacleNavigationMir100):
real_robot = True

Expand Down Expand Up @@ -692,18 +694,24 @@ def _generate_obstacles_positions(


class ObstacleAvoidanceMir100Sim(Simulation, ObstacleAvoidanceMir100):
cmd = "roslaunch mir100_robot_server sim_robot_server.launch world_name:=lab_6x8.world gazebo_gui:=true"

def __init__(
self, ip=None, lower_bound_port=None, upper_bound_port=None, gui=False, **kwargs
):
self.cmd = cmd_utils.construct_roslaunch_command(
module='mir100_robot_server',
launch_file='sim_robot_server.launch',
launch_args={
'world_name': 'lab_6x8.world',
'gazebo_gui': True,
}
)

Simulation.__init__(
self, self.cmd, ip, lower_bound_port, upper_bound_port, gui, **kwargs
)
ObstacleAvoidanceMir100.__init__(
self, rs_address=self.robot_server_ip, **kwargs
)


class ObstacleAvoidanceMir100Rob(ObstacleAvoidanceMir100):
real_robot = True
35 changes: 20 additions & 15 deletions robo_gym/envs/ur/ur_avoidance_basic.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
from __future__ import annotations
import numpy as np
from typing import Tuple, Any
from robo_gym.utils import cmd_utils
from robo_gym_server_modules.robot_server.grpc_msgs.python import robot_server_pb2
from robo_gym.envs.simulation_wrapper import Simulation
from robo_gym.envs.ur.ur_base_avoidance_env import URBaseAvoidanceEnv
Expand Down Expand Up @@ -190,19 +191,6 @@ def step(self, action) -> Tuple[np.array, float, bool, bool, dict]:


class BasicAvoidanceURSim(BasicAvoidanceUR, Simulation):
cmd = "roslaunch ur_robot_server ur_robot_server.launch \
world_name:=tabletop_sphere50.world \
reference_frame:=base_link \
max_velocity_scale_factor:=0.2 \
action_cycle_rate:=20 \
rviz_gui:=false \
gazebo_gui:=true \
objects_controller:=true \
rs_mode:=1moving2points \
n_objects:=1.0 \
object_0_model_name:=sphere50 \
object_0_frame:=target"

def __init__(
self,
ip=None,
Expand All @@ -212,15 +200,32 @@ def __init__(
ur_model="ur5",
**kwargs,
):
self.cmd = self.cmd + " " + "ur_model:=" + ur_model
self.cmd = cmd_utils.construct_roslaunch_command(
module='ur_robot_server',
launch_file='ur_robot_server.launch',
launch_args={
'world_name': 'tabletop_sphere50.world',
'reference_frame': 'base_link',
'max_velocity_scale_factor': 0.2,
'action_cycle_rate': 20,
'rviz_gui': False,
'gazebo_gui': True,
'objects_controller': True,
'rs_mode': '1moving2points',
'n_objects': 1.0,
'object_0_model_name': 'sphere50',
'object_0_frame': 'target',
'ur_model': ur_model
}
)

Simulation.__init__(
self, self.cmd, ip, lower_bound_port, upper_bound_port, gui, **kwargs
)
BasicAvoidanceUR.__init__(
self, rs_address=self.robot_server_ip, ur_model=ur_model, **kwargs
)


class BasicAvoidanceURRob(BasicAvoidanceUR):
real_robot = True

Expand Down
71 changes: 40 additions & 31 deletions robo_gym/envs/ur/ur_avoidance_raad.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
import numpy as np
import gymnasium as gym
from typing import Tuple, Any
from robo_gym.utils import cmd_utils
from robo_gym_server_modules.robot_server.grpc_msgs.python import robot_server_pb2
from robo_gym.envs.simulation_wrapper import Simulation
from robo_gym.envs.ur.ur_base_avoidance_env import URBaseAvoidanceEnv
Expand Down Expand Up @@ -386,19 +387,6 @@ def _get_joint_positions_as_array(self) -> np.ndarray:


class AvoidanceRaad2022URSim(AvoidanceRaad2022UR, Simulation):
cmd = "roslaunch ur_robot_server ur_robot_server.launch \
world_name:=tabletop_sphere50.world \
reference_frame:=base_link \
max_velocity_scale_factor:=0.2 \
action_cycle_rate:=20 \
rviz_gui:=false \
gazebo_gui:=true \
objects_controller:=true \
rs_mode:=1moving2points \
n_objects:=1.0 \
object_0_model_name:=sphere50 \
object_0_frame:=target"

def __init__(
self,
ip=None,
Expand All @@ -408,15 +396,32 @@ def __init__(
ur_model="ur5",
**kwargs,
):
self.cmd = self.cmd + " " + "ur_model:=" + ur_model
self.cmd = cmd_utils.construct_roslaunch_command(
module='ur_robot_server',
launch_file='ur_robot_server.launch',
launch_args={
'world_name': 'tabletop_sphere50.world',
'reference_frame': 'base_link',
'max_velocity_scale_factor': 0.2,
'action_cycle_rate': 20,
'rviz_gui': False,
'gazebo_gui': True,
'objects_controller': True,
'rs_mode': '1moving2points',
'n_objects': 1.0,
'object_0_model_name': 'sphere50',
'object_0_frame': 'target',
'ur_model': ur_model
}
)

Simulation.__init__(
self, self.cmd, ip, lower_bound_port, upper_bound_port, gui, **kwargs
)
AvoidanceRaad2022UR.__init__(
self, rs_address=self.robot_server_ip, ur_model=ur_model, **kwargs
)


class AvoidanceRaad2022URRob(AvoidanceRaad2022UR):
real_robot = True

Expand Down Expand Up @@ -477,20 +482,6 @@ def reset(


class AvoidanceRaad2022TestURSim(AvoidanceRaad2022TestUR, Simulation):
cmd = "roslaunch ur_robot_server ur_robot_server.launch \
world_name:=tabletop_sphere50.world \
reference_frame:=base_link \
max_velocity_scale_factor:=0.2 \
action_cycle_rate:=20 \
rviz_gui:=false \
gazebo_gui:=true \
objects_controller:=true \
rs_mode:=1moving2points \
n_objects:=1.0 \
object_trajectory_file_name:=splines_ur5 \
object_0_model_name:=sphere50 \
object_0_frame:=target"

def __init__(
self,
ip=None,
Expand All @@ -500,15 +491,33 @@ def __init__(
ur_model="ur5",
**kwargs,
):
self.cmd = self.cmd + " " + "ur_model:=" + ur_model
self.cmd = cmd_utils.construct_roslaunch_command(
module='ur_robot_server',
launch_file='ur_robot_server.launch',
launch_args={
'world_name': 'tabletop_sphere50.world',
'reference_frame': 'base_link',
'max_velocity_scale_factor': 0.2,
'action_cycle_rate': 20,
'rviz_gui': False,
'gazebo_gui': True,
'objects_controller': True,
'rs_mode': '1moving2points',
'n_objects': 1.0,
'object_trajectory_file_name': 'splines_ur5',
'object_0_model_name': 'sphere50',
'object_0_frame': 'target',
'ur_model': ur_model
}
)

Simulation.__init__(
self, self.cmd, ip, lower_bound_port, upper_bound_port, gui, **kwargs
)
AvoidanceRaad2022TestUR.__init__(
self, rs_address=self.robot_server_ip, ur_model=ur_model, **kwargs
)


class AvoidanceRaad2022TestURRob(AvoidanceRaad2022TestUR):
real_robot = True

Expand Down
30 changes: 16 additions & 14 deletions robo_gym/envs/ur/ur_base_env.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,11 @@

import copy
from typing import Tuple, Any

import gymnasium as gym
import numpy as np

import robo_gym_server_modules.robot_server.client as rs_client
from robo_gym.envs.simulation_wrapper import Simulation
from robo_gym.utils import ur_utils
from robo_gym.utils import cmd_utils, ur_utils
from robo_gym.utils.exceptions import (
InvalidStateError,
RobotServerError,
Expand Down Expand Up @@ -439,15 +437,6 @@ def _get_action_space(self) -> gym.spaces.Box:


class EmptyEnvironmentURSim(URBaseEnv, Simulation):
cmd = "roslaunch ur_robot_server ur_robot_server.launch \
world_name:=empty.world \
reference_frame:=base_link \
max_velocity_scale_factor:=0.2 \
action_cycle_rate:=20 \
rviz_gui:=true \
gazebo_gui:=true \
rs_mode:=only_robot"

def __init__(
self,
ip=None,
Expand All @@ -457,15 +446,28 @@ def __init__(
ur_model="ur5",
**kwargs,
):
self.cmd = self.cmd + " " + "ur_model:=" + ur_model
self.cmd = cmd_utils.construct_roslaunch_command(
module='ur_robot_server',
launch_file='ur_robot_server.launch',
launch_args={
'world_name': 'empty.world',
'reference_frame': 'base_link',
'max_velocity_scale_factor': 0.2,
'action_cycle_rate': 20,
'rviz_gui': True,
'gazebo_gui': True,
'rs_mode': 'only_robot',
'ur_model': ur_model,
}
)

Simulation.__init__(
self, self.cmd, ip, lower_bound_port, upper_bound_port, gui, **kwargs
)
URBaseEnv.__init__(
self, rs_address=self.robot_server_ip, ur_model=ur_model, **kwargs
)


class EmptyEnvironmentURRob(URBaseEnv):
real_robot = True

Expand Down
37 changes: 20 additions & 17 deletions robo_gym/envs/ur/ur_ee_positioning.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,9 @@
import gymnasium as gym
import numpy as np
from scipy.spatial.transform import Rotation as R

from robo_gym.envs.simulation_wrapper import Simulation
from robo_gym.envs.ur.ur_base_env import URBaseEnv
from robo_gym.utils import utils
from robo_gym.utils import utils, cmd_utils
from robo_gym.utils.exceptions import InvalidStateError, RobotServerError
from robo_gym_server_modules.robot_server.grpc_msgs.python import robot_server_pb2

Expand Down Expand Up @@ -485,19 +484,6 @@ def env_action_to_rs_action(self, action) -> np.array:


class EndEffectorPositioningURSim(EndEffectorPositioningUR, Simulation):
cmd = "roslaunch ur_robot_server ur_robot_server.launch \
world_name:=tabletop_sphere50_no_collision.world \
reference_frame:=base_link \
max_velocity_scale_factor:=0.1 \
action_cycle_rate:=10 \
rviz_gui:=true \
gazebo_gui:=true \
objects_controller:=true \
rs_mode:=1object \
n_objects:=1.0 \
object_0_model_name:=sphere50_no_collision \
object_0_frame:=target"

def __init__(
self,
ip=None,
Expand All @@ -507,15 +493,32 @@ def __init__(
ur_model="ur5",
**kwargs,
):
self.cmd = self.cmd + " " + "ur_model:=" + ur_model
self.cmd = cmd_utils.construct_roslaunch_command(
module='ur_robot_server',
launch_file='ur_robot_server.launch',
launch_args={
'world_name': 'tabletop_sphere50_no_collision.world',
'reference_frame': 'base_link',
'max_velocity_scale_factor': 0.1,
'action_cycle_rate': 10,
'rviz_gui': True,
'gazebo_gui': True,
'objects_controller': True,
'rs_mode': '1object',
'n_objects': 1.0,
'object_0_model_name': 'sphere50_no_collision',
'object_0_frame': 'target',
'ur_model': ur_model
}
)

Simulation.__init__(
self, self.cmd, ip, lower_bound_port, upper_bound_port, gui, **kwargs
)
EndEffectorPositioningUR.__init__(
self, rs_address=self.robot_server_ip, ur_model=ur_model, **kwargs
)


class EndEffectorPositioningURRob(EndEffectorPositioningUR):
real_robot = True

Expand Down
Loading