Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Ci #119

Merged
merged 7 commits into from
Jan 3, 2024
Merged

Ci #119

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
88 changes: 88 additions & 0 deletions .github/workflows/pycram-ci.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
name: CI standalone
defaults:
run:
shell: bash -ieo pipefail {0}
on:
push:
branches:
- dev
- master
pull_request:
branches:
- master
- dev
jobs:
Build_and_run_Tests:
runs-on: ubuntu-20.04
steps:
- name: Checkout pycram
uses: actions/checkout@v3
with:
path: 'ros_ws/src/pycram'
repository: ${{github.repository}}
ref: ${{github.ref}}
submodules: recursive

- name: Checkout iai_maps
uses: actions/checkout@v3
with:
path: 'ros_ws/src/iai_maps'
repository: code-iai/iai_maps
ref: master
- name: Checkout iai_robots
uses: actions/checkout@v3
with:
path: 'ros_ws/src/iai_robots'
repository: code-iai/iai_robots
ref: master
- name: Checkout pr2_common
uses: actions/checkout@v3
with:
path: 'ros_ws/src/pr2_common'
repository: PR2/pr2_common
ref: master
- name: Checkout kdl_ik_service
uses: actions/checkout@v3
with:
path: 'ros_ws/src/kdl_ik_service'
repository: cram2/kdl_ik_service
ref: master
- name: Checkout pr2_kinematics
uses: actions/checkout@v3
with:
path: 'ros_ws/src/pr2_kinematics'
repository: PR2/pr2_kinematics
ref: kinetic-devel
- name: install ros and deps
uses: betwo/github-setup-catkin@master
env:
ACTIONS_ALLOW_UNSECURE_COMMANDS: true
with:
# Version range or exact version of ROS version to use, using SemVer's version range syntax.
ros-version: noetic
build-tool: 'catkin_tools'
# Root directory of the catkin workspace
workspace: $GITHUB_WORKSPACE/ros_ws
- name: build and source workspace
run: |
cd ros_ws
catkin_make
echo 'export ROS_HOSTNAME=localhost' >> ~/.bashrc
echo 'source $GITHUB_WORKSPACE/ros_ws/devel/setup.bash' >> ~/.bashrc
- name: Install requirements
run: |
cd $GITHUB_WORKSPACE/ros_ws/src/pycram
sudo pip3 install -r requirements.txt
- name: upgrade numpy
run: |
sudo pip3 install --upgrade numpy
- name: install additional requirements
run: |
sudo pip3 install pytest pyjpt mlflow
- name: start roscore
run: |
roslaunch pycram ik_and_description.launch &
- name: Run Tests
run: |
roscd pycram
pytest -v test
3 changes: 1 addition & 2 deletions launch/ik_and_description.launch
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,7 @@
<include file="$(find pr2_arm_kinematics)/launch/pr2_ik_larm_node.launch"/>
<include file="$(find pr2_arm_kinematics)/launch/pr2_ik_rarm_node.launch"/>
<param name="robot_description"
command="$(find xacro)/xacro
'$(find pr2_description)/robots/pr2.urdf.xacro'"/>
textfile="$(find pycram)/resources/pr2.urdf"/>
</group>
<!-- Boxy -->
<group if="$(eval robot == 'boxy')">
Expand Down
6 changes: 4 additions & 2 deletions requirements.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,12 +4,14 @@ rospkg~=1.4.0
roslibpy~=1.2.1
# rospy~=1.14.11
pathlib~=1.0.1
numpy~=1.19.5
numpy~=1.22.2
pytransform3d~=1.9.1
# tf~=1.12.1
# actionlib~=1.12.1
urdf-parser-py~=0.0.3
graphviz
anytree>=2.8.0
SQLAlchemy>=2.0.9

tqdm==4.66.1
psutil==5.9.7
lxml==4.5.1
2 changes: 1 addition & 1 deletion src/pycram/bullet_world.py
Original file line number Diff line number Diff line change
Expand Up @@ -408,7 +408,7 @@ def __enter__(self):
def __exit__(self, *args):
if not self.prev_world == None:
BulletWorld.current_bullet_world = self.prev_world
BulletWorld.current_bullet_world.world_sync.pause_sync = False
BulletWorld.current_bullet_world.world_sync.pause_sync = False


class WorldSync(threading.Thread):
Expand Down
3 changes: 2 additions & 1 deletion src/pycram/orm/base.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
"""Implementation of base classes for orm modelling."""
import datetime
import getpass
import os
from typing import Optional

Expand Down Expand Up @@ -136,7 +137,7 @@ class ProcessMetaData(MappedAsDataclass, _Base):
init=False)
"""The timestamp where this row got created. This is an aid for versioning."""

created_by: Mapped[str] = mapped_column(default=os.getlogin(), init=False)
created_by: Mapped[str] = mapped_column(default=getpass.getuser(), init=False)
"""The user that created the experiment."""

description: Mapped[str] = mapped_column(init=False)
Expand Down
43 changes: 43 additions & 0 deletions test/bullet_world_testcase.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
import unittest

import numpy as np
import rospkg

from pycram.bullet_world import BulletWorld, Object, fix_missing_inertial
from pycram.pose import Pose
from pycram.robot_descriptions import robot_description
from pycram.process_module import ProcessModule
from pycram.enums import ObjectType
import os
import tf


class BulletWorldTestCase(unittest.TestCase):

world: BulletWorld

@classmethod
def setUpClass(cls):
cls.world = BulletWorld("DIRECT")
cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + ".urdf")
cls.kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen.urdf")
cls.milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9]))
cls.cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", pose=Pose([1.3, 0.7, 0.95]))
ProcessModule.execution_delay = False

def setUp(self):
self.world.reset_bullet_world()

# DO NOT WRITE TESTS HERE!!!
# Test related to the BulletWorld should be written in test_bullet_world.py
# Tests in here would not be properly executed in the CI

def tearDown(self):
self.world.reset_bullet_world()

@classmethod
def tearDownClass(cls):
cls.world.exit()



4 changes: 2 additions & 2 deletions test/local_transformer_tests.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,10 @@
from src.pycram.local_transformer import LocalTransformer
from pycram.robot_descriptions import robot_description
from pycram.pose import Pose, Transform
import test_bullet_world
import bullet_world_testcase


class TestLocalTransformer(test_bullet_world.BulletWorldTest):
class TestLocalTransformer(test_bullet_world.BulletWorldTestCase):

def test_singelton(self):
l1 = LocalTransformer()
Expand Down
4 changes: 2 additions & 2 deletions test/test_action_designator.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,11 @@
from pycram.pose import Pose
from pycram.enums import ObjectType
import pycram.enums
import test_bullet_world
from bullet_world_testcase import BulletWorldTestCase
import numpy as np


class TestActionDesignatorGrounding(test_bullet_world.BulletWorldTest):
class TestActionDesignatorGrounding(BulletWorldTestCase):
"""Testcase for the grounding methods of action designators."""

def test_move_torso(self):
Expand Down
41 changes: 11 additions & 30 deletions test/test_bullet_world.py
Original file line number Diff line number Diff line change
@@ -1,31 +1,15 @@
import unittest

import numpy as np
from pycram.bullet_world import BulletWorld, Object, fix_missing_inertial
import rospkg

from bullet_world_testcase import BulletWorldTestCase
from pycram.pose import Pose
from pycram.robot_descriptions import robot_description
from pycram.process_module import ProcessModule
from pycram.enums import ObjectType
import os
import numpy as np
from pycram.bullet_world import fix_missing_inertial
import xml.etree.ElementTree as ET
import tf


class BulletWorldTest(unittest.TestCase):

world: BulletWorld

@classmethod
def setUpClass(cls):
cls.world = BulletWorld("DIRECT")
cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + ".urdf")
cls.kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen.urdf")
cls.milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9]))
cls.cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", pose=Pose([1.3, 0.7, 0.95]))
ProcessModule.execution_delay = False

def setUp(self):
self.world.reset_bullet_world()
class BulletWorldTest(BulletWorldTestCase):

def test_object_movement(self):
self.milk.set_position(Pose([0, 1, 1]))
Expand All @@ -38,21 +22,18 @@ def test_robot_orientation(self):
self.robot.set_orientation(Pose(orientation=[0, 0, 1, 1]))
self.assertEqual(self.robot.get_link_position('head_pan_link').z, head_position)

def tearDown(self):
self.world.reset_bullet_world()

@classmethod
def tearDownClass(cls):
cls.world.exit()


class XMLTester(unittest.TestCase):

def setUp(self) -> None:
self.urdf_string = open(os.path.join("..", "resources", "pr2.urdf"), "r").read()
rospack = rospkg.RosPack()
filename = rospack.get_path('pycram') + '/resources/' + 'pr2.urdf'
with open(filename, "r") as f:
self.urdf_string = f.read()

def test_inertial(self):
result = fix_missing_inertial(self.urdf_string)
resulting_tree = ET.ElementTree(ET.fromstring(result))
for element in resulting_tree.iter("link"):
self.assertTrue(len([*element.iter("inertial")]) > 0)

4 changes: 2 additions & 2 deletions test/test_bullet_world_reasoning.py
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
import time

from test_bullet_world import BulletWorldTest
from bullet_world_testcase import BulletWorldTestCase
import pycram.bullet_world_reasoning as btr
from pycram.pose import Pose
from pycram.robot_descriptions import robot_description


class TestBulletWorldReasoning(BulletWorldTest):
class TestCaseBulletWorldReasoning(BulletWorldTestCase):

def test_contact(self):
self.milk.set_pose(Pose([1, 1, 1]))
Expand Down
4 changes: 2 additions & 2 deletions test/test_costmaps.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
from test_bullet_world import BulletWorldTest
from bullet_world_testcase import BulletWorldTestCase
from pycram.costmaps import OccupancyCostmap
from pycram.pose import Pose
import numpy as np


class TestCostmaps(BulletWorldTest):
class TestCostmapsCase(BulletWorldTestCase):

def test_raytest_bug(self):
for i in range(30):
Expand Down
4 changes: 2 additions & 2 deletions test/test_location_designator.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,10 @@
from pycram.process_module import simulated_robot
from pycram.pose import Pose
import pycram.enums
import test_bullet_world
from bullet_world_testcase import BulletWorldTestCase


class TestActionDesignatorGrounding(test_bullet_world.BulletWorldTest):
class TestActionDesignatorGrounding(BulletWorldTestCase):

def test_reachability(self):
self.robot.set_joint_state(robot_description.torso_joint, 0.3)
Expand Down
4 changes: 2 additions & 2 deletions test/test_object_designator.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
import unittest
import test_bullet_world
from bullet_world_testcase import BulletWorldTestCase
from pycram.designators.object_designator import *
from pycram.enums import ObjectType


class TestObjectDesignator(test_bullet_world.BulletWorldTest):
class TestObjectDesignator(BulletWorldTestCase):

def test_object_grounding(self):
description = ObjectDesignatorDescription(["milk"], [ObjectType.MILK])
Expand Down
6 changes: 3 additions & 3 deletions test/test_orm.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
import pycram.orm.task
import pycram.task
import pycram.task
import test_bullet_world
from bullet_world_testcase import BulletWorldTestCase
import test_task_tree
from pycram.designators import action_designator, object_designator
from pycram.pose import Pose
Expand Down Expand Up @@ -148,7 +148,7 @@ def test_meta_data_alternation(self):
self.assertEqual(metadata_result.description, "Test")


class ORMObjectDesignatorTestCase(test_bullet_world.BulletWorldTest):
class ORMObjectDesignatorTestCase(BulletWorldTestCase):
"""Test ORM functionality with a plan including object designators. """

engine: sqlalchemy.engine.Engine
Expand Down Expand Up @@ -251,7 +251,7 @@ def test_task_tree_node_parents(self):
self.assertTrue([r[i].parent == r[r[i].parent_id - 1] for i in range(len(r)) if r[i].parent_id is not None])


class MotionDesigTest(test_bullet_world.BulletWorldTest):
class MotionDesigTest(BulletWorldTestCase):
engine: sqlalchemy.engine.Engine
session: sqlalchemy.orm.Session

Expand Down
4 changes: 2 additions & 2 deletions test/test_task_tree.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,12 +4,12 @@
from pycram.task import with_tree
import unittest
import anytree
import test_bullet_world
from bullet_world_testcase import BulletWorldTestCase
import pycram.plan_failures
from pycram.designators import object_designator, action_designator


class TaskTreeTestCase(test_bullet_world.BulletWorldTest):
class TaskTreeTestCase(BulletWorldTestCase):

@with_tree
def plan(self):
Expand Down
Loading