planning_models::KinematicModel Class Reference

Definition of a kinematic model. This class is not thread safe, however multiple instances can be created. More...

#include <kinematic_model.h>

List of all members.

Classes

class  AttachedBodyModel
 Class defining bodies that can be attached to robot links. This is useful when handling objects picked up by the robot. More...
class  FixedJointModel
 A fixed joint. More...
class  FloatingJointModel
 A floating joint. More...
class  JointModel
 A joint from the robot. Contains the transform applied by the joint type. More...
class  JointModelGroup
class  LinkModel
 A link from the robot. Contains the constant transform applied to the link and its geometry. More...
struct  MultiDofConfig
class  PlanarJointModel
 A planar joint. More...
class  PrismaticJointModel
 A prismatic joint. More...
class  RevoluteJointModel
 A revolute joint. More...

Public Member Functions

void addAttachedBodyModel (const std::string &link_name, AttachedBodyModel *att_body_model)
void clearAllAttachedBodyModels ()
void clearLinkAttachedBodyModel (const std::string &link_name, const std::string &att_name)
void clearLinkAttachedBodyModels (const std::string &link_name)
void copyFrom (const KinematicModel &source)
void defaultState (void)
void exclusiveLock (void) const
 Provide interface to get an exclusive lock to change the model. Use carefully!
void exclusiveUnlock (void) const
 Provide interface to release an exclusive lock. Use carefully!
void getChildLinkModels (const LinkModel *parent, std::vector< const LinkModel * > &links) const
 Get the set of links that follow a parent link in the kinematic chain.
const JointModelgetJointModel (const std::string &joint) const
 Get a joint by its name.
const std::map< std::string,
JointModelGroup * > & 
getJointModelGroupMap () const
void getJointModelNames (std::vector< std::string > &joints) const
 Get the array of joint names, in the order they appear in the robot state.
const std::vector< JointModel * > & getJointModels () const
 Get the array of joints, in the order they appear in the robot state.
const LinkModelgetLinkModel (const std::string &link) const
 Get a link by its name.
void getLinkModelNames (std::vector< std::string > &links) const
 Get the link names in the order they should be updated.
const std::vector< LinkModel * > & getLinkModels () const
 Get the array of joints, in the order they should be updated.
const JointModelGroupgetModelGroup (const std::string &name) const
void getModelGroupNames (std::vector< std::string > &getModelGroupNames) const
const std::string & getName (void) const
 General the model name.
const JointModelgetRoot (void) const
 Get the root joint.
bool hasJointModel (const std::string &name) const
 Check if a joint exists.
bool hasLinkModel (const std::string &name) const
 Check if a link exists.
bool hasModelGroup (const std::string &group) const
 KinematicModel (const urdf::Model &model, const std::map< std::string, std::vector< std::string > > &groups, const std::vector< MultiDofConfig > &multi_dof_configs)
 Construct a kinematic model from a parsed description and a list of planning groups.
 KinematicModel (const KinematicModel &source)
 Construct a kinematic model from another one.
void printModelInfo (std::ostream &out=std::cout) const
 Print information about the constructed model.
void replaceAttachedBodyModels (const std::string &link_name, std::vector< AttachedBodyModel * > &attached_body_vector)
void sharedLock (void) const
 Provide interface to get a shared lock for reading model data.
void sharedUnlock (void) const
 Provide interface to release a shared lock.
 ~KinematicModel (void)
 Destructor. Clear all memory.

Private Member Functions

void buildGroups (const std::map< std::string, std::vector< std::string > > &groups)
JointModelbuildRecursive (LinkModel *parent, const urdf::Link *link, const std::vector< MultiDofConfig > &multi_dof_configs)
JointModelconstructJointModel (const urdf::Joint *urdfJointModel, const urdf::Link *child_link, const std::vector< MultiDofConfig > &multi_dof_configs)
LinkModelconstructLinkModel (const urdf::Link *urdfLink)
shapes::Shape * constructShape (const urdf::Geometry *geom)
JointModelcopyJointModel (const JointModel *joint)
JointModelcopyRecursive (LinkModel *parent, const LinkModel *link)

Private Attributes

std::map< std::string,
JointModelGroup * > 
joint_model_group_map_
std::map< std::string,
JointModel * > 
joint_model_map_
 A map from joint names to their instances.
std::vector< JointModel * > joint_model_vector_
 The vector of joints in the model, in the order they appear in the state vector.
std::map< std::string,
LinkModel * > 
link_model_map_
 A map from link names to their instances.
std::vector< LinkModel * > link_model_vector_
 The vector of links that are updated when computeTransforms() is called, in the order they are updated.
boost::shared_mutex lock_
 Shared lock for changing models.
std::string model_name_
 The name of the model.
JointModelroot_
 The root joint.

Detailed Description

Definition of a kinematic model. This class is not thread safe, however multiple instances can be created.

Definition at line 48 of file kinematic_model.h.


Constructor & Destructor Documentation

planning_models::KinematicModel::KinematicModel ( const KinematicModel source  ) 

Construct a kinematic model from another one.

Definition at line 68 of file kinematic_model.cpp.

planning_models::KinematicModel::KinematicModel ( const urdf::Model &  model,
const std::map< std::string, std::vector< std::string > > &  groups,
const std::vector< MultiDofConfig > &  multi_dof_configs 
)

Construct a kinematic model from a parsed description and a list of planning groups.

Author:
Ioan Sucan

Definition at line 50 of file kinematic_model.cpp.

planning_models::KinematicModel::~KinematicModel ( void   ) 

Destructor. Clear all memory.

Definition at line 73 of file kinematic_model.cpp.


Member Function Documentation

void planning_models::KinematicModel::addAttachedBodyModel ( const std::string &  link_name,
AttachedBodyModel att_body_model 
)

Definition at line 601 of file kinematic_model.cpp.

void planning_models::KinematicModel::buildGroups ( const std::map< std::string, std::vector< std::string > > &  groups  )  [private]

Definition at line 132 of file kinematic_model.cpp.

planning_models::KinematicModel::JointModel * planning_models::KinematicModel::buildRecursive ( LinkModel parent,
const urdf::Link *  link,
const std::vector< MultiDofConfig > &  multi_dof_configs 
) [private]

Definition at line 160 of file kinematic_model.cpp.

void planning_models::KinematicModel::clearAllAttachedBodyModels (  ) 

Definition at line 562 of file kinematic_model.cpp.

void planning_models::KinematicModel::clearLinkAttachedBodyModel ( const std::string &  link_name,
const std::string &  att_name 
)

Definition at line 592 of file kinematic_model.cpp.

void planning_models::KinematicModel::clearLinkAttachedBodyModels ( const std::string &  link_name  ) 

Definition at line 571 of file kinematic_model.cpp.

planning_models::KinematicModel::JointModel * planning_models::KinematicModel::constructJointModel ( const urdf::Joint *  urdfJointModel,
const urdf::Link *  child_link,
const std::vector< MultiDofConfig > &  multi_dof_configs 
) [private]

Definition at line 185 of file kinematic_model.cpp.

planning_models::KinematicModel::LinkModel * planning_models::KinematicModel::constructLinkModel ( const urdf::Link *  urdfLink  )  [private]

Definition at line 291 of file kinematic_model.cpp.

shapes::Shape * planning_models::KinematicModel::constructShape ( const urdf::Geometry *  geom  )  [private]

Definition at line 318 of file kinematic_model.cpp.

void planning_models::KinematicModel::copyFrom ( const KinematicModel source  ) 

Definition at line 109 of file kinematic_model.cpp.

planning_models::KinematicModel::JointModel * planning_models::KinematicModel::copyJointModel ( const JointModel joint  )  [private]

Definition at line 512 of file kinematic_model.cpp.

planning_models::KinematicModel::JointModel * planning_models::KinematicModel::copyRecursive ( LinkModel parent,
const LinkModel link 
) [private]

Definition at line 491 of file kinematic_model.cpp.

void planning_models::KinematicModel::defaultState ( void   ) 
void planning_models::KinematicModel::exclusiveLock ( void   )  const

Provide interface to get an exclusive lock to change the model. Use carefully!

Definition at line 85 of file kinematic_model.cpp.

void planning_models::KinematicModel::exclusiveUnlock ( void   )  const

Provide interface to release an exclusive lock. Use carefully!

Definition at line 90 of file kinematic_model.cpp.

void planning_models::KinematicModel::getChildLinkModels ( const LinkModel parent,
std::vector< const LinkModel * > &  links 
) const

Get the set of links that follow a parent link in the kinematic chain.

const planning_models::KinematicModel::JointModel * planning_models::KinematicModel::getJointModel ( const std::string &  joint  )  const

Get a joint by its name.

Definition at line 442 of file kinematic_model.cpp.

const std::map<std::string, JointModelGroup*>& planning_models::KinematicModel::getJointModelGroupMap (  )  const [inline]

Definition at line 559 of file kinematic_model.h.

void planning_models::KinematicModel::getJointModelNames ( std::vector< std::string > &  joints  )  const

Get the array of joint names, in the order they appear in the robot state.

Definition at line 483 of file kinematic_model.cpp.

const std::vector<JointModel*>& planning_models::KinematicModel::getJointModels (  )  const [inline]

Get the array of joints, in the order they appear in the robot state.

Definition at line 518 of file kinematic_model.h.

const planning_models::KinematicModel::LinkModel * planning_models::KinematicModel::getLinkModel ( const std::string &  link  )  const

Get a link by its name.

Definition at line 454 of file kinematic_model.cpp.

void planning_models::KinematicModel::getLinkModelNames ( std::vector< std::string > &  links  )  const

Get the link names in the order they should be updated.

Definition at line 474 of file kinematic_model.cpp.

const std::vector<LinkModel*>& planning_models::KinematicModel::getLinkModels (  )  const [inline]

Get the array of joints, in the order they should be updated.

Definition at line 524 of file kinematic_model.h.

const JointModelGroup* planning_models::KinematicModel::getModelGroup ( const std::string &  name  )  const [inline]

Definition at line 553 of file kinematic_model.h.

void planning_models::KinematicModel::getModelGroupNames ( std::vector< std::string > &  getModelGroupNames  )  const

Definition at line 466 of file kinematic_model.cpp.

const std::string & planning_models::KinematicModel::getName ( void   )  const

General the model name.

Definition at line 105 of file kinematic_model.cpp.

const planning_models::KinematicModel::JointModel * planning_models::KinematicModel::getRoot ( void   )  const

Get the root joint.

Definition at line 422 of file kinematic_model.cpp.

bool planning_models::KinematicModel::hasJointModel ( const std::string &  name  )  const

Check if a joint exists.

Definition at line 427 of file kinematic_model.cpp.

bool planning_models::KinematicModel::hasLinkModel ( const std::string &  name  )  const

Check if a link exists.

Definition at line 432 of file kinematic_model.cpp.

bool planning_models::KinematicModel::hasModelGroup ( const std::string &  group  )  const

Definition at line 437 of file kinematic_model.cpp.

void planning_models::KinematicModel::printModelInfo ( std::ostream &  out = std::cout  )  const

Print information about the constructed model.

void planning_models::KinematicModel::replaceAttachedBodyModels ( const std::string &  link_name,
std::vector< AttachedBodyModel * > &  attached_body_vector 
)

Definition at line 579 of file kinematic_model.cpp.

void planning_models::KinematicModel::sharedLock ( void   )  const

Provide interface to get a shared lock for reading model data.

Definition at line 95 of file kinematic_model.cpp.

void planning_models::KinematicModel::sharedUnlock ( void   )  const

Provide interface to release a shared lock.

Definition at line 100 of file kinematic_model.cpp.


Member Data Documentation

Definition at line 599 of file kinematic_model.h.

A map from joint names to their instances.

Definition at line 588 of file kinematic_model.h.

The vector of joints in the model, in the order they appear in the state vector.

Definition at line 591 of file kinematic_model.h.

A map from link names to their instances.

Definition at line 585 of file kinematic_model.h.

The vector of links that are updated when computeTransforms() is called, in the order they are updated.

Definition at line 594 of file kinematic_model.h.

boost::shared_mutex planning_models::KinematicModel::lock_ [mutable, private]

Shared lock for changing models.

Definition at line 579 of file kinematic_model.h.

The name of the model.

Definition at line 582 of file kinematic_model.h.

The root joint.

Definition at line 597 of file kinematic_model.h.


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


planning_models
Author(s): Ioan Sucan/isucan@willowgarage.com
autogenerated on Fri Jan 11 09:14:26 2013