Skip to content

Commit

Permalink
Fix remainign tests that are not related to arm IK/planning
Browse files Browse the repository at this point in the history
  • Loading branch information
stepjam committed Jan 30, 2024
1 parent f8ed911 commit 740faea
Show file tree
Hide file tree
Showing 34 changed files with 163 additions and 905 deletions.
11 changes: 3 additions & 8 deletions .github/workflows/build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -32,15 +32,10 @@ jobs:
# start xvfb in the background
sudo /usr/bin/Xvfb $DISPLAY -screen 0 1280x1024x24 &
cur=`pwd`
wget http://www.coppeliarobotics.com/files/CoppeliaSim_Edu_V4_1_0_Ubuntu20_04.tar.xz
tar -xf CoppeliaSim_Edu_V4_1_0_Ubuntu20_04.tar.xz
export COPPELIASIM_ROOT="$cur/CoppeliaSim_Edu_V4_1_0_Ubuntu20_04"
wget https://downloads.coppeliarobotics.com/V4_6_0_rev16/CoppeliaSim_Player_V4_6_0_rev16_Ubuntu20_04.tar.xz
tar -xf CoppeliaSim_Player_V4_6_0_rev16_Ubuntu20_04.tar.xz
export COPPELIASIM_ROOT="$cur/CoppeliaSim_Player_V4_6_0_rev16_Ubuntu20_04"
echo $COPPELIASIM_ROOT
ls -al
export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:$COPPELIASIM_ROOT:$COPPELIASIM_ROOT/platforms
export QT_QPA_PLATFORM_PLUGIN_PATH=$COPPELIASIM_ROOT
pip3 install -r requirements.txt
pip3 install setuptools
pip3 install .
mv pyrep _pyrep
python3 -m unittest discover tests
30 changes: 10 additions & 20 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -22,36 +22,26 @@ PyRep has undergone a __MAJOR__ update, and is now compatible with the most rece
## Install

PyRep requires version **4.6.0** of CoppeliaSim. Download:
- [Ubuntu 16.04](https://www.coppeliarobotics.com/files/V4_1_0/CoppeliaSim_Edu_V4_1_0_Ubuntu16_04.tar.xz)
- [Ubuntu 18.04](https://www.coppeliarobotics.com/files/V4_1_0/CoppeliaSim_Edu_V4_1_0_Ubuntu18_04.tar.xz)
- [Ubuntu 20.04](https://www.coppeliarobotics.com/files/V4_1_0/CoppeliaSim_Edu_V4_1_0_Ubuntu20_04.tar.xz)

Once you have downloaded CoppeliaSim, you can pull PyRep from git:
- [Ubuntu 20.04](https://downloads.coppeliarobotics.com/V4_6_0_rev16/CoppeliaSim_Edu_V4_6_0_rev16_Ubuntu20_04.tar.xz)
- [Ubuntu 22.04](https://downloads.coppeliarobotics.com/V4_6_0_rev16/CoppeliaSim_Edu_V4_6_0_rev16_Ubuntu22_04.tar.xz)

Once you have downloaded CoppeliaSim, add the following to your *~/.bashrc* / *~/.zshrc* / etc file: (__NOTE__: the 'EDIT ME')
```bash
git clone https://github.com/stepjam/PyRep.git
cd PyRep
export COPPELIASIM_ROOT=EDIT/ME/PATH/TO/COPPELIASIM/INSTALL/DIR
```

Add the following to your *~/.bashrc* file: (__NOTE__: the 'EDIT ME' in the first line)
Install PyRep:

```bash
export COPPELIASIM_ROOT=EDIT/ME/PATH/TO/COPPELIASIM/INSTALL/DIR
export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:$COPPELIASIM_ROOT
export QT_QPA_PLATFORM_PLUGIN_PATH=$COPPELIASIM_ROOT
git clone https://github.com/stepjam/PyRep.git
cd PyRep
pip install .
```

__Remember to source your bashrc (`source ~/.bashrc`) or
zshrc (`source ~/.zshrc`) after this.

Finally install the python library:

Or you can install directly via pip
```bash
pip3 install -r requirements.txt
pip3 install .
pip install git+https://github.com/stepjam/PyRep.git
```

You should be good to go!
Try running one of the examples in the *examples/* folder.

_Although you can use CoppeliaSim on any platform, communication via PyRep is currently only supported on Linux._
Expand Down
9 changes: 6 additions & 3 deletions pyrep/backend/sim.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@ class SimBackend:
def __new__(cls):
# Singleton pattern
if cls._instance is None:
print('Creating the object')
cls._instance = super(SimBackend, cls).__new__(cls)
# Put any initialization here.
return cls._instance
Expand All @@ -35,6 +34,10 @@ def sim_ik_api(self):
def sim_ompl_api(self):
return self._sim_ompl

@property
def sim_vision_api(self):
return self._sim_vision

@property
def lib(self):
return lib
Expand All @@ -48,9 +51,9 @@ def simInitialize(self, appDir: str, verbosity: str):
self._sim = bridge.require('sim')
self._sim_ik = bridge.require('simIK')
self._sim_ompl = bridge.require('simOMPL')
self._sim_vision = bridge.require('simVision')
v = self._sim.getInt32Param(self._sim.intparam_program_full_version)
version = '.'.join(str(v // 100 ** (3 - i) % 100) for i in range(4))
print('CoppeliaSim version is:', version)
self._coppelia_version = '.'.join(str(v // 100 ** (3 - i) % 100) for i in range(4))
return self._sim

def create_ui_thread(self, headless: bool) -> threading.Thread:
Expand Down
3 changes: 3 additions & 0 deletions pyrep/backend/sim_const.py
Original file line number Diff line number Diff line change
Expand Up @@ -714,11 +714,14 @@
sim_autoquit = 262144

sim_jointmode_passive = 0
sim_jointmode_kinematic = 0
sim_jointmode_motion_deprecated = 1
sim_jointmode_ik = 2
sim_jointmode_reserved_previously_ikdependent = 3
sim_jointmode_dependent = 4
sim_jointmode_force = 5
sim_jointmode_dynamic = 5


sim_verbosity_useglobal = -1
sim_verbosity_none = 100
Expand Down
51 changes: 16 additions & 35 deletions pyrep/misc/signals.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
from pyrep.backend.sim import SimBackend
from pyrep.errors import PyRepError
from pyrep.backend import sim
from typing import Any
Expand All @@ -13,6 +14,7 @@ class Signal(object):

def __init__(self, name):
self._name = name
self._sim_api = SimBackend().sim_api

def set(self, value) -> None:
"""Sets the value of this signal.
Expand Down Expand Up @@ -46,57 +48,36 @@ class IntegerSignal(Signal):
"""An integer-type signal."""

def set(self, value) -> None:
sim.simSetIntegerSignal(self._name, value)
self._sim_api.setInt32Signal(self._name, value)

def get(self) -> int:
ret, value = sim.simGetIntegerSignal(self._name)
self._check_signal(ret, 'int')
return value
return self._sim_api.getInt32Signal(self._name)

def clear(self) -> int:
return sim.simClearIntegerSignal(self._name)
def clear(self) -> None:
self._sim_api.clearInt32Signal(self._name)


class FloatSignal(Signal):
"""An float-type signal."""
"""A float-type signal."""

def set(self, value) -> None:
sim.simSetFloatSignal(self._name, value)
self._sim_api.setFloatSignal(self._name, value)

def get(self) -> float:
ret, value = sim.simGetFloatSignal(self._name)
self._check_signal(ret, 'float')
return value

def clear(self) -> int:
return sim.simClearFloatSignal(self._name)
return self._sim_api.getFloatSignal(self._name)


class DoubleSignal(Signal):
"""An double-type signal."""

def set(self, value) -> None:
sim.simSetDoubleSignal(self._name, value)

def get(self) -> float:
ret, value = sim.simGetDoubleSignal(self._name)
self._check_signal(ret, 'double')
return value

def clear(self) -> int:
return sim.simClearDoubleSignal(self._name)
def clear(self) -> None:
self._sim_api.clearFloatSignal(self._name)


class StringSignal(Signal):
"""An string-type signal."""
"""A string-type signal."""

def set(self, value) -> None:
sim.simSetStringSignal(self._name, value)
self._sim_api.setStringSignal(self._name, value)

def get(self) -> str:
ret, value = sim.simGetStringSignal(self._name)
self._check_signal(ret, 'string')
return value
return self._sim_api.getStringSignal(self._name)

def clear(self) -> int:
return sim.simClearStringSignal(self._name)
def clear(self) -> None:
self._sim_api.clearStringSignal(self._name)
3 changes: 1 addition & 2 deletions pyrep/objects/force_sensor.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,7 @@ def create(cls, sensor_size=0.01) -> 'ForceSensor':
intParams = [0, 0, 0, 0, 0]
floatParams = [sensor_size, 0, 0, 0, 0]
sim_api = SimBackend().sim_api
handle = sim_api.createForceSensor(options=0, intParams=intParams,
floatParams=floatParams, color=None)
handle = sim_api.createForceSensor(0, intParams, floatParams)
return cls(handle)

def read(self) -> Tuple[List[float], List[float]]:
Expand Down
28 changes: 15 additions & 13 deletions pyrep/objects/joint.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
from typing import Tuple, List, Union
from pyrep.backend import sim_const as sim, utils
from pyrep.backend import sim_const as simc
from pyrep.backend import utils
from pyrep.backend.sim import SimBackend
from pyrep.const import JointType, JointMode
from pyrep.objects.object import Object, object_type_to_class
Expand Down Expand Up @@ -57,7 +58,7 @@ def set_joint_position(self, position: float,
self.set_model(True)

prior = self._sim_api.getModelProperty(self.get_handle())
p = prior | sim.sim_modelproperty_not_dynamic
p = prior | simc.sim_modelproperty_not_dynamic
# Disable the dynamics
self._sim_api.setModelProperty(self._handle, p)
sim_instance = SimBackend()
Expand Down Expand Up @@ -147,8 +148,8 @@ def get_joint_velocity(self) -> float:
:return: Velocity of the joint (linear or angular velocity depending
on the joint-type).
"""
return self._sim_api.getObjectFloatParameter(
self._handle, sim.sim_jointfloatparam_velocity)
return self._sim_api.getObjectFloatParam(
self._handle, simc.sim_jointfloatparam_velocity)

def get_joint_interval(self) -> Tuple[bool, List[float]]:
"""Retrieves the interval parameters of a joint.
Expand Down Expand Up @@ -183,39 +184,39 @@ def get_joint_upper_velocity_limit(self) -> float:
:return: The upper velocity limit.
"""
return self._sim_api.getObjectFloatParam(
self._handle, sim.sim_jointfloatparam_upper_limit)
self._handle, simc.sim_jointfloatparam_upper_limit)

def is_control_loop_enabled(self) -> bool:
"""Gets whether the control loop is enable.
:return: True if the control loop is enabled.
"""
return self._sim_api.getObjectInt32Param(
self._handle, sim.sim_jointintparam_ctrl_enabled)
self._handle, simc.sim_jointintparam_ctrl_enabled)

def set_control_loop_enabled(self, value: bool) -> None:
"""Sets whether the control loop is enable.
:param value: The new value for the control loop state.
"""
self._sim_api.setObjectInt32Param(
self._handle, sim.sim_jointintparam_ctrl_enabled, value)
self._handle, simc.sim_jointintparam_ctrl_enabled, int(value))

def is_motor_enabled(self) -> bool:
"""Gets whether the motor is enable.
:return: True if the motor is enabled.
"""
return self._sim_api.getObjectInt32Param(
self._handle, sim.sim_jointintparam_motor_enabled)
self._handle, simc.sim_jointintparam_motor_enabled)

def set_motor_enabled(self, value: bool) -> None:
"""Sets whether the motor is enable.
:param value: The new value for the motor state.
"""
self._sim_api.setObjectInt32Param(
self._handle, sim.sim_jointintparam_motor_enabled, value)
self._handle, simc.sim_jointintparam_motor_enabled, int(value))

def is_motor_locked_at_zero_velocity(self) -> bool:
"""Gets if the motor is locked when target velocity is zero.
Expand All @@ -226,7 +227,7 @@ def is_motor_locked_at_zero_velocity(self) -> bool:
:return: If the motor will be locked at zero velocity.
"""
return self._sim_api.getObjectInt32Param(
self._handle, sim.sim_jointintparam_velocity_lock)
self._handle, simc.sim_jointintparam_velocity_lock)

def set_motor_locked_at_zero_velocity(self, value: bool) -> None:
"""Set if the motor is locked when target velocity is zero.
Expand All @@ -237,21 +238,22 @@ def set_motor_locked_at_zero_velocity(self, value: bool) -> None:
:param value: If the motor should be locked at zero velocity.
"""
self._sim_api.setObjectInt32Param(
self._handle, sim.sim_jointintparam_velocity_lock, value)
self._handle, simc.sim_jointintparam_velocity_lock, int(value))

def get_joint_mode(self) -> JointMode:
"""Retrieves the operation mode of the joint.
:return: The joint mode.
"""
return JointMode(self._sim_api.getJointMode(self._handle))
mode, _ = self._sim_api.getJointMode(self._handle)
return JointMode(mode)

def set_joint_mode(self, value: JointMode) -> None:
"""Sets the operation mode of the joint.
:param value: The new joint mode value.
"""
self._sim_api.setJointMode(self._handle, value.value)
self._sim_api.setJointMode(self._handle, int(value.value), 0)


object_type_to_class[ObjectType.JOINT] = Joint
12 changes: 6 additions & 6 deletions pyrep/objects/light.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,12 +21,12 @@ def _get_requested_type(self) -> ObjectType:
def turn_on(self):
""" Turn the light on.
"""
self._sim_api.setLightParameters(self._handle, True)
self._sim_api.setLightParameters(self._handle, 1, None, None, None)

def turn_off(self):
""" Turn the light off.
"""
self._sim_api.setLightParameters(self._handle, False)
self._sim_api.setLightParameters(self._handle, 0, None, None, None)

def is_on(self):
""" Determines whether the light is on.
Expand All @@ -46,23 +46,23 @@ def get_diffuse(self):
""" Get the diffuse colors of the light.
return: 3-vector np.array of diffuse colors
"""
return np.asarray(self._sim_api.getLightParameters(self._handle)[1])
return np.asarray(self._sim_api.getLightParameters(self._handle)[2])

def set_diffuse(self, diffuse):
""" Set the diffuse colors of the light.
"""
self._sim_api.setLightParameters(self._handle, self.is_on(), list(diffuse))
self._sim_api.setLightParameters(self._handle, self.is_on(), None, list(diffuse), None)

def get_specular(self):
""" Get the specular colors of the light.
return: 3-vector np.array of specular colors
"""
return np.asarray(self._sim_api.getLightParameters(self._handle)[2])
return np.asarray(self._sim_api.getLightParameters(self._handle)[3])

def set_specular(self, specular):
""" Set the specular colors of the light.
"""
self._sim_api.setLightParameters(self._handle, self.is_on(), specularPart=list(specular))
self._sim_api.setLightParameters(self._handle, self.is_on(), None, list(self.get_diffuse()), list(specular))

# Intensity Properties

Expand Down
14 changes: 6 additions & 8 deletions pyrep/objects/object.py
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@ def still_exists(self) -> bool:
:return: Whether the object exists or not.
"""
return self._sim_api.getObjectName(self._handle) != ''
return self._sim_api.isHandle(self._handle)

def get_name(self) -> str:
"""Gets the objects name in the scene.
Expand Down Expand Up @@ -295,10 +295,8 @@ def get_parent(self) -> Union['Object', None]:
:return: The parent of this object, or None if it doesn't have a parent.
"""
try:
handle = self._sim_api.getObjectParent(self._handle)
except RuntimeError:
# Most probably no parent.
handle = self._sim_api.getObjectParent(self._handle)
if handle < 0:
return None
object_type = ObjectType(self._sim_api.getObjectType(handle))
cls = object_type_to_class.get(object_type, Object)
Expand Down Expand Up @@ -539,7 +537,7 @@ def check_collision(self, obj: 'Object' = None) -> bool:
:return: If the object is colliding.
"""
handle = simc.sim_handle_all if obj is None else obj.get_handle()
return self._sim_api.checkCollision(self._handle, handle) == 1
return self._sim_api.checkCollision(self._handle, handle)[0] == 1

# === Model specific methods ===

Expand Down Expand Up @@ -740,8 +738,8 @@ def check_distance(self, other: 'Object') -> float:
:return: The distance between the objects.
"""
result, distance_data, object_handle_pair = self._sim_api.checkDistance(
self.get_handle(), other.get_handle(), -1)[6]
obj1x, obj1y, obj1z, obj2x, obj2y, obj2z = distance_data
self.get_handle(), other.get_handle(), -1)
obj1x, obj1y, obj1z, obj2x, obj2y, obj2z, _ = distance_data
return np.linalg.norm(np.array([obj1x, obj1y, obj1z]) - np.array([obj2x, obj2y, obj2z]))

def get_bullet_friction(self) -> float:
Expand Down
Loading

0 comments on commit 740faea

Please sign in to comment.