Locomotion¶
Quantities mainly relevant for locomotion tasks on floating-base robots.
- gym_jiminy.common.quantities.locomotion.sanitize_foot_frame_names(env, frame_names='auto')[source]¶
Try to detect automatically one frame name per foot of a given legged robot if ‘auto’ mode is enabled. Otherwise, make sure that the specified sequence of frame names is non-empty, and all of them corresponds to end-effectors, ie having one of the leaf joints of the kinematic tree of the robot as parent.
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
frame_names (Sequence[str] | Literal['auto']) – Name of the frames corresponding to some feet of the robot. ‘auto’ to automatically detect them from the set of contact and force sensors of the robot.
- Return type:
- gym_jiminy.common.quantities.locomotion.translate_position_odom(position, odom_pose, out)[source]¶
Translate a single or batch of 2D position vector (X, Y) from world to local frame.
- Parameters:
position (ndarray) – Batch of positions vectors as a 2D array whose first dimension gathers the 2 spatial coordinates (X, Y) while the second corresponds to the independent points.
odom_pose (ndarray) – Reference odometry pose as a 1D array gathering the 2 position and 1 orientation coordinates in world plane (X, Y), (Yaw,) respectively.
out (ndarray) – Pre-allocated array in which to store the result.
- Return type:
None
- class gym_jiminy.common.quantities.locomotion.BaseRelativeHeight(env, parent, *, mode=QuantityEvalMode.TRUE)[source]¶
Bases:
InterfaceQuantity
[float
]Relative height of the floating base of the robot wrt lowest contact point or collision body in world frame.
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
parent (InterfaceQuantity | None) – Higher-level quantity from which this quantity is a requirement if any, None otherwise.
mode (QuantityEvalMode) – Desired mode of evaluation for this quantity. Optional: ‘QuantityEvalMode.TRUE’ by default.
- mode: QuantityEvalMode¶
Specify on which state to evaluate this quantity. See QuantityEvalMode documentation for details about each mode.
Warning
Mode REFERENCE requires a reference trajectory to be selected manually prior to evaluating this quantity for the first time.
- refresh()[source]¶
Evaluate this quantity based on the agent state at the end of the current agent step.
- Return type:
- _abc_impl = <_abc._abc_data object>¶
- class gym_jiminy.common.quantities.locomotion.BaseOdometryPose(env, parent, *, mode=QuantityEvalMode.TRUE)[source]¶
Bases:
AbstractQuantity
[ndarray
]Odometry pose of the floating base of the robot at the end of the agent step.
The odometry pose fully specifies the position and heading of the robot in 2D world plane. As such, it comprises the linear translation (X, Y) and the rotation around Z axis (namely rate of change of Yaw Euler angle). Mathematically, one is supposed to rely on se2 Lie Algebra for performing operations on odometry poses such as differentiation. In practice, the double geodesic metric space is used instead to prevent coupling between the linear and angular parts by considering them independently. Strictly speaking, it corresponds to the cartesian space (R^2 x SO(2)).
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
parent (InterfaceQuantity | None) – Higher-level quantity from which this quantity is a requirement if any, None otherwise.
mode (QuantityEvalMode) – Desired mode of evaluation for this quantity. Optional: ‘QuantityEvalMode.TRUE’ by default.
- initialize()[source]¶
Initialize internal buffers.
This is typically useful to refresh shared memory proxies or to re-initialize pre-allocated buffers.
Warning
Intermediary quantities ‘requirements’ are NOT initialized automatically because they can be initialized lazily in most cases, or are optional depending on the most efficient computation path at run-time. It is up to the developer implementing quantities to take care of it.
Note
This method must be called before starting a new episode.
Note
Lazy-initialization is used for efficiency, ie initialize will be called before the first time refresh has to be called, which may never be the case if cache is shared between multiple identical instances of the same quantity.
- Return type:
None
- refresh()[source]¶
Evaluate this quantity based on the agent state at the end of the current agent step.
- Return type:
ndarray
- _abc_impl = <_abc._abc_data object>¶
- class gym_jiminy.common.quantities.locomotion.BaseSpatialAverageVelocity(env, parent, *, mode=QuantityEvalMode.TRUE)[source]¶
Bases:
InterfaceQuantity
[ndarray
]Average base spatial velocity of the floating base of the robot in local odometry frame at the end of the agent step.
The average spatial velocity is obtained by finite difference. See FrameSpatialAverageVelocity documentation for details.
Roughly speaking, the local odometry reference frame is half-way between pinocchio.LOCAL and pinocchio.LOCAL_WORLD_ALIGNED. The z-axis is world-aligned while x and y axes are local, which corresponds to applying the Roll and Pitch from the Roll-Pitch-Yaw decomposition to the local velocity. See remove_yaw_from_quat for details.
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
parent (InterfaceQuantity | None) – Higher-level quantity from which this quantity is a requirement if any, None otherwise.
mode (QuantityEvalMode) – Desired mode of evaluation for this quantity. Optional: ‘QuantityEvalMode.TRUE’ by default.
- mode: QuantityEvalMode¶
Specify on which state to evaluate this quantity. See QuantityEvalMode documentation for details about each mode.
Warning
Mode REFERENCE requires a reference trajectory to be selected manually prior to evaluating this quantity for the first time.
- refresh()[source]¶
Evaluate this quantity based on the agent state at the end of the current agent step.
- Return type:
ndarray
- _abc_impl = <_abc._abc_data object>¶
- class gym_jiminy.common.quantities.locomotion.BaseOdometryAverageVelocity(env, parent, *, mode=QuantityEvalMode.TRUE)[source]¶
Bases:
InterfaceQuantity
[ndarray
]Average odometry velocity of the floating base of the robot in local odometry frame at the end of the agent step.
The odometry velocity fully specifies the linear and angular velocity of the robot in 2D world plane. See BaseSpatialAverageVelocity and BaseOdometryPose, documentations for details.
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
parent (InterfaceQuantity | None) – Higher-level quantity from which this quantity is a requirement if any, None otherwise.
mode (QuantityEvalMode) – Desired mode of evaluation for this quantity. Optional: ‘QuantityEvalMode.TRUE’ by default.
- mode: QuantityEvalMode¶
Specify on which state to evaluate this quantity. See QuantityEvalMode documentation for details about each mode.
Warning
Mode REFERENCE requires a reference trajectory to be selected manually prior to evaluating this quantity for the first time.
- refresh()[source]¶
Evaluate this quantity based on the agent state at the end of the current agent step.
- Return type:
ndarray
- _abc_impl = <_abc._abc_data object>¶
- class gym_jiminy.common.quantities.locomotion.AverageBaseMomentum(env, parent, *, mode=QuantityEvalMode.TRUE)[source]¶
Bases:
AbstractQuantity
[ndarray
]Angular momentum of the floating base of the robot in local odometry frame at the end of the agent step.
The most sensible choice for the reference frame is the local odometry frame. The local-world-aligned frame makes no sense at all. The local frame is not ideal as a rotation around x- and y-axes would have an effect on z-axis in odometry frame, introducing an undesirable coupling between odometry tracking and angular momentum minimization. Indeed, it is likely undesirable to penalize the momentum around z-axis because it is firstly involved in navigation rather than stabilization.
At this point, it is worth keeping track of the individual components of the angular momentum rather than aggregating them as a scalar directly by computing the resulting kinematic energy. This gives the opportunity to the practitioner to weight differently the angular momentum for going back and forth (y-axis) wrt the angular momentum for oscillating sideways (x-axis).
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
parent (InterfaceQuantity | None) – Higher-level quantity from which this quantity is a requirement if any, None otherwise.
mode (QuantityEvalMode) – Desired mode of evaluation for this quantity. Optional: ‘QuantityEvalMode.TRUE’ by default.
- initialize()[source]¶
Initialize internal buffers.
This is typically useful to refresh shared memory proxies or to re-initialize pre-allocated buffers.
Warning
Intermediary quantities ‘requirements’ are NOT initialized automatically because they can be initialized lazily in most cases, or are optional depending on the most efficient computation path at run-time. It is up to the developer implementing quantities to take care of it.
Note
This method must be called before starting a new episode.
Note
Lazy-initialization is used for efficiency, ie initialize will be called before the first time refresh has to be called, which may never be the case if cache is shared between multiple identical instances of the same quantity.
- Return type:
None
- refresh()[source]¶
Evaluate this quantity based on the agent state at the end of the current agent step.
- Return type:
ndarray
- _abc_impl = <_abc._abc_data object>¶
- class gym_jiminy.common.quantities.locomotion.MultiFootMeanXYZQuat(env, parent, frame_names='auto', *, mode=QuantityEvalMode.TRUE)[source]¶
Bases:
InterfaceQuantity
[ndarray
]Average position and orientation of the feet of a legged robot at the end of the agent step.
The average foot pose may be more appropriate than the floating base pose to characterize the position and orientation the robot in the world, especially when it comes to assessing the tracking error of the foot trajectories. It has the advantage to make foot tracking independent from floating base tracking, giving the opportunity to the robot to locally recover stability by moving its upper body without impeding foot tracking.
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
parent (InterfaceQuantity | None) – Higher-level quantity from which this quantity is a requirement if any, None otherwise.
frame_names (Tuple[str, ...]) – Name of the frames corresponding to some feet of the robot. ‘auto’ to automatically detect them from the set of contact and force sensors of the robot. Optional: ‘auto’ by default.
mode (QuantityEvalMode) – Desired mode of evaluation for this quantity.
- frame_names: Tuple[str, ...]¶
Name of the frames corresponding to some feet of the robot.
These frames must be part of the end-effectors, ie being associated with a leaf joint in the kinematic tree of the robot.
- mode: QuantityEvalMode¶
Specify on which state to evaluate this quantity. See QuantityEvalMode documentation for details about each mode.
Warning
Mode REFERENCE requires a reference trajectory to be selected manually prior to evaluating this quantity for the first time.
- refresh()[source]¶
Evaluate this quantity based on the agent state at the end of the current agent step.
- Return type:
ndarray
- _abc_impl = <_abc._abc_data object>¶
- class gym_jiminy.common.quantities.locomotion.MultiFootMeanOdometryPose(env, parent, frame_names='auto', *, mode=QuantityEvalMode.TRUE)[source]¶
Bases:
InterfaceQuantity
[ndarray
]Odometry pose of the average position and orientation of the feet of a legged robot at the end of the agent step.
Using the average foot odometry pose may be more appropriate than the floating base odometry pose to characterize the position and heading the robot in the world plane. See MultiFootMeanXYZQuat documentation for details.
The odometry pose fully specifies the position and orientation of the robot in 2D world plane. See BaseOdometryPose documentation for details.
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
parent (InterfaceQuantity | None) – Higher-level quantity from which this quantity is a requirement if any, None otherwise.
frame_names (Tuple[str, ...]) – Name of the frames corresponding to the feet of the robot. ‘auto’ to automatically detect them from the set of contact and force sensors of the robot. Optional: ‘auto’ by default.
mode (QuantityEvalMode) – Desired mode of evaluation for this quantity. Optional: ‘QuantityEvalMode.TRUE’ by default.
- frame_names: Tuple[str, ...]¶
Name of the frames corresponding to the feet of the robot.
These frames must be part of the end-effectors, ie being associated with a leaf joint in the kinematic tree of the robot.
- mode: QuantityEvalMode¶
Specify on which state to evaluate this quantity. See QuantityEvalMode documentation for details about each mode.
Warning
Mode REFERENCE requires a reference trajectory to be selected manually prior to evaluating this quantity for the first time.
- refresh()[source]¶
Evaluate this quantity based on the agent state at the end of the current agent step.
- Return type:
ndarray
- _abc_impl = <_abc._abc_data object>¶
- class gym_jiminy.common.quantities.locomotion.MultiFootRelativeXYZQuat(env, parent, frame_names='auto', *, mode=QuantityEvalMode.TRUE)[source]¶
Bases:
InterfaceQuantity
[ndarray
]Relative position and orientation of the feet of a legged robot wrt themselves at the end of the agent step.
The reference frame used to compute the relative pose of the frames is the mean foot pose. See MultiFootMeanXYZQuat documentation for details.
Note that there is always one of the relative frame pose that is redundant wrt the others. Notably, in particular case where there is only two frames, it is one is the opposite of the other. As a result, the last relative pose is always dropped from the returned value, based on the same ordering as ‘self.frame_names’. As for MultiFrameXYZQuat, the data associated with each frame are returned as a 2D contiguous array. The first dimension gathers the 7 components (X, Y, Z, QuatX, QuatY, QuatZ, QuaW), while the last one corresponds to individual relative frames poses.
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
parent (InterfaceQuantity | None) – Higher-level quantity from which this quantity is a requirement if any, None otherwise.
frame_names (Tuple[str, ...]) – Name of the frames corresponding to the feet of the robot. ‘auto’ to automatically detect them from the set of contact and force sensors of the robot. Optional: ‘auto’ by default.
mode (QuantityEvalMode) – Desired mode of evaluation for this quantity. Optional: ‘QuantityEvalMode.TRUE’ by default.
- frame_names: Tuple[str, ...]¶
Name of the frames corresponding to the feet of the robot.
These frames must be part of the end-effectors, ie being associated with a leaf joint in the kinematic tree of the robot.
- mode: QuantityEvalMode¶
Specify on which state to evaluate this quantity. See QuantityEvalMode documentation for details about each mode.
Warning
Mode REFERENCE requires a reference trajectory to be selected manually prior to evaluating this quantity for the first time.
- refresh()[source]¶
Evaluate this quantity based on the agent state at the end of the current agent step.
- Return type:
ndarray
- _abc_impl = <_abc._abc_data object>¶
- class gym_jiminy.common.quantities.locomotion.CenterOfMass(env, parent, *, kinematic_level=pinocchio.pinocchio_pywrap.KinematicLevel.POSITION, mode=QuantityEvalMode.TRUE)[source]¶
Bases:
AbstractQuantity
[ndarray
]Position, Velocity or Acceleration of the center of mass (CoM) of the robot as a whole in world frame.
Considering that the CoM has no angular motion, the velocity and the acceleration is equally given in world or local-world-aligned frames.
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
parent (InterfaceQuantity | None) – Higher-level quantity from which this quantity is a requirement if any, None otherwise.
kinematic_level (KinematicLevel) – Desired kinematic level, ie position, velocity or acceleration.
mode (QuantityEvalMode) – Desired mode of evaluation for this quantity. Optional: ‘QuantityEvalMode.TRUE’ by default.
- kinematic_level: KinematicLevel¶
Kinematic level to compute, ie position, velocity or acceleration.
- initialize()[source]¶
Initialize internal buffers.
This is typically useful to refresh shared memory proxies or to re-initialize pre-allocated buffers.
Warning
Intermediary quantities ‘requirements’ are NOT initialized automatically because they can be initialized lazily in most cases, or are optional depending on the most efficient computation path at run-time. It is up to the developer implementing quantities to take care of it.
Note
This method must be called before starting a new episode.
Note
Lazy-initialization is used for efficiency, ie initialize will be called before the first time refresh has to be called, which may never be the case if cache is shared between multiple identical instances of the same quantity.
- Return type:
None
- refresh()[source]¶
Evaluate this quantity based on the agent state at the end of the current agent step.
- Return type:
ndarray
- _abc_impl = <_abc._abc_data object>¶
- class gym_jiminy.common.quantities.locomotion.ZeroMomentPoint(env, parent, *, reference_frame=pinocchio.pinocchio_pywrap.ReferenceFrame.LOCAL, mode=QuantityEvalMode.TRUE)[source]¶
Bases:
AbstractQuantity
[ndarray
]Zero-Tilting Moment Point (ZMP), also called Center of Pressure (CoP).
This quantity only makes sense for legged robots. Such a robot will keep balance if the ZMP [1] is maintained inside the support polygon [2].
See also
For academic reference about its relation with the notion of stability, see: [1] https://scaron.info/robotics/zero-tilting-moment-point.html
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
parent (InterfaceQuantity | None) – Higher-level quantity from which this quantity is a requirement if any, None otherwise.
reference_frame (ReferenceFrame) – Whether to compute the ZMP in local odometry frame (aka ‘pin.LOCAL’) or aligned with world axes (aka ‘pin.LOCAL_WORLD_ALIGNED’).
mode (QuantityEvalMode) – Desired mode of evaluation for this quantity. Optional: ‘QuantityEvalMode.TRUE’ by default.
- reference_frame: ReferenceFrame¶
Whether to compute the ZMP in local frame specified by the odometry pose of floating base of the robot or the frame located on the position of the floating base with axes kept aligned with world frame.
- initialize()[source]¶
Initialize internal buffers.
This is typically useful to refresh shared memory proxies or to re-initialize pre-allocated buffers.
Warning
Intermediary quantities ‘requirements’ are NOT initialized automatically because they can be initialized lazily in most cases, or are optional depending on the most efficient computation path at run-time. It is up to the developer implementing quantities to take care of it.
Note
This method must be called before starting a new episode.
Note
Lazy-initialization is used for efficiency, ie initialize will be called before the first time refresh has to be called, which may never be the case if cache is shared between multiple identical instances of the same quantity.
- Return type:
None
- refresh()[source]¶
Evaluate this quantity based on the agent state at the end of the current agent step.
- Return type:
ndarray
- _abc_impl = <_abc._abc_data object>¶
- class gym_jiminy.common.quantities.locomotion.CapturePoint(env, parent, *, reference_frame=pinocchio.pinocchio_pywrap.ReferenceFrame.LOCAL, mode=QuantityEvalMode.TRUE)[source]¶
Bases:
AbstractQuantity
[ndarray
]Divergent Component of Motion (DCM), also called Capture Point (CP).
This quantity only makes sense for legged robots, and in particular bipedal robots for which the inverted pendulum is a relevant approximate dynamic model. It is involved in various dynamic stability metrics (usually only on flat ground), such as N-steps capturability. The capture point is defined as “where should a bipedal robot should step right now to eliminate linear momentum and come asymptotically to a stop” [1].
See also
For academic reference about its relation with the notion of stability, see: [1] https://scaron.info/robotics/capture-point.html
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
parent (InterfaceQuantity | None) – Higher-level quantity from which this quantity is a requirement if any, None otherwise.
reference_frame (ReferenceFrame) – Whether to compute the DCM in local odometry frame (aka ‘pin.LOCAL’) or aligned with world axes (aka ‘pin.LOCAL_WORLD_ALIGNED’).
mode (QuantityEvalMode) – Desired mode of evaluation for this quantity. Optional: ‘QuantityEvalMode.TRUE’ by default.
- reference_frame: ReferenceFrame¶
Whether to compute the DCM in local frame specified by the odometry pose of floating base of the robot or the frame located on the position of the floating base with axes kept aligned with world frame.
- initialize()[source]¶
Initialize internal buffers.
This is typically useful to refresh shared memory proxies or to re-initialize pre-allocated buffers.
Warning
Intermediary quantities ‘requirements’ are NOT initialized automatically because they can be initialized lazily in most cases, or are optional depending on the most efficient computation path at run-time. It is up to the developer implementing quantities to take care of it.
Note
This method must be called before starting a new episode.
Note
Lazy-initialization is used for efficiency, ie initialize will be called before the first time refresh has to be called, which may never be the case if cache is shared between multiple identical instances of the same quantity.
- Return type:
None
- refresh()[source]¶
Evaluate this quantity based on the agent state at the end of the current agent step.
- Return type:
ndarray
- _abc_impl = <_abc._abc_data object>¶
- class gym_jiminy.common.quantities.locomotion.MultiContactNormalizedSpatialForce(env, parent, *, mode=QuantityEvalMode.TRUE)[source]¶
Bases:
AbstractQuantity
[ndarray
]Standardized spatial forces apply on all contact points and collision bodies in their respective local contact frame.
The local contact frame is defined as the frame having the normal of the ground as vertical axis, and the vector orthogonal to the x-axis in world frame as y-axis.
The spatial force is rescaled by the weight of the robot rather than the actual vertical force. It has the advantage to guarantee that the resulting quantity is never poorly conditioned, which would be the case otherwise. Moreover, the contribution of the vertical force is still present, which is interesting for deriving a reward, as it allows for indirectly penalize jerky contact states and violent impacts. The side effect is not being able to guarantee that this quantity is bounded. Indeed, only the ratio of the norm of the tangential force at every contact point (or the resulting one) is bounded by the product of the friction coefficient by the vertical force, not the tangential force itself. This issue is a minor inconvenience as all it requires is normalization using RBF kernel to make it finite.
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
parent (InterfaceQuantity | None) – Higher-level quantity from which this quantity is a requirement if any, None otherwise.
mode (QuantityEvalMode)
- _abc_impl = <_abc._abc_data object>¶
- initialize()[source]¶
Initialize internal buffers.
This is typically useful to refresh shared memory proxies or to re-initialize pre-allocated buffers.
Warning
Intermediary quantities ‘requirements’ are NOT initialized automatically because they can be initialized lazily in most cases, or are optional depending on the most efficient computation path at run-time. It is up to the developer implementing quantities to take care of it.
Note
This method must be called before starting a new episode.
Note
Lazy-initialization is used for efficiency, ie initialize will be called before the first time refresh has to be called, which may never be the case if cache is shared between multiple identical instances of the same quantity.
- Return type:
None
- class gym_jiminy.common.quantities.locomotion.MultiFootNormalizedForceVertical(env, parent, frame_names='auto', *, mode=QuantityEvalMode.TRUE)[source]¶
Bases:
AbstractQuantity
[ndarray
]Standardized total vertical forces apply on each foot in world frame.
The lambda multipliers of the contact constraints are used to compute the total forces applied on each foot. Although relying on the total wrench acting on their respective parent joint seems enticing, it aggregates all external forces, not just the ground contact reaction forces. Most often, there is no difference, but not in the case of multiple robots interacting with each others, or if user-specified external forces are manually applied on the foot, eg to create disturbances. Relying on sensors to get the desired information is not an option either, because they do not give access to the ground truth.
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
parent (InterfaceQuantity | None) – Higher-level quantity from which this quantity is a requirement if any, None otherwise.
frame_names (Tuple[str, ...]) – Name of the frames corresponding to some feet of the robot. ‘auto’ to automatically detect them from the set of contact and force sensors of the robot. Optional: ‘auto’ by default.
mode (QuantityEvalMode) – Desired mode of evaluation for this quantity.
- _abc_impl = <_abc._abc_data object>¶
- frame_names: Tuple[str, ...]¶
Name of the frames corresponding to some feet of the robot.
These frames must be part of the end-effectors, ie being associated with a leaf joint in the kinematic tree of the robot.
- initialize()[source]¶
Initialize internal buffers.
This is typically useful to refresh shared memory proxies or to re-initialize pre-allocated buffers.
Warning
Intermediary quantities ‘requirements’ are NOT initialized automatically because they can be initialized lazily in most cases, or are optional depending on the most efficient computation path at run-time. It is up to the developer implementing quantities to take care of it.
Note
This method must be called before starting a new episode.
Note
Lazy-initialization is used for efficiency, ie initialize will be called before the first time refresh has to be called, which may never be the case if cache is shared between multiple identical instances of the same quantity.
- Return type:
None
- class gym_jiminy.common.quantities.locomotion.MultiFootCollisionDetection(env, parent, frame_names='auto', *, security_margin=0.0)[source]¶
Bases:
InterfaceQuantity
[bool
]Check if some of the feet of the robot are colliding with each other.
It takes into account some safety margins by which their volume will be inflated / deflated. See MultiFrameCollisionDetection documentation for details.
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
parent (InterfaceQuantity | None) – Higher-level quantity from which this quantity is a requirement if any, None otherwise.
frame_names (Tuple[str, ...]) – Name of the frames corresponding to some feet of the robot. ‘auto’ to automatically detect them from the set of contact and force sensors of the robot. Optional: ‘auto’ by default.
security_margin (float) – Signed distance below which a pair of geometry objects is stated in collision. Optional: 0.0 by default.
- _abc_impl = <_abc._abc_data object>¶