@@ -367,52 +367,50 @@ class OffsetCfg:
367
367
``OperationalSpaceControllerCfg``.
368
368
"""
369
369
370
- # TODO: Here the clip effects are not homogeneous, but they have unique names that relate
371
- # to specific control modes so it's fine to me.
370
+ # TODO: Here the clip effects are not homogeneous, I don't like that depending on the controller mode the behavior
371
+ # is different. It makes it hard to understand what does what. Should we have an explicit velocity clip?
372
372
373
- clip_pose_abs : list [tuple [float , float ]] | None = None
374
- """Clip range for the absolute pose targets. Defaults to None for no clipping.
375
-
376
- The expected format is a list of tuples, each containing two values. This effectively bounds
377
- the reachable range of the end-effector in the world frame.
373
+ clip_position : list [tuple [float , float ]] | None = None
374
+ """Clip range for the position targets. Defaults to None for no clipping.
375
+
376
+ The expected format is a list of tuples, each containing two values. When using the controller in ``"abs"`` mode
377
+ this limits the reachable range of the end-effector in the world frame. When using the controller in ``"rel"`` mode
378
+ this limits the maximum velocity of the end-effector in the task frame. This must match the number of active axes
379
+ in :attr:`controller_cfg.motion_control_axes_task`.
378
380
379
381
Example:
380
382
..code-block:: python
381
- clip_pose_abs = [
383
+ clip_position = [
382
384
(min_x, max_x),
383
385
(min_y, max_y),
384
386
(min_z, max_z),
385
- (min_roll, max_roll),
386
- (min_pitch, max_pitch),
387
- (min_yaw, max_yaw),
388
387
]
389
388
"""
390
- clip_pose_rel : list [tuple [float , float ]] | None = None
391
- """Clip range for the relative pose targets. Defaults to None for no clipping.
389
+ clip_orientation : list [tuple [float , float ]] | None = None
390
+ """Clip range for the orientation targets. Defaults to None for no clipping.
392
391
393
- The expected format is a list of tuples, each containing two values. This effectively limits
394
- the end-effector's velocity in the task frame.
392
+ The expected format is a list of tuples, each containing two values. When using the controller in ``"abs"`` mode
393
+ this limits the reachable range of the end-effector in the world frame. When using the controller in ``"rel"`` mode
394
+ this limits the maximum velocity of the end-effector in the task frame. This must match the number of active axes
395
+ in :attr:`controller_cfg.motion_control_axes_task`.
395
396
396
397
Example:
397
398
..code-block:: python
398
- clip_pose_rel = [
399
- (min_x, max_x),
400
- (min_y, max_y),
401
- (min_z, max_z),
399
+ clip_orientation = [
402
400
(min_roll, max_roll),
403
401
(min_pitch, max_pitch),
404
402
(min_yaw, max_yaw),
405
403
]
406
404
"""
407
- clip_wrench_abs : list [tuple [float , float ]] | None = None
405
+ clip_wrench : list [tuple [float , float ]] | None = None
408
406
"""Clip range for the absolute wrench targets. Defaults to None for no clipping.
409
407
410
408
The expected format is a list of tuples, each containing two values. This effectively limits
411
409
the maximum force and torque that can be commanded in the task frame.
412
410
413
411
Example:
414
412
..code-block:: python
415
- clip_wrench_abs = [
413
+ clip_wrench = [
416
414
(min_fx, max_fx),
417
415
(min_fy, max_fy),
418
416
(min_fz, max_fz),
0 commit comments