Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/robot_state/link_state.h>
00038 #include <moveit/robot_state/robot_state.h>
00039
00040 robot_state::LinkState::LinkState(RobotState *state, const robot_model::LinkModel* lm) :
00041 robot_state_(state), link_model_(lm), parent_joint_state_(NULL), parent_link_state_(NULL)
00042 {
00043 global_link_transform_.setIdentity();
00044 global_collision_body_transform_.setIdentity();
00045 }
00046
00047 robot_state::LinkState::~LinkState()
00048 {
00049 }
00050
00051 void robot_state::LinkState::computeTransformForward(const Eigen::Affine3d& parent_transform)
00052 {
00053 global_link_transform_ = parent_transform;
00054
00055
00056 const std::vector<robot_model::JointModel*> &child_jmodels = link_model_->getChildJointModels();
00057 for (std::size_t i = 0 ; i < child_jmodels.size() ; ++i)
00058 robot_state_->getLinkState(child_jmodels[i]->getChildLinkModel()->getName())->computeTransformForward(this);
00059
00060 computeGeometryTransforms();
00061 }
00062
00063 void robot_state::LinkState::computeTransformForward(const LinkState *parent_link)
00064 {
00065 global_link_transform_ = parent_link->global_link_transform_ * link_model_->getJointOriginTransform() * parent_joint_state_->getVariableTransform();
00066
00067
00068 const std::vector<robot_model::JointModel*> &child_jmodels = link_model_->getChildJointModels();
00069 for (std::size_t i = 0 ; i < child_jmodels.size() ; ++i)
00070 robot_state_->getLinkState(child_jmodels[i]->getChildLinkModel()->getName())->computeTransformForward(this);
00071
00072 computeGeometryTransforms();
00073 }
00074
00075 void robot_state::LinkState::computeTransformBackward(const LinkState *child_link)
00076 {
00077 global_link_transform_ = child_link->global_link_transform_ * (child_link->link_model_->getJointOriginTransform() * child_link->parent_joint_state_->getVariableTransform()).inverse();
00078 if (parent_link_state_)
00079 parent_link_state_->computeTransformBackward(this);
00080 else
00081 parent_joint_state_->setVariableValues(global_link_transform_);
00082
00083
00084 const std::vector<robot_model::JointModel*> &child_jmodels = link_model_->getChildJointModels();
00085 for (std::size_t i = 0 ; i < child_jmodels.size() ; ++i)
00086 {
00087 LinkState *child = robot_state_->getLinkState(child_jmodels[i]->getChildLinkModel()->getName());
00088 if (child != child_link)
00089 child->computeTransformForward(this);
00090 }
00091
00092 computeGeometryTransforms();
00093 }
00094
00095 void robot_state::LinkState::computeTransformBackward(const Eigen::Affine3d& child_transform)
00096 {
00097 global_link_transform_ = child_transform;
00098 if (parent_link_state_)
00099 parent_link_state_->computeTransformBackward(this);
00100 else
00101 parent_joint_state_->setVariableValues(global_link_transform_);
00102
00103 const std::vector<robot_model::JointModel*> &child_jmodels = link_model_->getChildJointModels();
00104 for (std::size_t i = 0 ; i < child_jmodels.size() ; ++i)
00105 robot_state_->getLinkState(child_jmodels[i]->getChildLinkModel()->getName())->computeTransformForward(this);
00106
00107 computeGeometryTransforms();
00108 }
00109
00110 void robot_state::LinkState::computeGeometryTransforms()
00111 {
00112 global_collision_body_transform_ = global_link_transform_ * link_model_->getCollisionOriginTransform();
00113 updateAttachedBodies();
00114 }
00115
00116 void robot_state::LinkState::computeTransform()
00117 {
00118 global_link_transform_ = (parent_link_state_ ? parent_link_state_->global_link_transform_ : robot_state_->getRootTransform())
00119 * link_model_->getJointOriginTransform() * parent_joint_state_->getVariableTransform();
00120 computeGeometryTransforms();
00121 }
00122
00123 void robot_state::LinkState::updateAttachedBodies()
00124 {
00125 for (std::map<std::string, AttachedBody*>::const_iterator it = attached_body_map_.begin() ; it != attached_body_map_.end() ; ++it)
00126 it->second->computeTransform(global_link_transform_);
00127 }
00128
00129 bool robot_state::LinkState::hasAttachedBody(const std::string &id) const
00130 {
00131 return attached_body_map_.find(id) != attached_body_map_.end();
00132 }
00133
00134 const robot_state::AttachedBody* robot_state::LinkState::getAttachedBody(const std::string &id) const
00135 {
00136 std::map<std::string, AttachedBody*>::const_iterator it = attached_body_map_.find(id);
00137 if (it == attached_body_map_.end())
00138 {
00139 logError("Attached body '%s' not found on link '%s'", id.c_str(), getName().c_str());
00140 return NULL;
00141 }
00142 else
00143 return it->second;
00144 }
00145
00146 void robot_state::LinkState::getAttachedBodies(std::vector<const AttachedBody*> &attached_bodies) const
00147 {
00148 attached_bodies.clear();
00149 attached_bodies.reserve(attached_body_map_.size());
00150 for (std::map<std::string, AttachedBody*>::const_iterator it = attached_body_map_.begin() ; it != attached_body_map_.end() ; ++it)
00151 attached_bodies.push_back(it->second);
00152 }