This class contains the necessary information about the collision geometry used in C-IRIS.
Most notably it transcribes the geometric condition that the collision geometry is on one side of the plane to mathematical constraints. For the detailed algorithm please refer to the paper Certified Polyhedral Decompositions of Collision-Free Configuration Space by Hongkai Dai*, Alexandre Amice*, Peter Werner, Annan Zhang and Russ Tedrake.
#include <drake/geometry/optimization/c_iris_collision_geometry.h>
Public Member Functions | |
CIrisCollisionGeometry (const Shape *geometry, multibody::BodyIndex body_index, GeometryId id, math::RigidTransformd X_BG) | |
const Shape & | geometry () const |
multibody::BodyIndex | body_index () const |
GeometryId | id () const |
const math::RigidTransformd & | X_BG () const |
void | OnPlaneSide (const Vector3< symbolic::Polynomial > &a, const symbolic::Polynomial &b, const multibody::RationalForwardKinematics::Pose< symbolic::Polynomial > &X_AB_multilinear, const multibody::RationalForwardKinematics &rational_forward_kin, PlaneSide plane_side, const VectorX< symbolic::Variable > &y_slack, std::vector< symbolic::RationalFunction > *rationals) const |
Impose the constraint that the geometry is on a given side of the plane {x | aᵀx+b=0}. More... | |
CIrisGeometryType | type () const |
int | num_rationals () const |
Returns the number of rationals in the condition "this geometry is on one side of the plane. More... | |
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable | |
CIrisCollisionGeometry (const CIrisCollisionGeometry &)=default | |
CIrisCollisionGeometry & | operator= (const CIrisCollisionGeometry &)=default |
CIrisCollisionGeometry (CIrisCollisionGeometry &&)=default | |
CIrisCollisionGeometry & | operator= (CIrisCollisionGeometry &&)=default |
|
default |
|
default |
CIrisCollisionGeometry | ( | const Shape * | geometry, |
multibody::BodyIndex | body_index, | ||
GeometryId | id, | ||
math::RigidTransformd | X_BG | ||
) |
geometry | The actual geometry object. geometry must outlive this CIrisCollisionGeometry object. |
body_index | The index of the body to which this geometry is fixed. |
id | The ID of this geometry. |
X_BG | The pose of the geometry (G) in the attached body frame (B). |
multibody::BodyIndex body_index | ( | ) | const |
const Shape& geometry | ( | ) | const |
GeometryId id | ( | ) | const |
int num_rationals | ( | ) | const |
Returns the number of rationals in the condition "this geometry is on one side of the plane.
"
void OnPlaneSide | ( | const Vector3< symbolic::Polynomial > & | a, |
const symbolic::Polynomial & | b, | ||
const multibody::RationalForwardKinematics::Pose< symbolic::Polynomial > & | X_AB_multilinear, | ||
const multibody::RationalForwardKinematics & | rational_forward_kin, | ||
PlaneSide | plane_side, | ||
const VectorX< symbolic::Variable > & | y_slack, | ||
std::vector< symbolic::RationalFunction > * | rationals | ||
) | const |
Impose the constraint that the geometry is on a given side of the plane {x | aᵀx+b=0}.
For example, to impose the constraint that a polytope is on the positive side of the plane, we consider the following constraints aᵀp_AVᵢ + b ≥ 1 (1) where Vᵢ is the i'th vertex of the polytope. (1) says rational functions are non-negative.
To impose the constraint that a sphere is on positive side of the plane, we consider the following constraints aᵀp_AS + b ≥ r*|a| (2a) aᵀp_AS + b ≥ 1 (2b) where S is the sphere center, r is the sphere radius.
We can reformulate (2a) as the following constraint ⌈aᵀp_AS + b aᵀ⌉ is psd. (3) ⌊ a (aᵀp_AS + b)/r²*I₃⌋ (3) is equivalent to the rational ⌈1⌉ᵀ*⌈aᵀp_AS + b aᵀ⌉*⌈1⌉ ⌊y⌋ ⌊ a (aᵀp_AS+ b)/r²*I₃⌋ ⌊y⌋ is positive.
a | The normal vector in the separating plane. a is expressed in frame A. Note that a doesn't need to have a unit length. |
b | The constant term in the separating plane. |
X_AB_multilinear | The pose of the collision geometry body (B) in the expressed frame A, written as a multilinear polynomial. This quantity is generated from RationalForwardKinematics::CalcBodyPoseAsMultilinearPolynomial. |
rational_forward_kin | This object is constructed with the MultibodyPlant containing this collision geometry. |
plane_side | Whether the geometry is on the positive or negative side of the plane. |
y_slack | The slack variable y in the documentation above, used for non-polytopic geometries. For spheres and capsules, y_slack has size 3. For cylinders, y_slack has size 2. |
[in/out] | rationals We append new rational functions to rationals . If these new rational functions are positive, then the geometry is on a given side of the plane. |
|
default |
|
default |
CIrisGeometryType type | ( | ) | const |
const math::RigidTransformd& X_BG | ( | ) | const |