Skip to content

Commit 1d65b29

Browse files
committed
Update doctest and setup travis to run them
1 parent 774fb26 commit 1d65b29

File tree

22 files changed

+227
-217
lines changed

22 files changed

+227
-217
lines changed

.travis.yml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -30,10 +30,12 @@ matrix:
3030
- PYTEST_ADDOPTS=--doctest-modules
3131
services: docker
3232
before_install:
33+
- docker run -p 19997:19997 --name vrep_rfl -d gramaziokohler/vrep-rfl
3334
- docker-compose -f "docs/backends/files/ur5-demo/docker-compose.yml" up -d --build
3435
- docker ps -a
3536
after_script:
3637
- docker-compose -f "docs/backends/files/ur5-demo/docker-compose.yml" down
38+
- docker rm -f vrep_rfl
3739
- name: "Python 3.7: macOS"
3840
os: osx
3941
osx_image: xcode10.2

docs/examples/03_backends_ros/01_ros_examples.rst

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -23,10 +23,8 @@ see the output ``Connected: True`` if everything is working properly:
2323
.. code-block:: python
2424
2525
from compas_fab.backends import RosClient
26-
client = RosClient()
27-
client.run()
28-
print('Connected: %s' % client.is_connected)
29-
client.terminate()
26+
with RosClient() as client:
27+
print('Connected:', client.is_connected)
3028
3129
*Yay! Our first connection to ROS!*
3230

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,16 +1,17 @@
11
import time
22

3-
from roslibpy import Message
43
from roslibpy import Topic
5-
64
from compas_fab.backends import RosClient
75

8-
client = RosClient()
9-
listener = Topic(client, '/chatter', 'std_msgs/String')
106

117
def receive_message(message):
128
print('Heard talking: ' + message['data'])
139

14-
listener.subscribe(receive_message)
1510

16-
client.run_forever()
11+
with RosClient() as client:
12+
listener = Topic(client, '/chatter', 'std_msgs/String')
13+
14+
listener.subscribe(receive_message)
15+
16+
while client.is_connected:
17+
time.sleep(1)

docs/examples/03_backends_ros/files/01_ros_hello_world_talker.py

Lines changed: 7 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -5,16 +5,12 @@
55

66
from compas_fab.backends import RosClient
77

8-
client = RosClient()
9-
client.run()
8+
with RosClient() as client:
9+
talker = Topic(client, '/chatter', 'std_msgs/String')
1010

11-
talker = Topic(client, '/chatter', 'std_msgs/String')
11+
while client.is_connected:
12+
talker.publish(Message({'data': 'Hello World!'}))
13+
print('Sending message...')
14+
time.sleep(1)
1215

13-
while client.is_connected:
14-
talker.publish(Message({'data': 'Hello World!'}))
15-
print('Sending message...')
16-
time.sleep(1)
17-
18-
talker.unadvertise()
19-
20-
client.terminate()
16+
talker.unadvertise()

pytest.ini

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,3 @@
11
[pytest]
2-
testpaths = tests
2+
testpaths = tests src
33
doctest_optionflags= NORMALIZE_WHITESPACE IGNORE_EXCEPTION_DETAIL ALLOW_UNICODE ALLOW_BYTES

src/compas_fab/backends/ros/client.py

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -80,9 +80,8 @@ class RosClient(Ros):
8080
--------
8181
8282
>>> from compas_fab.backends import RosClient
83-
>>> client = RosClient()
84-
>>> client.run()
85-
>>> print('Connected: %s' % client.is_connected)
83+
>>> with RosClient() as client:
84+
... print('Connected: %s' % client.is_connected)
8685
Connected: True
8786
8887
Note

src/compas_fab/backends/ros/messages/control_msgs.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@ def __init__(self, name="", position=0., velocity=0., acceleration=0.):
1818

1919

2020
class FollowJointTrajectoryGoal(ROSmsg):
21-
"""http://docs.ros.org/fuerte/api/control_msgs/html/msg/FollowJointTrajectoryGoal.html
21+
"""http://docs.ros.org/api/control_msgs/html/action/FollowJointTrajectory.html
2222
"""
2323

2424
def __init__(self, trajectory=None, path_tolerance=None,

src/compas_fab/backends/ros/messages/moveit_msgs.py

Lines changed: 0 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -139,27 +139,6 @@ def from_msg(cls, msg):
139139

140140
class PositionIKRequest(ROSmsg):
141141
"""http://docs.ros.org/kinetic/api/moveit_msgs/html/msg/PositionIKRequest.html
142-
143-
Examples
144-
--------
145-
>>> base_link = 'base_link'
146-
>>> planning_group = 'manipulator'
147-
>>> pose = Pose([420, -25, 459], [1, 0, 0], [0, 1, 0])
148-
>>> joint_names = ['shoulder_pan_joint', 'shoulder_lift_joint',
149-
'elbow_joint', 'wrist_1_joint', 'wrist_2_joint',
150-
'wrist_3_joint']
151-
>>> joint_positions = [3.39, -1.47, -2.05, 0.38, -4.96, -6.28]
152-
>>> header = Header(frame_id='base_link')
153-
>>> pose_stamped = PoseStamped(header, pose)
154-
>>> joint_state = JointState(name=joint_names, position=joint_positions,
155-
header=header)
156-
>>> multi_dof_joint_state = MultiDOFJointState(header=header,
157-
joint_names=joint_names)
158-
>>> start_state = RobotState(joint_state, multi_dof_joint_state)
159-
>>> ik_request = PositionIKRequest(group_name=planning_group,
160-
robot_state=start_state,
161-
pose_stamped=pose_stamped,
162-
avoid_collisions=True)
163142
"""
164143

165144
def __init__(self, group_name="robot", robot_state=None, constraints=None,

src/compas_fab/backends/ros/messages/services.py

Lines changed: 0 additions & 51 deletions
Original file line numberDiff line numberDiff line change
@@ -17,31 +17,6 @@
1717

1818
class GetPositionIKRequest(ROSmsg):
1919
"""http://docs.ros.org/kinetic/api/moveit_msgs/html/srv/GetPositionIK.html
20-
21-
Examples
22-
--------
23-
>>> import roslibpy
24-
>>> base_link = 'base_link' # robot.get_base_link_name()
25-
>>> planning_group = 'manipulator' # robot.main_planning_group
26-
>>> pose = Pose([0.420, -0.025, 0.459], [1, 0, 0], [0, 1, 0])
27-
>>> joint_names = ['shoulder_pan_joint', 'shoulder_lift_joint',
28-
'elbow_joint', 'wrist_1_joint', 'wrist_2_joint',
29-
'wrist_3_joint']
30-
>>> joint_positions = [3.39, -1.47, -2.05, 0.38, -4.96, -6.28]
31-
>>> header = Header(frame_id='base_link')
32-
>>> pose_stamped = PoseStamped(header, pose)
33-
>>> joint_state = JointState(name=joint_names, position=joint_positions,
34-
header=header)
35-
>>> multi_dof_joint_state = MultiDOFJointState(header=header)
36-
>>> start_state = RobotState(joint_state, multi_dof_joint_state)
37-
>>> ik_request = PositionIKRequest(group_name=planning_group,
38-
robot_state=start_state,
39-
pose_stamped=pose_stamped,
40-
avoid_collisions=True)
41-
>>> reqmsg = GetPositionIKRequest(ik_request)
42-
>>> srv = roslibpy.Service(ros_client, '/compute_ik', 'GetPositionIK')
43-
>>> request = roslibpy.ServiceRequest(reqmsg.msg)
44-
>>> srv.call(request, GetPositionIKResponse.from_msg, GetPositionIKResponse.from_msg)
4520
"""
4621
def __init__(self, ik_request=None):
4722
self.ik_request = ik_request or PositionIKRequest()
@@ -91,32 +66,6 @@ def from_msg(cls, msg):
9166

9267
class GetCartesianPathRequest(ROSmsg):
9368
"""http://docs.ros.org/melodic/api/moveit_msgs/html/srv/GetCartesianPath.html
94-
95-
Examples
96-
--------
97-
>>> import roslibpy
98-
>>> base_link = 'base_link' # robot.get_base_link_name()
99-
>>> ee_link = 'ee_link' # robot.get_end_effector_link_name()
100-
>>> main_planning_group = 'manipulator' # robot.main_planning_group
101-
>>> joint_names = ['j0', 'j1', 'j2', 'j3', 'j4', 'j5']
102-
>>> position = [0, 0, 0, 0, 0, 0] # robot.get_configurable_joint_names()
103-
>>> header = Header(frame_id=base_link)
104-
>>> joint_state = JointState(header=header, name=joint_names, position=position) # or: robot.get_joint_state()
105-
>>> multi_dof_joint_state = MultiDOFJointState(header=header)
106-
>>> start_state = RobotState(joint_state=joint_state, multi_dof_joint_state=multi_dof_joint_state)
107-
>>> start_pose = Pose([0.1068, -0.1818, 0.5930], [1., 0., 0.], [-0., 0., 1.])
108-
>>> end_pose = Pose([0.1041, -0.2946, 0.1843], [1., 0., 0.], [0., 1., 0.])
109-
>>> waypoints = [start_pose, end_pose]
110-
>>> reqmsg = GetCartesianPathRequest(header=header,
111-
start_state=start_state,
112-
group_name=main_planning_group,
113-
link_name=ee_link,
114-
waypoints=waypoints,
115-
max_step=10,
116-
avoid_collisions=True)
117-
>>> srv = roslibpy.Service(ros_client, '/compute_cartesian_path', 'GetCartesianPath')
118-
>>> request = roslibpy.ServiceRequest(reqmsg.msg)
119-
>>> srv.call(request, GetCartesianPathResponse.from_msg, GetCartesianPathResponse.from_msg)
12069
"""
12170

12271
def __init__(self, header=None, start_state=None, group_name='',

src/compas_fab/backends/vrep/client.py

Lines changed: 11 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -54,17 +54,16 @@ class VrepClient(object):
5454
5555
>>> from compas_fab.backends import VrepClient
5656
>>> with VrepClient() as client:
57-
... print ('Connected: %s' % client.is_connected
58-
...
57+
... print ('Connected: %s' % client.is_connected)
5958
Connected: True
6059
6160
Note:
6261
For more examples, check out the :ref:`V-REP examples page <examples_vrep>`.
6362
"""
6463
SUPPORTED_PLANNERS = ('bitrrt', 'bkpiece1', 'est', 'kpiece1',
65-
'lazyprmstar', 'lbkpiece1', 'lbtrrt', 'pdst',
66-
'prm', 'prrt', 'rrt', 'rrtconnect', 'rrtstar',
67-
'sbl', 'stride', 'trrt')
64+
'lazyprmstar', 'lbkpiece1', 'lbtrrt', 'pdst',
65+
'prm', 'prrt', 'rrt', 'rrtconnect', 'rrtstar',
66+
'sbl', 'stride', 'trrt')
6867

6968
def __init__(self, host='127.0.0.1', port=19997, scale=DEFAULT_SCALE, lua_script='RFL', debug=False):
7069
super(VrepClient, self).__init__()
@@ -150,8 +149,8 @@ def get_object_matrices(self, object_handles):
150149
>>> from compas_fab.backends import VrepClient
151150
>>> with VrepClient() as client:
152151
... matrices = client.get_object_matrices([0])
153-
... print([int(i) for i in matrices[0]])
154-
[0, 0, 0, 19, 0, 0, 0, 10, 0, 0, 0, 6]
152+
... print([int(i) for i in matrices[0]]) # doctest: +SKIP
153+
[0, 0, 0, 19, 0, 0, 0, 10, 0, 0, 0, 6] # doctest: +SKIP
155154
156155
.. note::
157156
The resulting dictionary is keyed by object handle.
@@ -226,7 +225,7 @@ def set_robot_config(self, robot, config):
226225
>>> with VrepClient() as client:
227226
... config = Configuration.from_prismatic_and_revolute_values([7.600, -4.500, -5.500],
228227
... to_radians([90, 0, 0, 0, 0, -90]))
229-
... client.set_robot_config(Robot.basic('A', index=0), config)
228+
... client.set_robot_config(rfl.Robot('A'), config)
230229
...
231230
"""
232231
assert_robot(robot)
@@ -250,7 +249,7 @@ def get_robot_config(self, robot):
250249
251250
>>> from compas_fab.robots import *
252251
>>> with VrepClient() as client:
253-
... config = client.get_robot_config(Robot.basic('A', index=0))
252+
... config = client.get_robot_config(rfl.Robot('A'))
254253
255254
Returns:
256255
An instance of :class:`.Configuration`.
@@ -272,16 +271,16 @@ def forward_kinematics(self, robot):
272271
273272
>>> from compas_fab.robots import *
274273
>>> with VrepClient() as client:
275-
... frame = client.forward_kinematics(Robot.basic('A', index=0))
274+
... frame = client.forward_kinematics(rfl.Robot('A'))
276275
277276
Returns:
278277
An instance of :class:`Frame`.
279278
"""
280279
assert_robot(robot)
281280

282281
_res, _, pose, _, _ = self.run_child_script('getIkTipPose',
283-
[robot.model.attr['index']],
284-
[], [])
282+
[robot.model.attr['index']],
283+
[], [])
285284
return vrep_pose_to_frame(pose, self.scale)
286285

287286
def inverse_kinematics(self, robot, goal_frame, metric_values=None, gantry_joint_limits=None, arm_joint_limits=None, max_trials=None, max_results=1):

0 commit comments

Comments
 (0)