Link Class Reference

Used for bodies that are part of a robot. More...

#include <body.h>

Inheritance diagram for Link:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool externalContactsPreventMotion (const transf &motion)
int getChainNum () const
position getDistalJointLocation ()
int getLinkNum () const
virtual WorldElementgetOwner ()
vec3 getProximalJointAxis ()
position getProximalJointLocation ()
 Link (Robot *r, int c, int l, World *w, const char *name=0)
virtual void setContactsChanged ()
 Sets the flag that indicates that contacts have changed.
virtual ~Link ()

Protected Attributes

int chainNum
 Identifies what part of the robot this link is.
int linkNum
Robotowner
 A pointer to the robot that this link is a part of.

Friends

class KinematicChain
class Robot

Detailed Description

Used for bodies that are part of a robot.

A link is a dynamic body that notifies its owner robot when contacts have changed.

Definition at line 619 of file body.h.


Constructor & Destructor Documentation

Link::Link ( Robot r,
int  c,
int  l,
World w,
const char *  name = 0 
)

Definition at line 2163 of file body.cpp.

Link::~Link (  )  [virtual]

Definition at line 2172 of file body.cpp.


Member Function Documentation

bool Link::externalContactsPreventMotion ( const transf motion  ) 

Check if contact against a body not belonging to the same robot prevents motion.

This acts like contactPreventMotion, except in the case of a link belonging to a robot. In this case, contact against another link of the same robot does not prevent motion, as we assume the entire robot is moving.

Definition at line 2192 of file body.cpp.

int Link::getChainNum (  )  const [inline]

Returns which chain this link is a part of.

Definition at line 641 of file body.h.

position Link::getDistalJointLocation (  ) 

Returns the location of the distal joint in this link's coordinate system

By convention, in GraspIt! each link's origin is located at the next joint in the chain

Definition at line 2210 of file body.cpp.

int Link::getLinkNum (  )  const [inline]

Returns which link in the chain this link is.

Definition at line 644 of file body.h.

virtual WorldElement* Link::getOwner (  )  [inline, virtual]

Returns a pointer to the robot owning this link.

Reimplemented from Body.

Definition at line 638 of file body.h.

vec3 Link::getProximalJointAxis (  ) 

Returns the z axis of the proximal joint in link's coordinate system

Definition at line 2227 of file body.cpp.

position Link::getProximalJointLocation (  ) 

Returns the location of the proximal joint in this link's coordinate system

The translation component of the previous joint transform gives me the location of that joint in this joint's coordinate system

Definition at line 2218 of file body.cpp.

void Link::setContactsChanged (  )  [virtual]

Sets the flag that indicates that contacts have changed.

Sets BOTH the worldElement's AND the robot's contactsChanged flag.

Reimplemented from WorldElement.

Definition at line 2181 of file body.cpp.


Friends And Related Function Documentation

friend class KinematicChain [friend]

Definition at line 623 of file body.h.

friend class Robot [friend]

Definition at line 622 of file body.h.


Member Data Documentation

int Link::chainNum [protected]

Identifies what part of the robot this link is.

Definition at line 631 of file body.h.

int Link::linkNum [protected]

Definition at line 631 of file body.h.

Robot* Link::owner [protected]

A pointer to the robot that this link is a part of.

Definition at line 628 of file body.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


graspit
Author(s):
autogenerated on Wed Jan 25 11:00:22 2012