Drake
Drake C++ Documentation
CIrisCollisionGeometry Class Reference

Detailed Description

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 Shapegeometry () 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
 
CIrisCollisionGeometryoperator= (const CIrisCollisionGeometry &)=default
 
 CIrisCollisionGeometry (CIrisCollisionGeometry &&)=default
 
CIrisCollisionGeometryoperator= (CIrisCollisionGeometry &&)=default
 

Constructor & Destructor Documentation

◆ CIrisCollisionGeometry() [1/3]

◆ CIrisCollisionGeometry() [2/3]

◆ CIrisCollisionGeometry() [3/3]

CIrisCollisionGeometry ( const Shape geometry,
multibody::BodyIndex  body_index,
GeometryId  id,
math::RigidTransformd  X_BG 
)
Parameters
geometryThe actual geometry object. geometry must outlive this CIrisCollisionGeometry object.
body_indexThe index of the body to which this geometry is fixed.
idThe ID of this geometry.
X_BGThe pose of the geometry (G) in the attached body frame (B).

Member Function Documentation

◆ body_index()

multibody::BodyIndex body_index ( ) const

◆ geometry()

const Shape& geometry ( ) const

◆ id()

GeometryId id ( ) const

◆ num_rationals()

int num_rationals ( ) const

Returns the number of rationals in the condition "this geometry is on one side of the plane.

"

◆ OnPlaneSide()

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.

Parameters
aThe normal vector in the separating plane. a is expressed in frame A. Note that a doesn't need to have a unit length.
bThe constant term in the separating plane.
X_AB_multilinearThe 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_kinThis object is constructed with the MultibodyPlant containing this collision geometry.
plane_sideWhether the geometry is on the positive or negative side of the plane.
y_slackThe 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.
Precondition
rationals != nullptr

◆ operator=() [1/2]

CIrisCollisionGeometry& operator= ( CIrisCollisionGeometry &&  )
default

◆ operator=() [2/2]

CIrisCollisionGeometry& operator= ( const CIrisCollisionGeometry )
default

◆ type()

CIrisGeometryType type ( ) const

◆ X_BG()

const math::RigidTransformd& X_BG ( ) const

The documentation for this class was generated from the following file: