Skip to content

Commit c7361e0

Browse files
authored
Merge branch 'master' into start_full_configuration
2 parents ce42df4 + 7df15c8 commit c7361e0

File tree

13 files changed

+173
-51
lines changed

13 files changed

+173
-51
lines changed

.bumpversion.cfg

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
[bumpversion]
2-
current_version = 0.10.1
2+
current_version = 0.10.2
33
message = Bump version to {new_version}
44
commit = True
55
tag = True
@@ -15,4 +15,3 @@ replace = __version__ = '{new_version}'
1515
[bumpversion:file:CHANGELOG.rst]
1616
search = Unreleased
1717
replace = {new_version}
18-

.travis.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ script:
6060
- if [[ "$TRAVIS_PYTHON_VERSION" == "3.7" ]]; then
6161
python3 -m invoke lint || python -m invoke lint;
6262
fi
63-
- python3 -m invoke test --no-doctest || python -m invoke test --no-doctest
63+
- python3 -m invoke test || python -m invoke test
6464
- if [[ "$TRAVIS_GENERATE_DOCS" == "true" ]]; then
6565
python3 -m invoke docs || python -m invoke docs;
6666
fi

CHANGELOG.rst

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,13 +27,29 @@ Unreleased
2727
* ``Robot``: ``forward_kinematics`` returns now ``frame_WCF``
2828
* ``MoveItPlanner``: ``forward_kinematics`` takes now instance of ``Configuration`` and ``robot``
2929
* ``MoveItPlanner``: ``inverse_kinematics`` takes now instance of ``Configuration`` and ``robot``
30+
* Property :class:`compas_fab.robots.Robot.artist` does not try to scale robot
31+
geometry if links and/or joints are not defined.
3032

3133
**Removed**
3234

3335
**Fixed**
3436

37+
* Convert constraints on inverse kinematics and cartesian planner to ROS messages
38+
* Fix support for trajectory constraints on kinematic planner
39+
3540
**Deprecated**
3641

42+
0.10.2
43+
----------
44+
45+
**Added**
46+
47+
* Added Python 3.8 support
48+
49+
**Changed**
50+
51+
* Updated to COMPAS 0.13
52+
3753
0.10.1
3854
----------
3955

docs/conf.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@
2727
year = '2018'
2828
author = 'Gramazio Kohler Research'
2929
copyright = '{0}, {1}'.format(year, author)
30-
version = release = '0.10.1'
30+
version = release = '0.10.2'
3131

3232
pygments_style = 'sphinx'
3333
show_authors = True

pytest.ini

Lines changed: 0 additions & 3 deletions
This file was deleted.

requirements-dev.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@ flake8
77
autopep8
88
pylint
99
pytest
10+
pytest-cov
1011
isort
1112
twine
1213
-e .

setup.cfg

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@ exclude =
1717
convention = numpy
1818

1919
[tool:pytest]
20-
testpaths = tests
20+
testpaths = src tests
2121
norecursedirs =
2222
migrations
2323

@@ -28,9 +28,9 @@ python_files =
2828
addopts =
2929
-ra
3030
--strict
31-
--doctest-modules
3231
--doctest-glob=\*.rst
3332
--tb=short
33+
doctest_optionflags= NORMALIZE_WHITESPACE IGNORE_EXCEPTION_DETAIL ALLOW_UNICODE ALLOW_BYTES
3434

3535
[isort]
3636
force_single_line = True
@@ -40,3 +40,6 @@ default_section = THIRDPARTY
4040
forced_separate = test_compas_fab
4141
not_skip = __init__.py
4242
skip = migrations
43+
44+
[coverage:run]
45+
branch = True

setup.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@
1111

1212
requirements = [
1313
# Until COMPAS reaches 1.0, we pin major.minor and allow patch version updates
14-
'compas>=0.11,<0.12',
14+
'compas>=0.11,<0.14',
1515
'roslibpy>=0.7.1',
1616
'pyserial',
1717
]
@@ -63,6 +63,8 @@ def read(*names, **kwargs):
6363
'Programming Language :: Python :: 3.4',
6464
'Programming Language :: Python :: 3.5',
6565
'Programming Language :: Python :: 3.6',
66+
'Programming Language :: Python :: 3.7',
67+
'Programming Language :: Python :: 3.8',
6668
'Programming Language :: Python :: Implementation :: CPython',
6769
'Programming Language :: Python :: Implementation :: IronPython',
6870
'Topic :: Scientific/Engineering',

src/compas_fab/__version__.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
__title__ = 'compas_fab'
22
__description__ = 'Robotic fabrication package for the COMPAS Framework'
33
__url__ = 'https://github.com/compas-dev/compas_fab'
4-
__version__ = '0.10.1'
4+
__version__ = '0.10.2'
55
__author__ = 'Gramazio Kohler Research'
66
__author_email__ = '[email protected]'
77
__license__ = 'MIT license'

src/compas_fab/backends/ros/planner_backend_moveit.py

Lines changed: 32 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@
3333
from compas_fab.backends.ros.messages import PositionConstraint
3434
from compas_fab.backends.ros.messages import PositionIKRequest
3535
from compas_fab.backends.ros.messages import RobotState
36+
from compas_fab.backends.ros.messages import TrajectoryConstraints
3637
from compas_fab.backends.ros.planner_backend import PlannerBackend
3738
from compas_fab.backends.ros.planner_backend import ServiceDescription
3839
from compas_fab.robots import Configuration
@@ -113,6 +114,27 @@ def dispose_planner(self):
113114
if hasattr(self, 'attached_collision_object_topic') and self.attached_collision_object_topic:
114115
self.attached_collision_object_topic.unadvertise()
115116

117+
def _convert_constraints_to_rosmsg(self, constraints, header):
118+
"""Convert COMPAS FAB constraints into ROS Messages."""
119+
if not constraints:
120+
return None
121+
122+
ros_constraints = Constraints()
123+
for c in constraints:
124+
if c.type == c.JOINT:
125+
ros_constraints.joint_constraints.append(
126+
JointConstraint.from_joint_constraint(c))
127+
elif c.type == c.POSITION:
128+
ros_constraints.position_constraints.append(
129+
PositionConstraint.from_position_constraint(header, c))
130+
elif c.type == c.ORIENTATION:
131+
ros_constraints.orientation_constraints.append(
132+
OrientationConstraint.from_orientation_constraint(header, c))
133+
else:
134+
raise NotImplementedError
135+
136+
return ros_constraints
137+
116138
# ==========================================================================
117139
# planning services
118140
# ==========================================================================
@@ -134,6 +156,8 @@ def inverse_kinematics_async(self, callback, errback, robot, frame, group,
134156
aco = AttachedCollisionObject.from_attached_collision_mesh(acm)
135157
start_state.attached_collision_objects.append(aco)
136158

159+
constraints = self._convert_constraints_to_rosmsg(constraints, header)
160+
137161
ik_request = PositionIKRequest(group_name=group,
138162
robot_state=start_state,
139163
constraints=constraints,
@@ -184,6 +208,8 @@ def plan_cartesian_motion_async(self, callback, errback,
184208
aco = AttachedCollisionObject.from_attached_collision_mesh(acm)
185209
start_state.attached_collision_objects.append(aco)
186210

211+
path_constraints = self._convert_constraints_to_rosmsg(path_constraints, header)
212+
187213
request = dict(header=header,
188214
start_state=start_state,
189215
group_name=group,
@@ -243,38 +269,12 @@ def plan_motion_async(self, callback, errback,
243269
aco = AttachedCollisionObject.from_attached_collision_mesh(acm)
244270
start_state.attached_collision_objects.append(aco)
245271

246-
# goal constraints
247-
constraints = Constraints()
248-
for c in goal_constraints:
249-
if c.type == c.JOINT:
250-
constraints.joint_constraints.append(
251-
JointConstraint.from_joint_constraint(c))
252-
elif c.type == c.POSITION:
253-
constraints.position_constraints.append(
254-
PositionConstraint.from_position_constraint(header, c))
255-
elif c.type == c.ORIENTATION:
256-
constraints.orientation_constraints.append(
257-
OrientationConstraint.from_orientation_constraint(header, c))
258-
else:
259-
raise NotImplementedError
260-
goal_constraints = [constraints]
261-
262-
# path constraints
263-
if path_constraints:
264-
constraints = Constraints()
265-
for c in path_constraints:
266-
if c.type == c.JOINT:
267-
constraints.joint_constraints.append(
268-
JointConstraint.from_joint_constraint(c))
269-
elif c.type == c.POSITION:
270-
constraints.position_constraints.append(
271-
PositionConstraint.from_position_constraint(header, c))
272-
elif c.type == c.ORIENTATION:
273-
constraints.orientation_constraints.append(
274-
OrientationConstraint.from_orientation_constraint(header, c))
275-
else:
276-
raise NotImplementedError
277-
path_constraints = constraints
272+
# convert constraints
273+
goal_constraints = [self._convert_constraints_to_rosmsg(goal_constraints, header)]
274+
path_constraints = self._convert_constraints_to_rosmsg(path_constraints, header)
275+
276+
if trajectory_constraints is not None:
277+
trajectory_constraints = TrajectoryConstraints(constraints=self._convert_constraints_to_rosmsg(path_constraints, header))
278278

279279
request = dict(start_state=start_state,
280280
goal_constraints=goal_constraints,

0 commit comments

Comments
 (0)