@@ -120,20 +120,20 @@ Robot robot("172.16.0.2");
120
120
robot.setDynamicRel(0.05);
121
121
122
122
// Move the end-effector 20cm in positive x-direction
123
- auto motion = LinearMotion (RobotPose(Affine({0.2, 0.0, 0.0}), 0.0), ReferenceType::Relative);
123
+ auto motion = CartesianMotion (RobotPose(Affine({0.2, 0.0, 0.0}), 0.0), ReferenceType::Relative);
124
124
125
125
// Finally move the robot
126
126
robot.move(motion);
127
127
```
128
128
129
129
The corresponding program in Python is
130
130
```python
131
- from franky import Affine, LinearMotion , Robot, ReferenceType
131
+ from franky import Affine, CartesianMotion , Robot, ReferenceType
132
132
133
133
robot = Robot("172.16.0.2")
134
134
robot.relative_dynamics_factor = 0.05
135
135
136
- motion = LinearMotion (Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
136
+ motion = CartesianMotion (Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
137
137
robot.move(motion)
138
138
```
139
139
@@ -213,7 +213,7 @@ In python, you can use them as follows:
213
213
``` python
214
214
import math
215
215
from scipy.spatial.transform import Rotation
216
- from franky import JointWaypointMotion, JointWaypoint, JointPositionStopMotion, LinearMotion , CartesianWaypointMotion, CartesianWaypoint, Affine, RobotPose, ReferenceType, CartesianPoseStopMotion
216
+ from franky import JointWaypointMotion, JointWaypoint, JointPositionStopMotion, CartesianMotion , CartesianWaypointMotion, CartesianWaypoint, Affine, RobotPose, ReferenceType, CartesianPoseStopMotion
217
217
218
218
# A point-to-point motion in the joint space
219
219
m1 = JointWaypointMotion([JointWaypoint([- 1.8 , 1.1 , 1.7 , - 2.1 , - 1.1 , 1.6 , - 0.4 ])])
@@ -230,15 +230,15 @@ m3 = JointPositionStopMotion()
230
230
231
231
# A linear motion in cartesian space
232
232
quat = Rotation.from_euler(" xyz" , [0 , 0 , math.pi / 2 ]).as_quat()
233
- m4 = LinearMotion (Affine([0.2 , - 0.4 , 0.3 ], quat))
234
- m5 = LinearMotion (RobotPose(Affine([0.2 , - 0.4 , 0.3 ], quat), elbow_position = 1.7 )) # With target elbow angle
233
+ m4 = CartesianMotion (Affine([0.2 , - 0.4 , 0.3 ], quat))
234
+ m5 = CartesianMotion (RobotPose(Affine([0.2 , - 0.4 , 0.3 ], quat), elbow_position = 1.7 )) # With target elbow angle
235
235
236
236
# A linear motion in cartesian space relative to the initial position
237
237
# (Note that this motion is relative both in position and orientation. Hence, when the robot's end-effector is oriented
238
238
# differently, it will move in a different direction)
239
- m6 = LinearMotion (Affine([0.2 , 0.0 , 0.0 ]), ReferenceType.Relative)
239
+ m6 = CartesianMotion (Affine([0.2 , 0.0 , 0.0 ]), ReferenceType.Relative)
240
240
241
- # Generalization of LinearMotion that allows for multiple waypoints
241
+ # Generalization of CartesianMotion that allows for multiple waypoints
242
242
m7 = CartesianWaypointMotion([
243
243
CartesianWaypoint(RobotPose(Affine([0.2 , - 0.4 , 0.3 ], quat), elbow_position = 1.7 )),
244
244
# The following waypoint is relative to the prior one and 50% slower
@@ -266,11 +266,11 @@ By adding reactions to the motion data, the robot can react to unforeseen events
266
266
In the Python API, you can define conditions by using a comparison between a robot's value and a given threshold.
267
267
If the threshold is exceeded, the reaction fires.
268
268
``` python
269
- from franky import LinearMotion , Affine, ReferenceType, Measure, Reaction
269
+ from franky import CartesianMotion , Affine, ReferenceType, Measure, Reaction
270
270
271
- motion = LinearMotion (Affine([0.0 , 0.0 , 0.1 ]), ReferenceType.Relative) # Move down 10cm
271
+ motion = CartesianMotion (Affine([0.0 , 0.0 , 0.1 ]), ReferenceType.Relative) # Move down 10cm
272
272
273
- reaction_motion = LinearMotion (Affine([0.0 , 0.0 , 0.01 ]), ReferenceType.Relative) # Move up for 1cm
273
+ reaction_motion = CartesianMotion (Affine([0.0 , 0.0 , 0.01 ]), ReferenceType.Relative) # Move up for 1cm
274
274
275
275
# Trigger reaction if the Z force is greater than 30N
276
276
reaction = Reaction(Measure.FORCE_Z > 30.0 , reaction_motion)
@@ -322,7 +322,7 @@ Hence, callbacks might be executed significantly after their respective reaction
322
322
323
323
In C++ you can additionally use lambdas to define more complex behaviours:
324
324
``` c++
325
- auto motion = LinearMotion (RobotPose(Affine({0.0, 0.0, 0.2}), 0.0), ReferenceType::Relative);
325
+ auto motion = CartesianMotion (RobotPose(Affine({0.0, 0.0, 0.2}), 0.0), ReferenceType::Relative);
326
326
327
327
// Stop motion if force is over 10N
328
328
auto stop_motion = StopMotion< franka::CartesianPose > ()
@@ -357,16 +357,16 @@ By setting the `asynchronous` parameter of `Robot.move` to `True`, the function
357
357
Instead, it returns immediately and, thus, allows the main thread to set new motions asynchronously.
358
358
```python
359
359
import time
360
- from franky import Affine, LinearMotion , Robot, ReferenceType
360
+ from franky import Affine, CartesianMotion , Robot, ReferenceType
361
361
362
362
robot = Robot("172.16.0.2")
363
363
robot.relative_dynamics_factor = 0.05
364
364
365
- motion1 = LinearMotion (Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
365
+ motion1 = CartesianMotion (Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
366
366
robot.move(motion1, asynchronous=True)
367
367
368
368
time.sleep(0.5)
369
- motion2 = LinearMotion (Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
369
+ motion2 = CartesianMotion (Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
370
370
robot.move(motion2, asynchronous=True)
371
371
```
372
372
0 commit comments