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 
00037 #include <planning_models/kinematic_state.h>
00038 
00039 planning_models::KinematicState::KinematicState(const boost::shared_ptr<const KinematicModel> kinematic_model) :
00040   kinematic_model_(kinematic_model), dimension_(0)
00041 {
00042   kinematic_model_->sharedLock();
00043 
00044   const std::vector<KinematicModel::JointModel*>& joint_model_vector = kinematic_model_->getJointModels();
00045   joint_state_vector_.resize(joint_model_vector.size());
00046   
00047   unsigned int vector_index_counter = 0;
00048   for(unsigned int i = 0; i < joint_model_vector.size(); i++) {
00049     joint_state_vector_[i] = new JointState(joint_model_vector[i]);
00050     joint_state_map_[joint_state_vector_[i]->getName()] = joint_state_vector_[i];
00051     unsigned int joint_dim = joint_state_vector_[i]->getDimension();
00052     dimension_ += joint_dim;
00053     const std::vector<std::string>& name_order = joint_state_vector_[i]->getJointStateNameOrder();
00054     for(unsigned int j = 0; j < name_order.size(); j++) {
00055       joint_state_map_[name_order[j]] = joint_state_vector_[i];
00056       kinematic_state_index_map_[name_order[j]] = vector_index_counter+j;
00057     }
00058     vector_index_counter += joint_dim;
00059   }
00060   const std::vector<KinematicModel::LinkModel*>& link_model_vector = kinematic_model_->getLinkModels();
00061   link_state_vector_.resize(link_model_vector.size());
00062   for(unsigned int i = 0; i < link_model_vector.size(); i++) {
00063     link_state_vector_[i] = new LinkState(link_model_vector[i]);
00064     link_state_map_[link_state_vector_[i]->getName()] = link_state_vector_[i];
00065     for(unsigned int j = 0; j < link_state_vector_[i]->getAttachedBodyStateVector().size(); j++) {
00066       attached_body_state_vector_.push_back(link_state_vector_[i]->getAttachedBodyStateVector()[j]);
00067     }
00068   }
00069   setLinkStatesParents();
00070 
00071   
00072   const std::map<std::string,KinematicModel::JointModelGroup*>& joint_model_group_map = kinematic_model_->getJointModelGroupMap();
00073   for(std::map<std::string,KinematicModel::JointModelGroup*>::const_iterator it = joint_model_group_map.begin();
00074       it != joint_model_group_map.end();
00075       it++) {
00076     joint_state_group_map_[it->first] = new JointStateGroup(it->second, this);
00077   }
00078 }
00079 
00080 planning_models::KinematicState::KinematicState(const KinematicState* ks) :
00081   kinematic_model_(ks->getKinematicModel())
00082 {
00083   kinematic_model_->sharedLock();
00084   const std::vector<JointState*>& joint_states_vector = ks->getJointStateVector();
00085   unsigned int vector_index_counter = 0;
00086   for(unsigned int i = 0; i < joint_states_vector.size(); i++) {
00087     joint_state_vector_[i] = new JointState(joint_state_vector_[i]->getJointModel());
00088     joint_state_map_[joint_state_vector_[i]->getName()] = joint_state_vector_[i];
00089     const std::vector<std::string>& name_order = joint_state_vector_[i]->getJointStateNameOrder();
00090     for(unsigned int j = 0; j < name_order.size(); j++) {
00091       joint_state_map_[name_order[j]] = joint_state_vector_[i];
00092       kinematic_state_index_map_[name_order[j]] = vector_index_counter+j;
00093     }
00094     unsigned int joint_dim = joint_state_vector_[i]->getDimension();
00095     dimension_ += joint_dim;
00096     vector_index_counter += joint_dim;
00097     
00098     
00099   }
00100   const std::vector<LinkState*>& link_state_vector = ks->getLinkStateVector();
00101   for(unsigned int i = 0; i < link_state_vector.size(); i++) {
00102     link_state_vector_[i] = new LinkState(link_state_vector[i]->getLinkModel());
00103     link_state_map_[link_state_vector_[i]->getName()] = link_state_vector_[i];
00104     for(unsigned int j = 0; j < link_state_vector_[i]->getAttachedBodyStateVector().size(); j++) {
00105       attached_body_state_vector_.push_back(link_state_vector_[i]->getAttachedBodyStateVector()[j]);
00106     }
00107   }
00108   setLinkStatesParents();
00109   
00110   const std::map<std::string, JointStateGroup*>& joint_state_groups_map = ks->getJointStateGroupMap();
00111   for(std::map<std::string, JointStateGroup*>::const_iterator it = joint_state_groups_map.begin();
00112       it != joint_state_groups_map.end();
00113       it++) {
00114     joint_state_group_map_[it->first] = new JointStateGroup(it->second->getJointModelGroup(), this);
00115   }
00116 }
00117 
00118 planning_models::KinematicState::~KinematicState() 
00119 {
00120   kinematic_model_->sharedUnlock();
00121   for(unsigned int i = 0; i < joint_state_vector_.size(); i++) {
00122     delete joint_state_vector_[i];
00123   }
00124   for(unsigned int i = 0; i < link_state_vector_.size(); i++) {
00125     delete link_state_vector_[i];
00126   }
00127   for(std::map<std::string, JointStateGroup*>::iterator it = joint_state_group_map_.begin();
00128       it != joint_state_group_map_.end();
00129       it++) {
00130     delete it->second;
00131   }
00132 }
00133 
00134 bool planning_models::KinematicState::setKinematicState(const std::vector<double>& joint_state_values) {
00135   if(joint_state_values.size() != dimension_) return false;
00136   unsigned int value_counter = 0;
00137   for(unsigned int i = 0; i < joint_state_vector_.size(); i++) {
00138     unsigned int dim = joint_state_vector_[i]->getDimension();
00139     if(dim != 0) {
00140       std::vector<double> vec(dim, 0.0); 
00141       copy(joint_state_values.begin()+value_counter,
00142            joint_state_values.begin()+value_counter+dim,
00143            vec.begin());
00144       bool ok = joint_state_vector_[i]->setJointStateValues(vec);
00145       if(!ok) {
00146         ROS_WARN("Joint state unhappy");
00147       }
00148       value_counter += dim;
00149     }
00150   }
00151   updateKinematicLinks();
00152   return true;
00153 }
00154 
00155 bool planning_models::KinematicState::setKinematicState(const std::map<std::string, double>& joint_state_map) 
00156 {
00157   bool all_set = true;
00158   for(unsigned int i = 0; i < joint_state_vector_.size(); i++) {
00159     bool is_set = joint_state_vector_[i]->setJointStateValues(joint_state_map);
00160     if(!is_set) all_set = false;
00161   }
00162   updateKinematicLinks();
00163   return all_set;
00164 }
00165 
00166 void planning_models::KinematicState::getKinematicStateValues(std::vector<double>& joint_state_values) const {
00167   joint_state_values.clear();
00168   for(unsigned int i = 0; i < joint_state_vector_.size(); i++) {
00169     unsigned int dim = joint_state_vector_[i]->getDimension();  
00170     if(dim != 0) {
00171       for(unsigned int j = 0; j < joint_state_vector_[i]->getJointStateValues().size(); j++) {
00172         joint_state_values.push_back(joint_state_vector_[i]->getJointStateValues()[j]);
00173       }
00174     }
00175   }
00176   if(joint_state_values.size() != dimension_) {
00177     ROS_WARN("Some problem with dimension");
00178   }
00179 }
00180 
00181 void planning_models::KinematicState::getKinematicStateValues(std::map<std::string,double>& joint_state_values) const {
00182   joint_state_values.clear();
00183   for(unsigned int i = 0; i < joint_state_vector_.size(); i++) {
00184     unsigned int dim = joint_state_vector_[i]->getDimension();  
00185     if(dim != 0) {
00186       for(unsigned int j = 0; j < joint_state_vector_[i]->getJointStateValues().size(); j++) {
00187         joint_state_values[joint_state_vector_[i]->getJointStateNameOrder()[j]] = joint_state_vector_[i]->getJointStateValues()[j]; 
00188       }
00189     }
00190   }
00191   if(joint_state_values.size() != dimension_) {
00192     ROS_WARN("Some problems with dimension");
00193   }
00194 }
00195 
00196 void planning_models::KinematicState::updateKinematicLinks() 
00197 {
00198   for(unsigned int i = 0; i < link_state_vector_.size(); i++) {
00199     link_state_vector_[i]->computeTransform();
00200   }
00201 }
00202 
00203 bool planning_models::KinematicState::updateKinematicStateWithLinkAt(const std::string& link_name, const btTransform& transform)
00204 {
00205   if(!hasLinkState(link_name)) return false;
00206 
00207   link_state_map_.find(link_name)->second->updateGivenGlobalLinkTransform(transform);
00208   std::vector<LinkState*> child_links = getChildLinkStates(link_name);
00209   for(unsigned int i = 0; i < child_links.size(); i++) {
00210     child_links[i]->computeTransform();
00211   }
00212   return true;
00213 }
00214 
00215 std::vector<planning_models::KinematicState::LinkState*> planning_models::KinematicState::getChildLinkStates(const std::string& link_name) const {
00216   std::vector<LinkState*> child_link_states;
00217   std::vector<const KinematicModel::LinkModel*> child_link_models;
00218   kinematic_model_->getChildLinkModels(kinematic_model_->getLinkModel(link_name), child_link_models);
00219   for(unsigned int i = 0; i < child_link_models.size(); i++) {
00220     child_link_states.push_back(link_state_map_.find((child_link_models[i]->getName()))->second);
00221   }
00222   return child_link_states;
00223 }
00224 
00225 void planning_models::KinematicState::setKinematicStateToDefault(void)
00226 {
00227   std::map<std::string, double> default_joint_states;
00228 
00229   const unsigned int js = joint_state_vector_.size();
00230   for (unsigned int i = 0  ; i < js ; ++i)
00231   {
00232     for(std::map<std::string, std::pair<double,double> >::const_iterator it = joint_state_vector_[i]->getAllJointValueBounds().begin();
00233         it != joint_state_vector_[i]->getAllJointValueBounds().end();
00234         it++) {
00235       std::pair<double,double> bounds = it->second;
00236       if(bounds.first <= 0.0 && bounds.second >= 0.0) {
00237         default_joint_states[it->first] = 0.0;
00238       } else {
00239         default_joint_states[it->first] = (bounds.first+bounds.second)/2.0;
00240       }
00241     }
00242   }
00243   setKinematicState(default_joint_states);
00244 }
00245 
00246 bool planning_models::KinematicState::isJointWithinBounds(const std::string& joint) const {
00247   const JointState* joint_state = getJointState(joint);
00248   if(joint_state == NULL) {
00249     ROS_WARN_STREAM("No joint with name " << joint);
00250     return false;
00251   }
00252   return(joint_state->areJointStateValuesWithinBounds());
00253 }
00254 
00255 bool planning_models::KinematicState::areJointsWithinBounds(const std::vector<std::string>& joints) const
00256 {
00257   for(std::vector<std::string>::const_iterator it = joints.begin();
00258       it != joints.end();
00259       it++) {
00260     const JointState* joint_state = getJointState(*it);
00261     if(joint_state == NULL) {
00262       ROS_WARN_STREAM("No joint with name " << *it);
00263       return false;
00264     }
00265     if(!joint_state->areJointStateValuesWithinBounds()) {
00266       return false;
00267     }
00268   }   
00269   return true;
00270 }
00271 
00272 void planning_models::KinematicState::setLinkStatesParents() {
00273   
00274   for(unsigned int i = 0; i < link_state_vector_.size(); i++) {
00275     const KinematicModel::JointModel* parent_joint_model = link_state_vector_[i]->getLinkModel()->getParentJointModel();
00276     if(parent_joint_model == NULL) {
00277       ROS_WARN("Parent joint really should be NULL");
00278       continue;
00279     }
00280     if(joint_state_map_.find(parent_joint_model->getName()) == joint_state_map_.end()) {
00281       ROS_WARN_STREAM("Don't have a joint state for parent joint " << parent_joint_model->getName());
00282       continue;
00283     }
00284     link_state_vector_[i]->setParentJointState(joint_state_map_[parent_joint_model->getName()]);
00285     if(parent_joint_model->getParentLinkModel() != NULL) {
00286       if(link_state_map_.find(parent_joint_model->getParentLinkModel()->getName()) == link_state_map_.end()) {
00287         ROS_WARN_STREAM("Don't have a link state for parent link " << parent_joint_model->getParentLinkModel()->getName());
00288         continue;
00289       }
00290       link_state_vector_[i]->setParentLinkState(link_state_map_[parent_joint_model->getParentLinkModel()->getName()]);
00291     }
00292   }
00293 }
00294 
00295 const planning_models::KinematicState::JointStateGroup* planning_models::KinematicState::getJointStateGroup(const std::string &name) const
00296 {
00297   if(joint_state_group_map_.find(name) == joint_state_group_map_.end()) return NULL;
00298   return joint_state_group_map_.find(name)->second;
00299 }
00300 
00301 planning_models::KinematicState::JointStateGroup* planning_models::KinematicState::getJointStateGroup(const std::string &name)
00302 {
00303   if(joint_state_group_map_.find(name) == joint_state_group_map_.end()) return NULL;
00304   return joint_state_group_map_.find(name)->second;
00305 }
00306 
00307 bool planning_models::KinematicState::hasJointStateGroup(const std::string &name) const
00308 {
00309   return(joint_state_group_map_.find(name) != joint_state_group_map_.end());
00310 }
00311 
00312 void planning_models::KinematicState::getJointStateGroupNames(std::vector<std::string>& names) const 
00313 {
00314   for(std::map<std::string, JointStateGroup*>::const_iterator it = joint_state_group_map_.begin();
00315       it != joint_state_group_map_.end();
00316       it++) {
00317     names.push_back(it->first);
00318   }
00319 }
00320 
00321 bool planning_models::KinematicState::hasJointState(const std::string &joint) const
00322 {
00323   return joint_state_map_.find(joint) != joint_state_map_.end();
00324 }
00325 bool planning_models::KinematicState::hasLinkState(const std::string& link) const
00326 {
00327   return (link_state_map_.find(link) != link_state_map_.end());
00328 }
00329 
00330 planning_models::KinematicState::JointState* planning_models::KinematicState::getJointState(const std::string &joint) const
00331 {
00332   if(!hasJointState(joint)) return NULL;
00333   return joint_state_map_.find(joint)->second;
00334 }
00335 
00336 planning_models::KinematicState::LinkState* planning_models::KinematicState::getLinkState(const std::string &link) const
00337 {
00338   if(!hasLinkState(link)) return NULL;
00339   return link_state_map_.find(link)->second;
00340 }
00341 
00342 planning_models::KinematicState::AttachedBodyState* planning_models::KinematicState::getAttachedBodyState(const std::string &att) const
00343 {
00344   for(unsigned int i = 0; i < link_state_vector_.size(); i++) {
00345     for(unsigned int j = 0; j < link_state_vector_[i]->getAttachedBodyStateVector().size(); j++) {
00346       if(link_state_vector_[i]->getAttachedBodyStateVector()[j]->getName() == att) {
00347         return (link_state_vector_[i]->getAttachedBodyStateVector()[j]);
00348       }
00349     }
00350   }
00351   return NULL;
00352 }
00353 
00354 
00355 
00356 planning_models::KinematicState::JointState::JointState(const planning_models::KinematicModel::JointModel* jm) :
00357   joint_model_(jm)
00358 {
00359   variable_transform_.setIdentity();
00360   joint_state_values_ = joint_model_->computeJointStateValues(variable_transform_);
00361   joint_state_name_order_.resize(joint_state_values_.size());
00362 
00363   unsigned int i = 0;
00364   for(std::map<unsigned int, std::string>::const_iterator it = joint_model_->getComputatationOrderMapIndex().begin();
00365       it != joint_model_->getComputatationOrderMapIndex().end();
00366       it++,i++) {
00367     if(i != it->first) {
00368       ROS_WARN("Missing value");
00369       continue;
00370     }
00371     joint_state_index_map_[it->second] = it->first;
00372     joint_state_name_order_[i] = it->second;
00373   }
00374 }
00375 
00376 bool planning_models::KinematicState::JointState::setJointStateValues(const std::vector<double>& joint_state_values) {
00377   if(joint_state_values.size() != joint_state_index_map_.size()) {
00378     return false;
00379   }
00380   joint_state_values_ = joint_state_values;
00381   variable_transform_ = joint_model_->computeTransform(joint_state_values);
00382   return true;
00383 }
00384 
00385 bool planning_models::KinematicState::JointState::setJointStateValues(const std::map<std::string, double>& joint_value_map) {
00386   std::map<std::string, bool> seen_already;
00387   for(std::map<std::string, double>::const_iterator it = joint_value_map.begin();
00388       it != joint_value_map.end();
00389       it++) {
00390     std::map<std::string,unsigned int>::iterator it2 = joint_state_index_map_.find(it->first);
00391     if(it2 != joint_state_index_map_.end()) {
00392       seen_already[it->first] = true;
00393       if(it2->second > joint_state_values_.size()) {
00394         ROS_WARN_STREAM("Trying to set value " << it2->second << " which is larger than joint state values size " << joint_state_values_.size());
00395       } else {
00396         joint_state_values_[it2->second] = it->second;
00397       }
00398     }
00399   }
00400   variable_transform_ = joint_model_->computeTransform(joint_state_values_);
00401   if(seen_already.size() != joint_state_index_map_.size()) {
00402     return false;
00403   }
00404   return true;
00405 }
00406 
00407 bool planning_models::KinematicState::JointState::setJointStateValues(const btTransform& transform) {
00408   variable_transform_ = transform;
00409   joint_state_values_ = joint_model_->computeJointStateValues(variable_transform_);
00410   return true;
00411 }
00412 
00413 bool planning_models::KinematicState::JointState::allJointStateValuesAreDefined(const std::map<std::string, double>& joint_value_map) const {
00414   for(planning_models::KinematicModel::JointModel::js_type::const_iterator it = joint_model_->getJointStateEquivalents().begin();
00415       it != joint_model_->getJointStateEquivalents().end();
00416       it++) {
00417     if(joint_value_map.find(it->right) == joint_value_map.end()) {
00418       return false;
00419     }
00420   }
00421   return true;
00422 }
00423 
00424 const std::vector<double>& planning_models::KinematicState::JointState::getJointStateValues() const {
00425   return joint_state_values_;
00426 }
00427 
00428 const std::vector<std::string>& planning_models::KinematicState::JointState::getJointStateNameOrder() const {
00429   return joint_state_name_order_;
00430 }
00431 
00432 bool planning_models::KinematicState::JointState::getJointValueBounds(const std::string& value_name,
00433                                                                       double& low, 
00434                                                                       double& high) const {
00435   if(!joint_model_->hasVariable(value_name)) return false;
00436   std::pair<double,double> bounds = joint_model_->getVariableBounds(value_name);
00437   low = bounds.first;
00438   high = bounds.second;
00439   return true;
00440 }
00441 
00442 const std::map<std::string, std::pair<double, double> >& planning_models::KinematicState::JointState::getAllJointValueBounds() const 
00443 {
00444   return joint_model_->getAllVariableBounds();
00445 }
00446 
00447 bool planning_models::KinematicState::JointState::areJointStateValuesWithinBounds() const {
00448   for(std::map<std::string, unsigned int>::const_iterator it = joint_state_index_map_.begin();
00449       it != joint_state_index_map_.end();
00450       it++) {
00451     std::pair<double,double> bounds = joint_model_->getVariableBounds(it->first);
00452     if(joint_state_values_[it->second] < bounds.first || joint_state_values_[it->second] > bounds.second) {
00453       return false;
00454     }
00455   }
00456   return true;
00457 }
00458 
00459 
00460 
00461 planning_models::KinematicState::LinkState::LinkState(const planning_models::KinematicModel::LinkModel* lm) :
00462   link_model_(lm), parent_joint_state_(NULL), parent_link_state_(NULL)
00463 {
00464   global_link_transform_.setIdentity();
00465   global_collision_body_transform_.setIdentity();
00466   const std::vector<planning_models::KinematicModel::AttachedBodyModel*>& attached_body_vector = link_model_->getAttachedBodyModels();
00467   attached_body_state_vector_.resize(attached_body_vector.size());
00468   unsigned int j = 0;
00469   for(std::vector<planning_models::KinematicModel::AttachedBodyModel*>::const_iterator it = attached_body_vector.begin();
00470       it != attached_body_vector.end();
00471       it++, j++) {
00472     attached_body_state_vector_[j] = new AttachedBodyState(*it, this);
00473   }
00474 }
00475 
00476 planning_models::KinematicState::LinkState::~LinkState() 
00477 {
00478   for(unsigned int i = 0; i < attached_body_state_vector_.size(); i++) {
00479     delete attached_body_state_vector_[i];
00480   }
00481 }
00482 
00483 void planning_models::KinematicState::LinkState::computeTransform() {
00484   btTransform ident;
00485   ident.setIdentity();
00486   global_link_transform_.mult(parent_link_state_ ? parent_link_state_->global_link_transform_ : ident, link_model_->getJointOriginTransform());
00487   global_link_transform_ *= parent_joint_state_->getVariableTransform();
00488   global_collision_body_transform_.mult(global_link_transform_, link_model_->getCollisionOriginTransform());
00489   updateAttachedBodies();
00490 }
00491 
00492 void planning_models::KinematicState::LinkState::updateAttachedBodies() 
00493 {
00494   for (unsigned int i = 0 ; i < attached_body_state_vector_.size() ; ++i) {
00495     attached_body_state_vector_[i]->computeTransform();
00496   }
00497 }
00498 
00499 
00500 
00501 planning_models::KinematicState::AttachedBodyState::AttachedBodyState(const planning_models::KinematicModel::AttachedBodyModel* abm,
00502                                                                       const planning_models::KinematicState::LinkState* parent_link_state) :
00503   attached_body_model_(abm),
00504   parent_link_state_(parent_link_state)
00505 {
00506   global_collision_body_transforms_.resize(attached_body_model_->getAttachedBodyFixedTransforms().size());
00507   for(unsigned int i = 0; i < attached_body_model_->getAttachedBodyFixedTransforms().size(); i++) {
00508     global_collision_body_transforms_[i].setIdentity();
00509   }
00510 }
00511 
00512 void planning_models::KinematicState::AttachedBodyState::computeTransform() 
00513 {
00514   for(unsigned int i = 0; i < global_collision_body_transforms_.size(); i++) {
00515     global_collision_body_transforms_[i] = parent_link_state_->getGlobalLinkTransform() * attached_body_model_->getAttachedBodyFixedTransforms()[i];
00516   }
00517 }
00518 
00519 
00520 
00521 planning_models::KinematicState::JointStateGroup::JointStateGroup(const planning_models::KinematicModel::JointModelGroup* jmg, 
00522                                                                   const planning_models::KinematicState* kinematic_state) : 
00523   joint_model_group_(jmg), dimension_(0)
00524 {
00525   const std::vector<const KinematicModel::JointModel*>& joint_model_vector = jmg->getJointModels();
00526   unsigned int vector_index_counter = 0;
00527   for(unsigned int i = 0; i < joint_model_vector.size(); i++) {
00528     if(!kinematic_state->hasJointState(joint_model_vector[i]->getName())) {
00529       ROS_WARN_STREAM("No joint state for group joint name " << joint_model_vector[i]->getName());
00530       continue;
00531     }
00532     JointState* js = kinematic_state->getJointState(joint_model_vector[i]->getName());
00533     joint_state_vector_.push_back(js);
00534     joint_names_.push_back(joint_model_vector[i]->getName());
00535     joint_state_map_[joint_model_vector[i]->getName()] = js;
00536     unsigned int joint_dim = joint_state_vector_[i]->getDimension();
00537     dimension_ += joint_dim;
00538     const std::vector<std::string>& name_order = joint_state_vector_[i]->getJointStateNameOrder();
00539     for(unsigned int i = 0; i < name_order.size(); i++) {
00540       kinematic_state_index_map_[name_order[i]] = vector_index_counter+i;
00541     }
00542     vector_index_counter += joint_dim;
00543   }
00544   const std::vector<const KinematicModel::LinkModel*>& link_model_vector = jmg->getUpdatedLinkModels();
00545   for(unsigned int i = 0; i < link_model_vector.size(); i++) {
00546     if(!kinematic_state->hasLinkState(link_model_vector[i]->getName())) {
00547       ROS_WARN_STREAM("No link state for link joint name " << link_model_vector[i]->getName());
00548       continue;
00549     }
00550     LinkState* ls = kinematic_state->getLinkState(link_model_vector[i]->getName());
00551     updated_links_.push_back(ls);
00552   }
00553 
00554   const std::vector<const KinematicModel::JointModel*>& joint_root_vector = jmg->getJointRoots();
00555   for(unsigned int i = 0; i < joint_root_vector.size(); i++) {
00556     joint_roots_.push_back(joint_state_map_[joint_root_vector[i]->getName()]);
00557   }
00558 }
00559 
00560 bool planning_models::KinematicState::JointStateGroup::hasJointState(const std::string &joint) const
00561 {
00562   return joint_state_map_.find(joint) != joint_state_map_.end();
00563 }
00564 bool planning_models::KinematicState::JointStateGroup::updatesLinkState(const std::string& link) const
00565 {
00566   for(unsigned int i = 0; i < updated_links_.size(); i++) {
00567     if(updated_links_[i]->getName() == link) return true;
00568   }
00569   return false;
00570 }
00571 
00572 bool planning_models::KinematicState::JointStateGroup::setKinematicState(const std::vector<double>& joint_state_values) {
00573   if(joint_state_values.size() != dimension_) return false;
00574   unsigned int value_counter = 0;
00575   for(unsigned int i = 0; i < joint_state_vector_.size(); i++) {
00576     unsigned int dim = joint_state_vector_[i]->getDimension();
00577     if(dim != 0) {
00578       std::vector<double> vec(dim); 
00579       copy(joint_state_values.begin()+value_counter,
00580            joint_state_values.begin()+value_counter+dim,
00581            vec.begin());
00582       bool ok = joint_state_vector_[i]->setJointStateValues(vec);
00583       if(!ok) {
00584         ROS_WARN("Joint state unhappy");
00585       }
00586       value_counter += dim;
00587     }
00588   }
00589   updateKinematicLinks();
00590   return true;
00591 }
00592 
00593 bool planning_models::KinematicState::JointStateGroup::setKinematicState(const std::map<std::string, double>& joint_state_map) 
00594 {
00595   bool all_set = true;
00596   for(unsigned int i = 0; i < joint_state_vector_.size(); i++) {
00597     bool is_set = joint_state_vector_[i]->setJointStateValues(joint_state_map);
00598     if(!is_set) all_set = false;
00599   }
00600   updateKinematicLinks();
00601   return all_set;
00602 }
00603 
00604 void planning_models::KinematicState::JointStateGroup::updateKinematicLinks() 
00605 {
00606   for(unsigned int i = 0; i < updated_links_.size(); i++) {
00607     updated_links_[i]->computeTransform();
00608   }
00609 }
00610 
00611 void planning_models::KinematicState::JointStateGroup::setKinematicStateToDefault(void)
00612 {
00613   std::map<std::string, double> default_joint_states;
00614 
00615   const unsigned int js = joint_state_vector_.size();
00616   for (unsigned int i = 0  ; i < js ; ++i)
00617   {
00618     for(std::map<std::string, std::pair<double,double> >::const_iterator it = joint_state_vector_[i]->getAllJointValueBounds().begin();
00619         it != joint_state_vector_[i]->getAllJointValueBounds().end();
00620         it++) {
00621       std::pair<double,double> bounds = it->second;
00622       if(bounds.first <= 0.0 && bounds.second >= 0.0) {
00623         default_joint_states[it->first] = 0.0;
00624       } else {
00625         default_joint_states[it->first] = (bounds.first+bounds.second)/2.0;
00626       }
00627     }
00628   }
00629   setKinematicState(default_joint_states);
00630 }
00631 
00632 void planning_models::KinematicState::JointStateGroup::getKinematicStateValues(std::vector<double>& joint_state_values) const {
00633   joint_state_values.clear();
00634   for(unsigned int i = 0; i < joint_state_vector_.size(); i++) {
00635     unsigned int dim = joint_state_vector_[i]->getDimension();  
00636     if(dim != 0) {
00637       for(unsigned int j = 0; j < joint_state_vector_[i]->getJointStateValues().size(); j++) {
00638         joint_state_values.push_back(joint_state_vector_[i]->getJointStateValues()[j]);
00639       }
00640     }
00641   }
00642   if(joint_state_values.size() != dimension_) {
00643     ROS_WARN("Some problem with dimension");
00644   }
00645 }
00646 
00647 void planning_models::KinematicState::JointStateGroup::getKinematicStateValues(std::map<std::string,double>& joint_state_values) const {
00648   joint_state_values.clear();
00649   for(unsigned int i = 0; i < joint_state_vector_.size(); i++) {
00650     unsigned int dim = joint_state_vector_[i]->getDimension();  
00651     if(dim != 0) {
00652       for(unsigned int j = 0; j < joint_state_vector_[i]->getJointStateValues().size(); j++) {
00653         joint_state_values[joint_state_vector_[i]->getJointStateNameOrder()[j]] = joint_state_vector_[i]->getJointStateValues()[j]; 
00654       }
00655     }
00656   }
00657   if(joint_state_values.size() != dimension_) {
00658     ROS_WARN("Some problems with dimension");
00659   }
00660 }
00661 
00662 planning_models::KinematicState::JointState* planning_models::KinematicState::JointStateGroup::getJointState(const std::string &joint) const
00663 {
00664   if(!hasJointState(joint)) return NULL;
00665   return joint_state_map_.find(joint)->second;
00666 }
00667 
00668 
00669 
00670 void planning_models::KinematicState::printStateInfo(std::ostream &out) const
00671 {
00672   out << "Complete model state dimension = " << getDimension() << std::endl;
00673     
00674   std::ios_base::fmtflags old_flags = out.flags();    
00675   out.setf(std::ios::fixed, std::ios::floatfield);
00676   std::streamsize old_prec = out.precision();
00677   out.precision(5);
00678   out << "State bounds: ";
00679   for(unsigned int i = 0; i < joint_state_vector_.size(); i++) {
00680     for(std::map<std::string, std::pair<double, double> >::const_iterator it = joint_state_vector_[i]->getAllJointValueBounds().begin();
00681         it != joint_state_vector_[i]->getAllJointValueBounds().end();
00682         it++) {
00683       if(it->second.first == -DBL_MAX) {
00684         out << "[-DBL_MAX, ";
00685       } else {
00686         out << "[" << it->second.first << ", ";
00687       }
00688       if(it->second.second == DBL_MAX) {
00689         out << "DBL_MAX] ";
00690       } else {
00691         out << it->second.second << "] ";  
00692       }
00693     }
00694   }
00695     
00696   out << std::endl;
00697   out.precision(old_prec);    
00698   out.flags(old_flags);
00699         
00700   out << "Root joint : ";
00701   out << kinematic_model_->getRoot()->getName() << " ";
00702   out << std::endl;
00703     
00704   out << "Available groups: ";
00705   std::vector<std::string> l;
00706   getJointStateGroupNames(l);
00707   for (unsigned int i = 0 ; i < l.size() ; ++i)
00708     out << l[i] << " ";
00709   out << std::endl;
00710     
00711   for (unsigned int i = 0 ; i < l.size() ; ++i)
00712   {
00713     const JointStateGroup *g = getJointStateGroup(l[i]);
00714     out << "Group " << l[i] << " has " << g->getJointRoots().size() << " roots: ";
00715     for (unsigned int j = 0 ; j < g->getJointRoots().size() ; ++j)
00716       out << g->getJointRoots()[j]->getName() << " ";
00717     out << std::endl;
00718   }
00719 }
00720 
00721 void planning_models::KinematicState::printTransform(const std::string &st, const btTransform &t, std::ostream &out) const
00722 {
00723   out << st << std::endl;
00724   const btVector3 &v = t.getOrigin();
00725   out << "  origin: " << v.x() << ", " << v.y() << ", " << v.z() << std::endl;
00726   const btQuaternion &q = t.getRotation();
00727   out << "  quaternion: " << q.x() << ", " << q.y() << ", " << q.z() << ", " << q.w() << std::endl;
00728 }
00729 
00730 void planning_models::KinematicState::printTransforms(std::ostream &out) const
00731 {
00732   out << "Joint transforms:" << std::endl;
00733   for (unsigned int i = 0 ; i < joint_state_vector_.size() ; ++i)
00734   {
00735     printTransform(joint_state_vector_[i]->getName(), joint_state_vector_[i]->getVariableTransform(), out);
00736     out << std::endl;   
00737   }
00738   out << "Link poses:" << std::endl;
00739   for (unsigned int i = 0 ; i < link_state_vector_.size() ; ++i)
00740   {
00741     printTransform(link_state_vector_[i]->getName(), link_state_vector_[i]->getGlobalCollisionBodyTransform(), out);
00742     out << std::endl;   
00743   }    
00744 }
00745