56                                                      moveit_msgs::GetStateValidity::Response& res)
 
   69   creq.
max_contacts = ls->getWorld()->size() + ls->getRobotModel()->getLinkModelsWithCollisionGeometry().size();
 
   75   ls->checkCollision(creq, cres, rs);
 
   83     for (collision_detection::CollisionResult::ContactMap::const_iterator it = cres.
contacts.begin();
 
   87         res.contacts.resize(res.contacts.size() + 1);
 
   89         res.contacts.back().header.frame_id = ls->getPlanningFrame();
 
   90         res.contacts.back().header.stamp = time_now;
 
   98     res.cost_sources.resize(res.cost_sources.size() + 1);
 
  106     kset.add(req.constraints, ls->getTransforms());
 
  107     std::vector<kinematic_constraints::ConstraintEvaluationResult> kres;
 
  113     res.constraint_result.resize(kres.size());
 
  114     for (std::size_t k = 0; k < kres.size(); ++k)
 
  116       res.constraint_result[k].result = kres[k].
satisfied;
 
  117       res.constraint_result[k].distance = kres[k].distance;