Drake
 All Classes Files Functions Variables
Point2LineSegDistConstraint Class Reference

This constrain the distance between a point on a body to a line segment is within a range. More...

Inheritance diagram for Point2LineSegDistConstraint:
Collaboration diagram for Point2LineSegDistConstraint:

Public Member Functions

function Point2LineSegDistConstraint (robot, pt_body, pt, line_body, line_ends, dist_lb, dist_ub, tspan)
 
function bounds (obj, t)
 
function name (obj, t)
 
function kinematicsPathJoints (obj)
 
- Public Member Functions inherited from SingleTimeKinematicConstraint
function SingleTimeKinematicConstraint (robot, tspan)
 
function getTspan (obj)
 
function isTimeValid (obj, t)
 
function getNumConstraint (obj, t)
 
function updateRobot (obj, robot)
 
function eval (obj, t, kinsol)
 
function generateConstraint (obj, t)
 generate a FunctionHandleConstraint object if time is valid or if no time is given More...
 
function kinematicsPathJoints (obj)
 return the indices of the joints used to evaluate the constraint. More...
 
- Public Member Functions inherited from RigidBodyConstraint
function RigidBodyConstraint (category, robot, tspan)
 
function categoryString (obj)
 

Protected Member Functions

function evalValidTime (obj, kinsol)
 

Protected Attributes

Property pt_body
 
Property pt
 
Property line_body
 
Property line_ends
 
Property dist_lb
 
Property dist_ub
 
Property pt_body_name
 
Property line_body_name
 
- Protected Attributes inherited from SingleTimeKinematicConstraint
Property num_constraint
 
- Protected Attributes inherited from RigidBodyConstraint
Property category
 
Property type
 
Property robot
 
Property tspan
 
Property mex_ptr
 

Additional Inherited Members

- Public Attributes inherited from RigidBodyConstraint
Constant Property SingleTimeKinematicConstraintCategory
 
Constant Property MultipleTimeKinematicConstraintCategory
 
Constant Property QuasiStaticConstraintCategory
 
Constant Property PostureConstraintCategory
 
Constant Property MultipleTimeLinearPostureConstraintCategory
 
Constant Property SingleTimeLinearPostureConstraintCategory
 
Constant Property ContactWrenchConstraintCategory
 
Constant Property QuasiStaticConstraintType
 
Constant Property PostureConstraintType
 
Constant Property SingleTimeLinearPostureConstraintType
 
Constant Property AllBodiesClosestDistanceConstraintType
 
Constant Property WorldEulerConstraintType
 
Constant Property WorldGazeDirConstraintType
 
Constant Property WorldGazeOrientConstraintType
 
Constant Property WorldGazeTargetConstraintType
 
Constant Property RelativeGazeTargetConstraintType
 
Constant Property WorldCoMConstraintType
 
Constant Property WorldPositionConstraintType
 
Constant Property WorldPositionInFrameConstraintType
 
Constant Property WorldQuatConstraintType
 
Constant Property Point2PointDistanceConstraintType
 
Constant Property Point2LineSegDistConstraintType
 
Constant Property WorldFixedPositionConstraintType
 
Constant Property WorldFixedOrientConstraintType
 
Constant Property WorldFixedBodyPoseConstraintType
 
Constant Property PostureChangeConstraintType
 
Constant Property RelativePositionConstraintType
 
Constant Property FrictionConeWrenchConstraintType
 
Constant Property LinearFrictionConeWrenchConstraintType
 
Constant Property RailGraspWrenchConstraintType
 
Constant Property RelativeQuatConstraintType
 
Constant Property RelativeGazeDirConstraintType
 
Constant Property MinDistanceConstraintType
 
Constant Property GravityCompensationTorqueConstraintType
 

Detailed Description

This constrain the distance between a point on a body to a line segment is within a range.

Also the projection of the point is within the LineSegment

Parameters
robot
pt_body– The body index
pt– A 3x1 double array, the coordinate of the point in pt_body frame
line_body– The body index, the body on which the line segment is on
line_ends– a 3x2 double matrix, line_ends(:,1) and line_ends(:,2) are the coordinate of the two ends of the line segment, on the line_body frame
dist_lb– A nonnegative double scalar. The lower bound of the point to line distance
dist_ub– A nonnegative double scalar. The upper bound of the point to line distance
tspan– A 1x2 double array, optional argument. The time span of the constraint. Default is [-inf inf];

Constructor & Destructor Documentation

function Point2LineSegDistConstraint ( robot  ,
pt_body  ,
pt  ,
line_body  ,
line_ends  ,
dist_lb  ,
dist_ub  ,
tspan   
)
Return values
obj

Member Function Documentation

function bounds ( obj  ,
 
)
virtual
Return values
lb
ub

Reimplemented from SingleTimeKinematicConstraint.

function evalValidTime ( obj  ,
kinsol   
)
protectedvirtual
Return values
c
dc

Reimplemented from SingleTimeKinematicConstraint.

function kinematicsPathJoints ( obj  )
Return values
joint_idx
function name ( obj  ,
 
)
virtual
Return values
name_str

Reimplemented from SingleTimeKinematicConstraint.

Member Data Documentation

Property dist_lb
protected
Property dist_ub
protected
Property line_body
protected
Property line_body_name
protected
Property line_ends
protected
Property pt
protected
Property pt_body
protected
Property pt_body_name
protected

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