Skip to content

Commit 270ec5a

Browse files
committed
Add Python client library documentation using existing material from README. This needs to be updated.
1 parent eee9c10 commit 270ec5a

File tree

3 files changed

+266
-0
lines changed

3 files changed

+266
-0
lines changed

docs/index.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,3 +9,4 @@ CRTK
99

1010
pages/introduction
1111
pages/api
12+
pages/clients

docs/pages/client-python.rst

Lines changed: 237 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,237 @@
1+
General concepts
2+
================
3+
4+
The main class in the CRTK Python client library is ``crtk.utils``. It
5+
can be used to quickly populate an existing class by adding CRTK like
6+
methods. These methods will handle the following for you:
7+
8+
* Declare all required ROS publishers and wrap publisher calls in
9+
methods to send data to the device
10+
11+
* Declare all required ROS subscribers and provide callbacks to
12+
receive the data from the device
13+
14+
* Convert ROS messages to more convenient Python data types,
15+
i.e. numpy arrays for joint values and PyKDL types for cartesian
16+
data.
17+
18+
* Some events to manage asynchronous communication between the device
19+
and the "proxy" class.
20+
21+
The class ``crtk.utils`` is designed to add CRTK features "a la
22+
carte", i.e. it doesn't assume that all CRTK features are
23+
available. This allows to:
24+
25+
* Match only the features that are available on the CRTK devices one wants to use (server side)
26+
27+
* Reduce the number of features to those strictly needed for the
28+
application (client side). Reducing the number of ROS topics used
29+
helps in terms of performance.
30+
31+
32+
Installing the package
33+
======================
34+
35+
ROS 1
36+
-----
37+
38+
To build the ROS 1 CRTK Client library, we recommend to use the catkin
39+
build tools, i.e. ``catkin build``. You will need to clone this repository
40+
as well as the repository with CRTK specific ROS messages:
41+
42+
.. code-block:: bash
43+
44+
cd ~/catkin_ws/src # or wherever your catkin workspace is
45+
git clone https://github.com/collaborative-robotics/crtk_msgs
46+
git clone https://github.com/collaborative-robotics/crtk_python_client
47+
catkin build
48+
49+
Once these packages are built, you should source your ``setup.bash``:
50+
``source ~/catkin_ws/devel/setup.bash``. At that point, you should be able
51+
to import the crtk python package in Python using import crtk.
52+
53+
ROS 2
54+
-----
55+
56+
57+
Setting up a client
58+
===================
59+
60+
Overview
61+
--------
62+
63+
You can find some examples in the scripts directory. Overall, the
64+
approach is always the same, i.e. create a class and populate it with
65+
``crtk.utils``. You can then use an instance of this class. For
66+
example:
67+
68+
.. code-block:: python
69+
70+
class crtk_move_cp_example:
71+
# constructor
72+
def __init__(self, device_namespace):
73+
# ROS initialization
74+
if not rospy.get_node_uri():
75+
rospy.init_node('crtk_move_cp_example', anonymous = True, log_level = rospy.WARN)
76+
# populate this class with all the ROS topics we need
77+
self.crtk_utils = crtk.utils(self, device_namespace)
78+
self.crtk_utils.add_measured_cp()
79+
self.crtk_utils.add_move_cp()
80+
81+
What is happening behind the scene:
82+
83+
* ``device_namespace`` is the ROS namespace used by the
84+
device. E.g. if the namespace is ``left``, we assume the device will
85+
have its CRTK ROS topics under ``/left``
86+
87+
* ``get_node_uri()`` and ``init_node()`` are not strictly needed but
88+
helps if the user did not properly initialize the ROS node
89+
90+
* Add an instance of ``crtk.utils`` in your class. The first parameter
91+
indicates which Python object should be "populated", i.e. which
92+
object will have the CRTK methods added to its dictionary
93+
94+
* ``add_measured_cp()``:
95+
96+
* Creates a subscriber for the topic, e.g. ``/left/measured_cp``
97+
98+
* Registers a built-in callback for the topic. The callback will store the latest ``measured_cp`` ROS message in ``crtk_utils``
99+
100+
* Provides a method to read the latest ``measured_cp`` message as a PyKDL frame
101+
102+
* Adds the method ``measured_cp()`` to the user class (``crtk_move_cp_example``)
103+
104+
* ``add_move_cp()``:
105+
106+
* Creates a publisher for the topic, e.g. ``/left/move_cp``
107+
108+
* Provides a method to send a PyKDL frame (goal), internally converts to a ROS message
109+
110+
* Adds the method ``move_cp()`` to the user class (crtk_move_cp_example)
111+
112+
Once the class is defined, the user can use it:
113+
114+
.. code-block:: python
115+
116+
example = crtk_move_cp_example('left')
117+
position = example.measured_cp()
118+
position.p[2] += 0.05 # move by 5 cm
119+
example.move_cp(position)
120+
121+
122+
Operating state
123+
---------------
124+
125+
``crtk.utils.add_operating_state`` adds:
126+
127+
* State status ``operating_state()`` and helper queries: ``is_enabled()``, ``is_homed()``, ``is_busy()``
128+
129+
* State command ``operating_state_command()`` and helper commands: ``enable()``, ``disable()``, ``home()``, ``unhome()``
130+
131+
* Timer/event utilities:
132+
133+
* For subscribers: ``wait_for_valid_data()``
134+
135+
* For publishers (used by move commands): ``wait_for_busy()``
136+
137+
* For state changes (used by ``enable()``, ``home()``...): ``wait_for_operating_state()``
138+
139+
140+
Robot motion
141+
------------
142+
143+
``crtk.utils`` supports the following CRTK features:
144+
145+
* Subscribers:
146+
147+
* ``add_setpoint_js``, ``add_setpoint_cp``
148+
149+
* ``add_measured_js``, ``add_measured_cp``, ``add_measured_cv``, ``add_measured_cf``...
150+
151+
* Publishers:
152+
153+
* ``add_servo_jp``, ``add_servo_jf``, ``add_servo_cp``, ``add_servo_cf``...
154+
155+
* ``add_move_jp``, ``add_move_cp``
156+
157+
All methods relying on subscribers to get data have the following two optional parameters: ``age`` and ``wait``:
158+
159+
.. code-block:: python
160+
161+
setpoint_cp(age = None, wait = None)
162+
163+
The parameter age specifies how old the data can be to be considered
164+
valid and wait specifies how long to wait for the next message if the
165+
data currently cached is too old. By default, both are based on the
166+
expected interval provided when creating an instance of
167+
``crtk.utils``. The expected interval should match the publishing rate
168+
from the CRTK device. Setting the age to zero means that any cached
169+
data should be used and the method shouldn't wait for new messages.
170+
171+
All move commands (``move_jp`` and ``move_cp``) return a ROS time
172+
object. This is the time just before sending (i.e., publishing) the
173+
move command to the device. This timestamp can be used to wait for
174+
motion completion using:
175+
176+
.. code-block:: python
177+
178+
# wait until robot is not busy, i.e. move has ended
179+
h = example.move_cp(goal) # record time move was sent
180+
h.wait()
181+
# compact syntax
182+
example.move_cp(goal).wait()
183+
# other example, wait until move has started
184+
example.move_cp(goal).wait(is_busy = True)
185+
186+
The method ``wait_for_busy()`` used by ``handle.wait()`` depends on the CRTK
187+
device operating state and can be added to the example class using
188+
``crtk.utils.add_operating_state``. See previous section.
189+
190+
191+
Using a client
192+
==============
193+
194+
For the dVRK, one can use the classes ``dvrk.arm``, ``dvrk.psm``,
195+
``dvrk.mtm``... that use the ``crtk.utils`` to provide as many
196+
features as possible. This is convenient for general purpose testing,
197+
for example in combination with iPython to test snippets of code. In
198+
general, it is recommended to use your own class and only add the
199+
features you need to reduce the number of ROS messages and callbacks.
200+
201+
The dVRK arm class implementation can be found in the "dvrk_python package.
202+
203+
Example of use:
204+
205+
.. code-block:: python
206+
207+
import dvrk
208+
p = dvrk.arm('PSM1')
209+
p.enable()
210+
p.home()
211+
212+
# get measured joint state
213+
[position, velocity, effort, time] = p.measured_js()
214+
# get only position
215+
position = p.measured_jp()
216+
# get position and time
217+
[position, time] = p.measured_jp(extra = True)
218+
219+
# move in joint space
220+
import numpy
221+
p.move_jp(numpy.array([0.0, 0.0, 0.10, 0.0, 0.0, 0.0]))
222+
223+
# move in cartesian space
224+
import PyKDL
225+
# start position
226+
goal = p.setpoint_cp()
227+
# move 5cm in z direction
228+
goal.p[2] += 0.05
229+
p.move_cp(goal).wait()
230+
231+
import math
232+
# start position
233+
goal = p.setpoint_cp()
234+
# rotate tool tip frame by 25 degrees
235+
goal.M.DoRotX(math.pi * 0.25)
236+
p.move_cp(goal).wait()
237+

docs/pages/clients.rst

Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,28 @@
1+
.. _clients:
2+
3+
################
4+
Client Libraries
5+
################
6+
7+
********
8+
Overview
9+
********
10+
11+
This Python package provides some tools to facilitate the development of a CRTK compatible client over ROS, i.e. create a "proxy" class to communicate with an existing CRTK compatible ROS device.
12+
13+
.. _client_python:
14+
15+
*************
16+
Python client
17+
*************
18+
19+
.. include:: client-python.rst
20+
21+
.. _client_matlab:
22+
23+
*************
24+
Matlab client
25+
*************
26+
27+
..
28+
.. include:: client-matla.rst

0 commit comments

Comments
 (0)