collision_check.cpp
Go to the documentation of this file.
00001 
00026 #include <ros/console.h>
00027 #include <pluginlib/class_list_macros.h>
00028 #include <moveit/robot_state/conversions.h>
00029 #include "stomp_moveit/cost_functions/collision_check.h"
00030 
00031 PLUGINLIB_EXPORT_CLASS(stomp_moveit::cost_functions::CollisionCheck,stomp_moveit::cost_functions::StompCostFunction)
00032 
00033 static const int MIN_KERNEL_WINDOW_SIZE = 3;
00034 
00041 static void applyKernelSmoothing(std::size_t window_size, const Eigen::VectorXd& data, Eigen::VectorXd& smoothed)
00042 {
00043   using namespace Eigen;
00044 
00045   // allocation
00046   window_size = 2*(window_size/2) + 1;// forcing it into an odd number
00047   smoothed.setZero(data.size());
00048   VectorXd x_nneighbors = VectorXd::Zero(window_size);
00049   VectorXd y_nneighbors = VectorXd::Zero(window_size);
00050   VectorXd kernel_weights = VectorXd::Zero(window_size);
00051 
00052 
00053   // indexing
00054   int index_left, index_right;
00055   std::size_t window_index_middle = window_size/2;
00056 
00057   // kernel function
00058   //Epanechnikov(x,neighbors,lambda)
00059   auto epanechnikov_function = [](double x_m,const VectorXd& neighbors,double lambda, VectorXd& weights )
00060   {
00061 
00062     double t = 0;
00063     for(int i = 0; i < neighbors.size(); i++)
00064     {
00065       t = std::abs(x_m - neighbors(i))/lambda;
00066       if(t < 1)
00067       {
00068         weights(i) = 0.75f*(1 - std::pow(t,2));
00069       }
00070       else
00071       {
00072         weights(i) = 0;
00073       }
00074     }
00075 
00076   };
00077 
00078   for(int i = 0; i < data.size(); i++)
00079   {
00080     // middle term
00081     x_nneighbors(window_index_middle) = i;
00082     y_nneighbors(window_index_middle) = data(i);
00083 
00084     // grabbing neighbors
00085     for(int j = 1; j <= window_size/2; j++)
00086     {
00087       index_left = i - j;
00088       index_right = i + j;
00089 
00090       if(index_left < 0)
00091       {
00092         x_nneighbors(window_index_middle - j) = 0;
00093         y_nneighbors(window_index_middle - j) = data(0);
00094       }
00095       else
00096       {
00097         x_nneighbors(window_index_middle - j) = index_left;
00098         y_nneighbors(window_index_middle - j) = data(index_left);
00099       }
00100 
00101       if(index_right > data.rows()-1)
00102       {
00103         x_nneighbors(window_index_middle + j) = data.rows()-1;
00104         y_nneighbors(window_index_middle + j) = data(data.rows() - 1);
00105       }
00106       else
00107       {
00108         x_nneighbors(window_index_middle + j) = index_right;
00109         y_nneighbors(window_index_middle + j) = data(index_right);
00110       }
00111 
00112     }
00113 
00114     epanechnikov_function(i,x_nneighbors,window_size,kernel_weights);
00115     smoothed(i) = (y_nneighbors.array()*kernel_weights.array()).sum()/kernel_weights.sum();
00116   }
00117 
00118 
00119 }
00120 
00121 namespace stomp_moveit
00122 {
00123 namespace cost_functions
00124 {
00125 
00126 CollisionCheck::CollisionCheck():
00127     name_("CollisionCheckPlugin"),
00128     robot_state_(),
00129     collision_penalty_(0.0)
00130 {
00131   // TODO Auto-generated constructor stub
00132 
00133 }
00134 
00135 CollisionCheck::~CollisionCheck()
00136 {
00137   // TODO Auto-generated destructor stub
00138 }
00139 
00140 bool CollisionCheck::initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
00141                         const std::string& group_name,XmlRpc::XmlRpcValue& config)
00142 {
00143   robot_model_ptr_ = robot_model_ptr;
00144   group_name_ = group_name;
00145   return configure(config);
00146 }
00147 
00148 bool CollisionCheck::setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
00149                  const moveit_msgs::MotionPlanRequest &req,
00150                  const stomp_core::StompConfiguration &config,
00151                  moveit_msgs::MoveItErrorCodes& error_code)
00152 {
00153   using namespace moveit::core;
00154 
00155   planning_scene_ = planning_scene;
00156   plan_request_ = req;
00157   error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
00158 
00159   // initialize collision request
00160   collision_request_.group_name = group_name_;
00161   collision_request_.cost = false;
00162   collision_request_.distance = false;
00163   collision_request_.max_contacts = 1;
00164   collision_request_.max_contacts_per_pair = 1;
00165   collision_request_.contacts = true;
00166   collision_request_.verbose = false;
00167 
00168   collision_robot_ = planning_scene->getCollisionRobot();
00169   collision_world_ = planning_scene->getCollisionWorld();
00170 
00171   // storing robot state
00172   robot_state_.reset(new RobotState(robot_model_ptr_));
00173   if(!robotStateMsgToRobotState(req.start_state,*robot_state_,true))
00174   {
00175     ROS_ERROR("%s Failed to get current robot state from request",getName().c_str());
00176     return false;
00177   }
00178 
00179   // copying into intermediate robot states
00180   for(auto& rs : intermediate_coll_states_)
00181   {
00182     rs.reset(new RobotState(*robot_state_));
00183   }
00184 
00185   // allocating arrays
00186   raw_costs_ = Eigen::VectorXd::Zero(config.num_timesteps);
00187 
00188 
00189   return true;
00190 }
00191 
00192 bool CollisionCheck::computeCosts(const Eigen::MatrixXd& parameters,
00193                           std::size_t start_timestep,
00194                           std::size_t num_timesteps,
00195                           int iteration_number,
00196                           int rollout_number,
00197                           Eigen::VectorXd& costs,
00198                           bool& validity)
00199 {
00200 
00201   using namespace moveit::core;
00202   using namespace Eigen;
00203 
00204   if(!robot_state_)
00205   {
00206     ROS_ERROR("%s Robot State has not been updated",getName().c_str());
00207     return false;
00208   }
00209 
00210   typedef collision_detection::CollisionResult::ContactMap ContactMap;
00211   typedef ContactMap::iterator ContactMapIterator;
00212   typedef std::vector<collision_detection::Contact> ContactArray;
00213 
00214   // initializing result array
00215   costs = Eigen::VectorXd::Zero(num_timesteps);
00216 
00217   // resetting array
00218   raw_costs_.setZero();
00219 
00220   // collision
00221   collision_detection::CollisionRequest request = collision_request_;
00222   collision_detection::CollisionResult result_world_collision, result_robot_collision;
00223   std::vector<collision_detection::CollisionResult> results(2);
00224   validity = true;
00225 
00226   // planning groups
00227   const JointModelGroup* joint_group = robot_model_ptr_->getJointModelGroup(group_name_);
00228 
00229   if(parameters.cols()< (start_timestep + num_timesteps))
00230   {
00231     ROS_ERROR_STREAM("Size in the 'parameters' matrix is less than required");
00232     return false;
00233   }
00234 
00235   // check for collisions at each state
00236   bool skip_next_check = false;
00237   for (auto t=start_timestep; t<start_timestep + num_timesteps; ++t)
00238   {
00239     if(!skip_next_check)
00240     {
00241       robot_state_->setJointGroupPositions(joint_group,parameters.col(t));
00242       robot_state_->update();
00243 
00244       // checking robot vs world (attached objects, octomap, not in urdf) collisions
00245       result_world_collision.distance = std::numeric_limits<double>::max();
00246 
00247       collision_world_->checkRobotCollision(request,
00248                                             result_world_collision,
00249                                             *collision_robot_,
00250                                             *robot_state_,
00251                                             planning_scene_->getAllowedCollisionMatrix());
00252 
00253       collision_robot_->checkSelfCollision(request,
00254                                            result_robot_collision,
00255                                            *robot_state_,
00256                                            planning_scene_->getAllowedCollisionMatrix());
00257 
00258       results[0]= result_world_collision;
00259       results[1] = result_robot_collision;
00260       for(std::vector<collision_detection::CollisionResult>::iterator i = results.begin(); i != results.end(); i++)
00261       {
00262         collision_detection::CollisionResult& result = *i;
00263         if(result.collision)
00264         {
00265           raw_costs_(t) = collision_penalty_;
00266           validity = false;
00267           break;
00268         }
00269       }
00270     }
00271 
00272     // check intermediate poses to the next position (skip the last one)
00273     if(t  < start_timestep + num_timesteps - 1)
00274     {
00275       if(!checkIntermediateCollisions(parameters.col(t),parameters.col(t+1),longest_valid_joint_move_))
00276       {
00277         raw_costs_(t) = 1.0;
00278         raw_costs_(t+1) = 1.0;
00279         validity = false;
00280         skip_next_check = true;
00281       }
00282       else
00283       {
00284         skip_next_check = false;
00285       }
00286     }
00287   }
00288 
00289   // applying kernel smoothing
00290   if(!validity)
00291   {
00292 
00293     if(kernel_window_percentage_> 1e-6)
00294     {
00295       int window_size = num_timesteps*kernel_window_percentage_;
00296       window_size = window_size < MIN_KERNEL_WINDOW_SIZE ? MIN_KERNEL_WINDOW_SIZE : window_size;
00297 
00298       // adding minimum cost
00299       intermediate_costs_slots_ = (raw_costs_.array() < collision_penalty_).cast<double>();
00300       raw_costs_ += (raw_costs_.sum()/raw_costs_.size())*(intermediate_costs_slots_.matrix());
00301 
00302       // smoothing
00303       applyKernelSmoothing(window_size,raw_costs_,costs);
00304     }
00305     else
00306     {
00307       costs = raw_costs_;
00308     }
00309 
00310   }
00311 
00312   return true;
00313 }
00314 
00315 bool CollisionCheck::checkIntermediateCollisions(const Eigen::VectorXd& start,
00316                                                            const Eigen::VectorXd& end,double longest_valid_joint_move)
00317 {
00318   Eigen::VectorXd diff = end - start;
00319   int num_intermediate = std::ceil(((diff.cwiseAbs())/longest_valid_joint_move).maxCoeff()) - 1;
00320   if(num_intermediate < 1.0)
00321   {
00322     // no interpolation needed
00323     return true;
00324   }
00325 
00326   // grabbing states
00327   auto& start_state = intermediate_coll_states_[0];
00328   auto& mid_state = intermediate_coll_states_[1];
00329   auto& end_state = intermediate_coll_states_[2];
00330 
00331   if(!start_state || !mid_state || !end_state)
00332   {
00333     ROS_ERROR("%s intermediate states not initialized",getName().c_str());
00334     return false;
00335   }
00336 
00337   // setting up collision
00338   auto req = collision_request_;
00339   req.distance = false;
00340   collision_detection::CollisionResult res;
00341   const moveit::core::JointModelGroup* joint_group = robot_model_ptr_->getJointModelGroup(group_name_);
00342   start_state->setJointGroupPositions(joint_group,start);
00343   end_state->setJointGroupPositions(joint_group,end);
00344 
00345   // checking intermediate states
00346   double dt = 1.0/static_cast<double>(num_intermediate);
00347   double interval = 0.0;
00348   for(std::size_t i = 1; i < num_intermediate;i++)
00349   {
00350     interval = i*dt;
00351     start_state->interpolate(*end_state,interval,*mid_state) ;
00352     if(planning_scene_->isStateColliding(*mid_state))
00353     {
00354       return false;
00355     }
00356   }
00357 
00358   return true;
00359 }
00360 
00361 bool CollisionCheck::configure(const XmlRpc::XmlRpcValue& config)
00362 {
00363 
00364   // check parameter presence
00365   auto members = {"cost_weight","collision_penalty","kernel_window_percentage"};
00366   for(auto& m : members)
00367   {
00368     if(!config.hasMember(m))
00369     {
00370       ROS_ERROR("%s failed to find one or more required parameters",getName().c_str());
00371       return false;
00372     }
00373   }
00374 
00375   try
00376   {
00377     // check parameter presence
00378     auto members = {"cost_weight","collision_penalty","kernel_window_percentage", "longest_valid_joint_move"};
00379     for(auto& m : members)
00380     {
00381       if(!config.hasMember(m))
00382       {
00383         ROS_ERROR("%s failed to find '%s' parameter",getName().c_str(),m);
00384         return false;
00385       }
00386     }
00387 
00388     XmlRpc::XmlRpcValue c = config;
00389     cost_weight_ = static_cast<double>(c["cost_weight"]);
00390     collision_penalty_ = static_cast<double>(c["collision_penalty"]);
00391     kernel_window_percentage_ = static_cast<double>(c["kernel_window_percentage"]);
00392     longest_valid_joint_move_ = static_cast<double>(c["longest_valid_joint_move"]);
00393   }
00394   catch(XmlRpc::XmlRpcException& e)
00395   {
00396     ROS_ERROR("%s failed to parse configuration parameters",name_.c_str());
00397     return false;
00398   }
00399 
00400   return true;
00401 }
00402 
00403 void CollisionCheck::done(bool success,int total_iterations,double final_cost,const Eigen::MatrixXd& parameters)
00404 {
00405   robot_state_.reset();
00406 }
00407 
00408 } /* namespace cost_functions */
00409 } /* namespace stomp_moveit */


stomp_moveit
Author(s): Jorge Nicho
autogenerated on Sat Jun 8 2019 19:24:01