Wraps the information that a pair of collision geometries are separated by a plane.
One collision geometry is on the "positive" side of the separating plane, namely {x| aᵀx + b ≥ δ} (with δ ≥ 0}, and the other collision geometry is on the "negative" side of the separating plane, namely {x|aᵀx+b ≤ −δ}.
T | The type of decision_variables. T= symbolic::Variable or double. |
#include <drake/geometry/optimization/cspace_separating_plane.h>
Public Member Functions | |
CSpaceSeparatingPlane (Vector3< symbolic::Polynomial > m_a, symbolic::Polynomial m_b, const CIrisCollisionGeometry *m_positive_side_geometry, const CIrisCollisionGeometry *m_negative_side_geometry, multibody::BodyIndex m_expressed_body, int m_plane_degree, const Eigen::Ref< const VectorX< T >> &m_decision_variables) | |
const CIrisCollisionGeometry * | geometry (PlaneSide plane_side) const |
Return the geometry on the specified side. More... | |
SortedPair< geometry::GeometryId > | geometry_pair () const |
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable | |
CSpaceSeparatingPlane (const CSpaceSeparatingPlane &)=default | |
CSpaceSeparatingPlane & | operator= (const CSpaceSeparatingPlane &)=default |
CSpaceSeparatingPlane (CSpaceSeparatingPlane &&)=default | |
CSpaceSeparatingPlane & | operator= (CSpaceSeparatingPlane &&)=default |
Public Attributes | |
Vector3< symbolic::Polynomial > | a |
symbolic::Polynomial | b |
const CIrisCollisionGeometry * | positive_side_geometry |
const CIrisCollisionGeometry * | negative_side_geometry |
multibody::BodyIndex | expressed_body |
int | plane_degree {1} |
VectorX< T > | decision_variables |
|
default |
|
default |
CSpaceSeparatingPlane | ( | Vector3< symbolic::Polynomial > | m_a, |
symbolic::Polynomial | m_b, | ||
const CIrisCollisionGeometry * | m_positive_side_geometry, | ||
const CIrisCollisionGeometry * | m_negative_side_geometry, | ||
multibody::BodyIndex | m_expressed_body, | ||
int | m_plane_degree, | ||
const Eigen::Ref< const VectorX< T >> & | m_decision_variables | ||
) |
const CIrisCollisionGeometry* geometry | ( | PlaneSide | plane_side | ) | const |
Return the geometry on the specified side.
SortedPair<geometry::GeometryId> geometry_pair | ( | ) | const |
|
default |
|
default |
VectorX<T> decision_variables |
multibody::BodyIndex expressed_body |
const CIrisCollisionGeometry* negative_side_geometry |
int plane_degree {1} |
const CIrisCollisionGeometry* positive_side_geometry |