state_validation_service_capability.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2012, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
00036 
00037 #include "state_validation_service_capability.h"
00038 #include <moveit/robot_state/conversions.h>
00039 #include <moveit/kinematic_constraints/utils.h>
00040 #include <moveit/collision_detection/collision_tools.h>
00041 #include <eigen_conversions/eigen_msg.h>
00042 #include <moveit/move_group/capability_names.h>
00043 
00044 move_group::MoveGroupStateValidationService::MoveGroupStateValidationService():
00045   MoveGroupCapability("StateValidationService")
00046 {
00047 }
00048 
00049 void move_group::MoveGroupStateValidationService::initialize()
00050 {
00051   validity_service_ = root_node_handle_.advertiseService(STATE_VALIDITY_SERVICE_NAME, &MoveGroupStateValidationService::computeService, this);
00052 }
00053 
00054 bool move_group::MoveGroupStateValidationService::computeService(moveit_msgs::GetStateValidity::Request &req, moveit_msgs::GetStateValidity::Response &res)
00055 {
00056   planning_scene_monitor::LockedPlanningSceneRO ls(context_->planning_scene_monitor_);
00057   robot_state::RobotState rs = ls->getCurrentState();
00058   robot_state::robotStateMsgToRobotState(req.robot_state, rs);
00059 
00060   res.valid = true;
00061 
00062   // configure collision request
00063   collision_detection::CollisionRequest creq;
00064   creq.group_name = req.group_name;
00065   creq.cost = true;
00066   creq.contacts = true;
00067   creq.max_contacts = ls->getWorld()->size();
00068   creq.max_cost_sources = creq.max_contacts + ls->getRobotModel()->getLinkModelsWithCollisionGeometry().size();
00069   creq.max_contacts *= creq.max_contacts;
00070   collision_detection::CollisionResult cres;
00071 
00072   // check collision
00073   ls->checkCollision(creq, cres, rs);
00074 
00075   // copy contacts if any
00076   if (cres.collision)
00077   {
00078     ros::Time time_now = ros::Time::now();
00079     res.contacts.reserve(cres.contact_count);
00080     res.valid = false;
00081     for (collision_detection::CollisionResult::ContactMap::const_iterator it = cres.contacts.begin() ; it != cres.contacts.end() ; ++it)
00082       for (std::size_t k = 0 ; k < it->second.size() ; ++k)
00083       {
00084         res.contacts.resize(res.contacts.size() + 1);
00085         collision_detection::contactToMsg(it->second[k], res.contacts.back());
00086         res.contacts.back().header.frame_id = ls->getPlanningFrame();
00087         res.contacts.back().header.stamp = time_now;
00088       }
00089   }
00090 
00091   // copy cost sources
00092   res.cost_sources.reserve(cres.cost_sources.size());
00093   for (std::set<collision_detection::CostSource>::const_iterator it = cres.cost_sources.begin() ; it != cres.cost_sources.end() ; ++it)
00094   {
00095     res.cost_sources.resize(res.cost_sources.size() + 1);
00096     collision_detection::costSourceToMsg(*it, res.cost_sources.back());
00097   }
00098 
00099   // evaluate constraints
00100   if (!kinematic_constraints::isEmpty(req.constraints))
00101   {
00102     kinematic_constraints::KinematicConstraintSet kset(ls->getRobotModel());
00103     kset.add(req.constraints, ls->getTransforms());
00104     std::vector<kinematic_constraints::ConstraintEvaluationResult> kres;
00105     kinematic_constraints::ConstraintEvaluationResult total_result = kset.decide(rs, kres);
00106     if (!total_result.satisfied)
00107       res.valid = false;
00108 
00109     // copy constraint results
00110     res.constraint_result.resize(kres.size());
00111     for (std::size_t k = 0 ; k < kres.size() ; ++k)
00112     {
00113       res.constraint_result[k].result = kres[k].satisfied;
00114       res.constraint_result[k].distance = kres[k].distance;
00115     }
00116   }
00117 
00118   return true;
00119 }
00120 
00121 
00122 #include <class_loader/class_loader.h>
00123 CLASS_LOADER_REGISTER_CLASS(move_group::MoveGroupStateValidationService, move_group::MoveGroupCapability)


move_group
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Oct 6 2014 02:32:44