Drake
 All Classes Files Functions Variables
LinearFrictionConeWrench Class Reference

constrain the contact force to be in a linearized friction cone The contact force f_contact = [edge1 edge2 edgeN] *[f1;f2;;fN] where edgeK is % the K'th edge of the linearized friction cone, fK is the force paramter along the K'th % edge More...

Inheritance diagram for LinearFrictionConeWrench:
Collaboration diagram for LinearFrictionConeWrench:

Public Member Functions

function LinearFrictionConeWrench (robot, body, body_pts, FC_edge)
 the linearized friction cone in the world frame. More...
 
function evalWrenchConstraint (obj, kinsol, F, slack)
 return the constraint. There is no nonlinear constraint on the force paramter More...
 
function torque (obj)
 Compute the torque at each contact point from the force parameter. More...
 
function force (obj)
 Compute the indivisual force from the force parameters F. More...
 
function contactPosition (obj, kinsol)
 Returns the contact positions and its gradient w.r.t q. More...
 
- Public Member Functions inherited from RigidBodyContactWrench
function RigidBodyContactWrench (robot, body, body_pts)
 
function generateWrenchConstraint (obj)
 

Protected Member Functions

function generateWrenchLincon (obj)
 
- Protected Member Functions inherited from RigidBodyContactWrench
function checkForceSize (obj, F)
 

Protected Attributes

Property normal_dir
 
Property FC_edge
 
- Protected Attributes inherited from RigidBodyContactWrench
Property robot
 
Property body
 
Property body_name
 
Property body_pts
 
Property num_pts
 of the contact point on the body frame. More...
 
Property num_wrench_constraint
 
Property num_pt_F
 
Property F_lb
 
Property F_ub
 force parameters More...
 
Property wrench_iCfun
 force parameters More...
 
Property wrench_jCvar
 
Property wrench_cnstr_ub
 
Property wrench_cnstr_lb
 
Property wrench_cnstr_name
 
Property contact_force_type
 
Property num_slack
 
Property slack_name
 
Property slack_lb
 
Property slack_ub
 
Property kinematics_chain_idx
 
Property complementarity_flag
 

Additional Inherited Members

- Public Attributes inherited from RigidBodyContactWrench
Constant Property FrictionConeType
 
Constant Property LinearFrictionConeType
 
Constant Property GraspType
 
Constant Property GraspFrictionConeType
 

Detailed Description

constrain the contact force to be in a linearized friction cone The contact force f_contact = [edge1 edge2 edgeN] *[f1;f2;;fN] where edgeK is % the K'th edge of the linearized friction cone, fK is the force paramter along the K'th % edge

Constructor & Destructor Documentation

function LinearFrictionConeWrench ( robot  ,
body  ,
body_pts  ,
FC_edge   
)

the linearized friction cone in the world frame.

Parameters
body– The index of contact body on the robot
body_pts– A 3 x num_pts double matrix, each column represents the coordinate of the contact point on the body frame. Every contact point shares the same friction cone.
FC_edge– A 3 x num_edge double matrix. FC_edge(:,i) is the i'th edge of the linearized friction cone in the WORLD frame
Return values
obj

Member Function Documentation

function contactPosition ( obj  ,
kinsol   
)
virtual

Returns the contact positions and its gradient w.r.t q.

Parameters
t– A double scalar, the time to evaluate the contact position
kinsol– The kinematics tree
Return values
pos– A matrix with 3 rows. pos(:,i) is the i'th contact position
J– A matrix of size prod(size(pos)) x nq. The gradient of pos w.r.t q

Reimplemented from RigidBodyContactWrench.

function evalWrenchConstraint ( obj  ,
kinsol  ,
,
slack   
)
virtual

return the constraint. There is no nonlinear constraint on the force paramter

Return values
c
dc

Reimplemented from RigidBodyContactWrench.

function force ( obj  )
virtual

Compute the indivisual force from the force parameters F.

The individual forces are reshape(A*F,3,obj.num_pts)

Return values
A– A (3*num_pts) x (obj.num_pt_F*obj.num_pts) double matrix

Reimplemented from RigidBodyContactWrench.

function generateWrenchLincon ( obj  )
protectedvirtual
Return values
lincon

Reimplemented from RigidBodyContactWrench.

function torque ( obj  )
virtual

Compute the torque at each contact point from the force parameter.

Return values
A– A (3*num_pts) x (obj.num_pt_F*obj.num_pts) double matrix. reshape(A*F(:),3,num_pts) are the torque at each contact point

Reimplemented from RigidBodyContactWrench.

Member Data Documentation

Property FC_edge
protected
Property normal_dir
protected

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