56 moveit_msgs::GetStateValidity::Response& res)
59 robot_state::RobotState rs = ls->getCurrentState();
60 robot_state::robotStateMsgToRobotState(req.robot_state, rs);
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();
85 for (std::size_t k = 0; k < it->second.size(); ++k)
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;
96 for (std::set<collision_detection::CostSource>::const_iterator it = cres.
cost_sources.begin();
99 res.cost_sources.resize(res.cost_sources.size() + 1);
107 kset.
add(req.constraints, ls->getTransforms());
108 std::vector<kinematic_constraints::ConstraintEvaluationResult> kres;
114 res.constraint_result.resize(kres.size());
115 for (std::size_t k = 0; k < kres.size(); ++k)
117 res.constraint_result[k].result = kres[k].
satisfied;
118 res.constraint_result[k].distance = kres[k].distance;
static const std::string STATE_VALIDITY_SERVICE_NAME
bool isEmpty(const moveit_msgs::Constraints &constr)
MoveGroupStateValidationService()
void costSourceToMsg(const CostSource &cost_source, moveit_msgs::CostSource &msg)
void contactToMsg(const Contact &contact, moveit_msgs::ContactInformation &msg)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
std::size_t contact_count
MoveGroupContextPtr context_
std::set< CostSource > cost_sources
bool add(const moveit_msgs::Constraints &c, const robot_state::Transforms &tf)
bool computeService(moveit_msgs::GetStateValidity::Request &req, moveit_msgs::GetStateValidity::Response &res)
virtual void initialize()
std::size_t max_cost_sources
ros::NodeHandle root_node_handle_
ros::ServiceServer validity_service_
CLASS_LOADER_REGISTER_CLASS(Dog, Base)