environment_chain3d.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2010, Maxim Likhachev
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the University of Pennsylvania nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00031 #include <sbpl_interface/environment_chain3d.h>
00032 #include <collision_detection/collision_common.h>
00033 #include <planning_models/conversions.h>
00034 #include <boost/timer.hpp>
00035 #include <planning_models/angle_utils.h>
00036 
00037 static const unsigned int DEBUG_OVER = 1;
00038 static const unsigned int PRINT_HEURISTIC_UNDER = 1;
00039 
00040 static const double JOINT_DIST_MULT=1000.0;
00041 
00042 namespace sbpl_interface
00043 {
00044 
00045 EnvironmentChain3D::EnvironmentChain3D(const planning_scene::PlanningSceneConstPtr& planning_scene) :
00046   planning_scene_(planning_scene),
00047   bfs_(NULL),
00048   state_(planning_scene->getCurrentState()),
00049   planning_data_(StateID2IndexMapping),
00050   goal_constraint_set_(planning_scene->getRobotModel(),
00051                        planning_scene->getTransforms()),
00052   path_constraint_set_(planning_scene->getRobotModel(),
00053                        planning_scene->getTransforms()),
00054   interpolation_state_1_(planning_scene->getCurrentState()),
00055   interpolation_state_2_(planning_scene->getCurrentState()),
00056   interpolation_state_temp_(planning_scene->getCurrentState()),
00057   closest_to_goal_(DBL_MAX)
00058 {
00059 }
00060 
00061 
00062 EnvironmentChain3D::~EnvironmentChain3D()
00063 {
00064   if(bfs_ != NULL) {
00065     delete bfs_;
00066   }
00067 }
00068 
00070 //                      SBPL Planner Interface
00072 
00073 bool EnvironmentChain3D::InitializeMDPCfg(MDPConfig *MDPCfg)
00074 {
00075   if(planning_data_.goal_hash_entry_ &&
00076      planning_data_.start_hash_entry_) {
00077     MDPCfg->goalstateid = planning_data_.goal_hash_entry_->stateID;
00078     MDPCfg->startstateid = planning_data_.start_hash_entry_->stateID;
00079     return true;
00080   }
00081   return false;
00082 }
00083 
00084 bool EnvironmentChain3D::InitializeEnv(const char* sEnvFile)
00085 {
00086   ROS_INFO("[env] InitializeEnv is not implemented right now.");
00087   return true;
00088 }
00089 
00090 int EnvironmentChain3D::GetFromToHeuristic(int FromStateID, int ToStateID)
00091 {
00092   //std::cerr << "Getting heuristic" << std::endl;
00093   return getEndEffectorHeuristic(FromStateID,ToStateID);
00094 }
00095 
00096 int EnvironmentChain3D::GetGoalHeuristic(int stateID)
00097 {
00098   if(planning_data_.state_ID_to_coord_table_.size() < DEBUG_OVER) {
00099     std::cerr << "Getting heur distance from " << stateID << " to "
00100               << planning_data_.goal_hash_entry_->stateID << " "
00101               << GetFromToHeuristic(stateID, planning_data_.goal_hash_entry_->stateID) << std::endl;
00102   }
00103   return GetFromToHeuristic(stateID, planning_data_.goal_hash_entry_->stateID);
00104 }
00105 
00106 int EnvironmentChain3D::GetStartHeuristic(int stateID)
00107 {
00108   return GetFromToHeuristic(stateID, planning_data_.start_hash_entry_->stateID);
00109 }
00110 
00111 int EnvironmentChain3D::SizeofCreatedEnv()
00112 {
00113   return planning_data_.state_ID_to_coord_table_.size();
00114 }
00115 
00116 void EnvironmentChain3D::PrintState(int stateID, bool bVerbose, FILE* fOut /*=NULL*/)
00117 {
00118   // if(fOut == NULL)
00119   //   fOut = stdout;
00120 
00121   // EnvChain3DHashEntry* HashEntry = EnvChain.StateID2CoordTable[stateID];
00122 
00123   // bool bGoal = false;
00124   // if(stateID == EnvChain.goalHashEntry->stateID)
00125   //   bGoal = true;
00126 
00127   // if(stateID == EnvChain.goalHashEntry->stateID && bVerbose)
00128   // {
00129   //   //ROS_DEBUG_NAMED(fOut, "the state is a goal state\n");
00130   //   bGoal = true;
00131   // }
00132 
00133   // printJointArray(fOut, HashEntry, bGoal, bVerbose);
00134 }
00135 
00136 void EnvironmentChain3D::PrintEnv_Config(FILE* fOut)
00137 {
00138   std::cerr <<("ERROR in EnvChain... function: PrintEnv_Config is undefined\n");
00139   throw new SBPL_Exception();
00140 }
00141 
00142 void EnvironmentChain3D::GetSuccs(int source_state_ID,
00143                                   std::vector<int>* succ_idv,
00144                                   std::vector<int>* cost_v)
00145 {
00146   boost::this_thread::interruption_point();
00147   //std::cerr << "Calling get succ state " << source_state_ID << std::endl;
00148 
00149   ros::WallTime expansion_start_time = ros::WallTime::now();
00150 
00151   succ_idv->clear();
00152   cost_v->clear();
00153 
00154   //From environment_robarm3d.cpp -- //goal state should be absorbing
00155   if(source_state_ID == planning_data_.goal_hash_entry_->stateID) {
00156     std::cerr << "Think we have goal" << std::endl;
00157     return;
00158   }
00159 
00160   if(source_state_ID > (int)planning_data_.state_ID_to_coord_table_.size()-1) {
00161     ROS_WARN_STREAM("source id too large");
00162     std::cerr << "Source id too large" << std::endl;
00163     return;
00164   }
00165 
00166   if(planning_data_.state_ID_to_coord_table_.size() < DEBUG_OVER) {
00167     std::cerr << "Expanding " << source_state_ID << std::endl;
00168   }
00169 
00170   EnvChain3DHashEntry* hash_entry = planning_data_.state_ID_to_coord_table_[source_state_ID];
00171 
00172   std::vector<double> source_joint_angles = hash_entry->angles;
00173   //convertCoordToJointAngles(hash_entry->coord, source_joint_angles);
00174 
00175   std::vector<int> succ_coord;
00176   std::vector<double> succ_joint_angles;
00177 
00178   // for(unsigned int i = 0; i < source_joint_angles.size(); i++) {
00179   //   std::cerr << "Source " << i << " " << source_joint_angles[i] << std::endl;
00180   // }
00181 
00182   planning_statistics_.total_expansions_++;
00183 
00184   for(unsigned int i = 0; i < possible_actions_.size(); i++) {
00185     if(!possible_actions_[i]->generateSuccessorState(source_joint_angles, succ_joint_angles)) {
00186       continue;
00187     }
00188 
00189     // for(unsigned int j = 0; j < planning_data_.goal_hash_entry_->angles.size(); j++) {
00190     //   if(joint_is_continuous_[j]) {
00191     //     if(source_joint_angles[j] < M_PI && succ_joint_angles[j] > M_PI) {
00192     //       succ_joint_angles[j] -= 2*M_PI;
00193     //     } else if(source_joint_angles[j] > -M_PI && succ_joint_angles[j] < -M_PI) {
00194     //       succ_joint_angles[j] += 2*M_PI;
00195     //     }
00196     //   }
00197     // }
00198     // double dist = 0.0;
00199     // for(unsigned int j = 0; j < planning_data_.goal_hash_entry_->angles.size(); j++) {
00200     //   dist += fabs(planning_data_.goal_hash_entry_->angles[j]-succ_joint_angles[j]);
00201     //   //std::cerr << "Succ " << i << " " << j << " " << succ_joint_angles[j] << std::endl;
00202     // }
00203     // if(dist < closest_to_goal_) {
00204     //   //std::cerr << "Got dist " << dist << std::endl;
00205     //   closest_to_goal_ = dist;
00206     // }
00207 
00208     // int max_dist = getJointDistanceIntegerMax(succ_joint_angles,
00209     //                                           planning_data_.goal_hash_entry_->angles);
00210     // if(max_dist*1.0 < closest_to_goal_) {
00211     //   std::cerr << "Max integer distance is " << max_dist << std::endl;
00212     //   closest_to_goal_ = max_dist*1.0;
00213     //   // for(unsigned int j = 0; j < joint_motion_wrappers_.size(); j++) {
00214     //   //   if(joint_motion_wrappers_[j]->canGetCloser(succ_joint_angles[j],
00215     //   //                                              planning_data_.goal_hash_entry_->angles[j],
00216     //   //                                              LONG_RANGE_JOINT_DIFF)) {
00217     //   //     std::cerr << "Joint " << j << " succ " << succ_joint_angles[j] << " "
00218     //   //               << planning_data_.goal_hash_entry_->angles[j] << " can get closer\n";
00219     //   //     break;
00220     //   //   }
00221     //   // }
00222     // }
00223     convertJointAnglesToCoord(succ_joint_angles, succ_coord);
00224 
00225     joint_state_group_->setStateValues(succ_joint_angles);
00226 
00227     kinematic_constraints::ConstraintEvaluationResult con_res = path_constraint_set_.decide(state_);
00228     if(!con_res.satisfied) {
00229       ROS_INFO_STREAM("State violates path constraints");
00230     }
00231 
00232     // if(!joint_state_group_->satisfiesBounds()) {
00233     //   std::cerr << "ERROR - successor doesn't satisfy bounds" << std::endl;
00234     //   //std::cerr << "Successor doesn't satisfy bounds" << std::endl;
00235     //   continue;
00236     // }
00237     ros::WallTime before_coll = ros::WallTime::now();
00238     collision_detection::CollisionRequest req;
00239     collision_detection::CollisionResult res;
00240     req.group_name = planning_group_;
00241     if(!planning_parameters_.use_standard_collision_checking_) {
00242       hy_world_->checkCollisionDistanceField(req,
00243                                              res,
00244                                              *hy_robot_->getCollisionRobotDistanceField().get(),
00245                                              state_,
00246                                              gsr_);
00247     } else {
00248       planning_scene_->checkCollision(req, res, state_);
00249     }
00250     planning_statistics_.coll_checks_++;
00251     //std::cerr << "Elapsed " << t.elapsed() << std::endl;
00252     ros::WallDuration dur(ros::WallTime::now()-before_coll);
00253     //std::cerr << dur.toSec() << std::endl;
00254     //ROS_DEBUG_STREAM("Time " << ros::WallTime::now()-before_coll);
00255     planning_statistics_.total_coll_check_time_ += dur;
00256     if(res.collision) {
00257       //std::cerr << "Successor in collision" << std::endl;
00258       continue;
00259     }
00260 
00261     Eigen::Affine3d pose = tip_link_state_->getGlobalLinkTransform();
00262 
00263     int xyz[3];
00264     if(!planning_parameters_.use_standard_collision_checking_) {
00265       if(!getGridXYZInt(pose, xyz)) {
00266         std::cerr << "Can't get successor x y z" << std::endl;
00267         continue;
00268       }
00269     }
00270     int dist;
00271     if(planning_parameters_.use_bfs_) {
00272       dist = getBFSCostToGoal(xyz[0],
00273                               xyz[1],
00274                               xyz[2]);
00275     } else {
00276       dist = getJointDistanceIntegerMax(succ_joint_angles,
00277                                         planning_data_.goal_hash_entry_->angles,
00278                                         planning_parameters_.joint_motion_primitive_distance_);
00279     }
00280 
00281     EnvChain3DHashEntry* succ_hash_entry = NULL;
00282     // bool can_get_closer = false;
00283     // for(unsigned int j = 0; j < joint_motion_wrappers_.size(); j++) {
00284     //   if(joint_motion_wrappers_[j]->canGetCloser(succ_joint_angles[j],
00285     //                                              planning_data_.goal_hash_entry_->angles[j],
00286     //                                              LONG_RANGE_JOINT_DIFF)) {
00287     //     can_get_closer = true;
00288     //     // std::cerr << "Joint " << j << " succ " << succ_joint_angles[j] << " "
00289     //     //           << planning_data_.goal_hash_entry_->angles[j] << " can get closer\n";
00290     //     break;
00291     //   }
00292     // }
00293     //if(!can_get_closer) {
00294     bool succ_is_goal_state = false;
00295     if((planning_parameters_.use_bfs_ && dist == 0) || (!planning_parameters_.use_bfs_ && dist == 1)) {
00296       //std::cerr << "Joint distance for goal move " << getJointDistanceDoubleSum(planning_data_.goal_hash_entry_->angles, succ_joint_angles) << std::endl;
00297       std::vector<std::vector<double> > interpolated_values;
00298       if(interpolateAndCollisionCheck(source_joint_angles,
00299                                       planning_data_.goal_hash_entry_->angles,
00300                                       interpolated_values)) {
00301         //std::cerr << "Interpolation generated from id " << source_state_ID << " is " << interpolated_values.size() << " states\n";
00302         generated_interpolations_map_[source_state_ID][planning_data_.goal_hash_entry_->stateID] = interpolated_values;
00303         succ_hash_entry = planning_data_.goal_hash_entry_;
00304         succ_is_goal_state = true;
00305       } else {
00306         //std::cerr << "Interpolation in collision\n";
00307       }
00308     }
00309     std::vector<std::vector<double> > interpolated_values;
00310     if(!succ_is_goal_state) {
00311       if(planning_parameters_.interpolation_distance_ < planning_parameters_.joint_motion_primitive_distance_) {
00312         if(!interpolateAndCollisionCheck(source_joint_angles,
00313                                          succ_joint_angles,
00314                                          interpolated_values)) {
00315           //std::cerr << "Interpolation failed" << std::endl;
00316           continue;
00317         }
00318       }
00319       succ_hash_entry = planning_data_.getHashEntry(succ_coord, i);
00320     }
00321     // double max_dist = getJointDistanceMax(planning_data_.goal_hash_entry_->angles, succ_joint_angles);
00322     // if(max_dist < closest_to_goal_) {
00323     //   std::cerr << "State " << source_state_ID << " sum dist " << getJointDistanceSum(planning_data_.goal_hash_entry_->angles, succ_joint_angles) << " max "
00324     //             << " " << getJointDistanceMax(planning_data_.goal_hash_entry_->angles, succ_joint_angles) << std::endl;
00325     //   for(unsigned int i = 0; i < planning_data_.goal_hash_entry_->angles.size(); i++) {
00326     //     std::cerr << "Joint " << i << " " << planning_data_.goal_hash_entry_->angles[i] << " " << succ_joint_angles[i] << std::endl;
00327     //   }
00328     //   closest_to_goal_ = max_dist;
00329     // }
00330     // std::cerr << "Dist " << dist << " source state id " << source_state_ID << std::endl;
00331     // if(max_dist <= LONG_RANGE_JOINT_DIFF/2.0+.001) {
00332     //   succ_hash_entry = planning_data_.goal_hash_entry_;
00333     // } else {
00334     //   succ_hash_entry = planning_data_.getHashEntry(succ_coord, i);
00335     // }
00336 
00337     // kinematic_constraints::ConstraintEvaluationResult con_res = goal_constraint_set_.decide(state_);
00338     // if(con_res.satisfied) {
00339     //   std::cerr << "Constraints satisfied, dist is " << dist << std::endl;
00340     //   succ_hash_entry = planning_data_.goal_hash_entry_;
00341     // } else {
00342     //   succ_hash_entry = planning_data_.getHashEntry(succ_coord, i);
00343     // }
00344     if(!succ_hash_entry) {
00345       succ_hash_entry = planning_data_.addHashEntry(succ_coord, succ_joint_angles, xyz, i);
00346     } else {
00347       if(planning_data_.state_ID_to_coord_table_.size() < DEBUG_OVER) {
00348         std::cerr << "Already have hash entry " << succ_hash_entry->stateID << std::endl;
00349       }
00350     }
00351 
00352     if(planning_parameters_.interpolation_distance_ < planning_parameters_.joint_motion_primitive_distance_
00353        && !succ_is_goal_state) {
00354       //std::cerr << "Adding segment from " << source_state_ID << " to " << succ_hash_entry->stateID << std::endl;
00355       generated_interpolations_map_[source_state_ID][succ_hash_entry->stateID] = interpolated_values;
00356     }
00357 
00358     //std::cerr << "Adding hash entry" << std::endl;
00359     if(planning_data_.state_ID_to_coord_table_.size() < DEBUG_OVER) {
00360       std::cerr << std::endl;
00361       std::cerr << "Adding " << succ_hash_entry->stateID << std::endl;
00362       for(unsigned int j = 0; j < planning_data_.goal_hash_entry_->angles.size(); j++) {
00363         std::cerr << "Succ " << j << " " << succ_joint_angles[j] << std::endl;
00364       }
00365     }
00366     succ_idv->push_back(succ_hash_entry->stateID);
00367     cost_v->push_back(calculateCost(hash_entry, succ_hash_entry));
00368   }
00369   planning_statistics_.total_expansion_time_ += ros::WallTime::now()-expansion_start_time;
00370 }
00371 
00372 void EnvironmentChain3D::GetPreds(int TargetStateID, vector<int>* PredIDV, vector<int>* cost_v)
00373 {
00374   std::cerr <<("ERROR in EnvChain... function: GetPreds is undefined\n");
00375   throw new SBPL_Exception();
00376 }
00377 
00378 bool EnvironmentChain3D::AreEquivalent(int StateID1, int StateID2)
00379 {
00380   std::cerr <<("ERROR in EnvChain... function: AreEquivalent is undefined\n");
00381   throw new SBPL_Exception();
00382 }
00383 
00384 void EnvironmentChain3D::SetAllActionsandAllOutcomes(CMDPSTATE* state)
00385 {
00386   std::cerr <<("ERROR in EnvChain..function: SetAllActionsandOutcomes is undefined\n");
00387   throw new SBPL_Exception();
00388 }
00389 
00390 void EnvironmentChain3D::SetAllPreds(CMDPSTATE* state)
00391 {
00392   std::cerr <<("ERROR in EnvChain... function: SetAllPreds is undefined\n");
00393   throw new SBPL_Exception();
00394 }
00395 
00397 //                      End of SBPL Planner Interface
00399 
00400 bool EnvironmentChain3D::setupForMotionPlan(const planning_scene::PlanningSceneConstPtr& planning_scene,
00401                                             const moveit_msgs::GetMotionPlan::Request &mreq,
00402                                             moveit_msgs::GetMotionPlan::Response &mres,
00403                                             const PlanningParameters& params)
00404 {
00405   std::cerr << "really here " << std::endl;
00406   planning_scene_ = planning_scene;
00407 
00408   planning_group_ = mreq.motion_plan_request.group_name;
00409   planning_parameters_ = params;
00410 
00411   if(!planning_parameters_.use_standard_collision_checking_) {
00412     hy_world_ = dynamic_cast<const collision_detection::CollisionWorldHybrid*>(planning_scene->getCollisionWorld().get());
00413     if(!hy_world_) {
00414       ROS_WARN_STREAM("Could not initialize hybrid collision world from planning scene");
00415       mres.error_code.val = moveit_msgs::MoveItErrorCodes::COLLISION_CHECKING_UNAVAILABLE;
00416       return false;
00417     }
00418 
00419     hy_robot_ = dynamic_cast<const collision_detection::CollisionRobotHybrid*>(planning_scene->getCollisionRobot().get());
00420     if(!hy_robot_) {
00421       ROS_WARN_STREAM("Could not initialize hybrid collision robot from planning scene");
00422       mres.error_code.val = moveit_msgs::MoveItErrorCodes::COLLISION_CHECKING_UNAVAILABLE;
00423       return false;
00424     }
00425   }
00426 
00427   state_ = planning_scene->getCurrentState();
00428   interpolation_state_1_ = planning_scene->getCurrentState();
00429   interpolation_state_2_ = planning_scene->getCurrentState();
00430   interpolation_state_temp_ = planning_scene->getCurrentState();
00431 
00432   planning_models::robotStateMsgToRobotState(*planning_scene->getTransforms(), mreq.motion_plan_request.start_state, state_);
00433   joint_state_group_ = state_.getJointStateGroup(planning_group_);
00434   interpolation_joint_state_group_1_ = interpolation_state_1_.getJointStateGroup(planning_group_);
00435   interpolation_joint_state_group_2_ = interpolation_state_2_.getJointStateGroup(planning_group_);
00436   interpolation_joint_state_group_temp_ = interpolation_state_temp_.getJointStateGroup(planning_group_);
00437   tip_link_state_ = state_.getLinkState(joint_state_group_->getJointModelGroup()->getLinkModelNames().back());
00438 
00439   collision_detection::CollisionRequest req;
00440   collision_detection::CollisionResult res;
00441   req.group_name = planning_group_;
00442   if(!planning_parameters_.use_standard_collision_checking_) {
00443     hy_world_->checkCollisionDistanceField(req,
00444                                            res,
00445                                            *hy_robot_->getCollisionRobotDistanceField().get(),
00446                                            state_,
00447                                            planning_scene_->getAllowedCollisionMatrix(),
00448                                            gsr_);
00449   } else {
00450     planning_scene->checkCollision(req, res, state_);
00451   }
00452   if(res.collision) {
00453     ROS_WARN_STREAM("Start state is in collision.  Can't plan");
00454     mres.error_code.val = moveit_msgs::MoveItErrorCodes::START_STATE_IN_COLLISION;
00455     return false;
00456   }
00457   if(!planning_parameters_.use_standard_collision_checking_) {
00458     angle_discretization_ = gsr_->dfce_->distance_field_->getResolution();
00459   } else {
00460     angle_discretization_ = .02;
00461   }
00462   setMotionPrimitives(planning_group_);
00463 
00464   //can only do bfs if not using standard collison checking
00465   if(planning_parameters_.use_standard_collision_checking_) {
00466     planning_parameters_.use_bfs_ = false;
00467   }
00468   if(!planning_parameters_.use_standard_collision_checking_ && planning_parameters_.use_bfs_) {
00469     bfs_ = new BFS_3D(gsr_->dfce_->distance_field_->getXNumCells(),
00470                       gsr_->dfce_->distance_field_->getYNumCells(),
00471                       gsr_->dfce_->distance_field_->getZNumCells());
00472 
00473     boost::shared_ptr<const distance_field::DistanceField> world_distance_field = hy_world_->getCollisionWorldDistanceField()->getDistanceField();
00474     if(world_distance_field->getXNumCells() != gsr_->dfce_->distance_field_->getXNumCells() ||
00475        world_distance_field->getYNumCells() != gsr_->dfce_->distance_field_->getYNumCells() ||
00476        world_distance_field->getZNumCells() != gsr_->dfce_->distance_field_->getZNumCells()) {
00477       ROS_WARN_STREAM("Size mismatch between world and self distance fields");
00478       std::cerr << "Size mismatch between world and self distance fields" << std::endl;
00479       mres.error_code.val = moveit_msgs::MoveItErrorCodes::COLLISION_CHECKING_UNAVAILABLE;
00480       return false;
00481     }
00482     // std::cerr << "BFS dimensions are "
00483     //           << world_distance_field->getXNumCells() << " "
00484     //           << world_distance_field->getYNumCells() << " "
00485     //           << world_distance_field->getZNumCells() << std::endl;
00486     unsigned int wall_count = 0;
00487     for(int i = 0; i < gsr_->dfce_->distance_field_->getXNumCells()-2; i++) {
00488       for(int j = 0; j < gsr_->dfce_->distance_field_->getYNumCells()-2; j++) {
00489         for(int k = 0; k < gsr_->dfce_->distance_field_->getZNumCells()-2; k++) {
00490           boost::this_thread::interruption_point();
00491           if(gsr_->dfce_->distance_field_->getDistanceFromCell(i+1, j+1, k+1) == 0.0 ||
00492              world_distance_field->getDistanceFromCell(i+1, j+1, k+1) == 0.0) {
00493             bfs_->setWall(i+1, j+1, k+1);
00494             wall_count++;
00495           }
00496         }
00497       }
00498     }
00499   }
00500   // std::cerr << "Wall cells are " << wall_count << " of " <<
00501   //   world_distance_field->getXNumCells()*world_distance_field->getYNumCells()*world_distance_field->getZNumCells() << std::endl;
00502 
00503   //setting start position
00504   std::vector<double> start_joint_values;
00505   joint_state_group_->getGroupStateValues(start_joint_values);
00506   std::vector<int> start_coords;
00507   convertJointAnglesToCoord(start_joint_values, start_coords);
00508   Eigen::Affine3d start_pose = tip_link_state_->getGlobalLinkTransform();
00509 
00510   int start_xyz[3];
00511   if(!planning_parameters_.use_standard_collision_checking_) {
00512     if(!getGridXYZInt(start_pose, start_xyz)) {
00513       std::cerr << "Bad start pose" << std::endl;
00514       mres.error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE;
00515       return false;
00516     }
00517   } else {
00518     start_xyz[0] = 0.0;
00519     start_xyz[1] = 0.0;
00520     start_xyz[2] = 0.0;
00521   }
00522   planning_data_.start_hash_entry_ = planning_data_.addHashEntry(start_coords,
00523                                                                  start_joint_values,
00524                                                                  start_xyz,
00525                                                                  0);
00526 
00527   //setting goal position
00528   planning_models::RobotState *goal_state(state_);
00529   std::map<std::string, double> goal_vals;
00530   for(unsigned int i = 0; i < mreq.motion_plan_request.goal_constraints[0].joint_constraints.size(); i++) {
00531     goal_vals[mreq.motion_plan_request.goal_constraints[0].joint_constraints[i].joint_name] = mreq.motion_plan_request.goal_constraints[0].joint_constraints[i].position;
00532   }
00533   goal_state.setStateValues(goal_vals);
00534   if(!planning_parameters_.use_standard_collision_checking_) {
00535     hy_world_->checkCollisionDistanceField(req,
00536                                            res,
00537                                            *hy_robot_->getCollisionRobotDistanceField().get(),
00538                                            goal_state,
00539                                            planning_scene_->getAllowedCollisionMatrix(),
00540                                            gsr_);
00541   } else {
00542     planning_scene->checkCollision(req, res, goal_state);
00543   }
00544   if(res.collision) {
00545     ROS_WARN_STREAM("Goal state is in collision.  Can't plan");
00546     mres.error_code.val = moveit_msgs::MoveItErrorCodes::GOAL_IN_COLLISION;
00547     return false;
00548   }
00549   std::vector<double> goal_joint_values;
00550   planning_models::RobotState *::JointStateGroup* goal_joint_state_group = goal_state.getJointStateGroup(planning_group_);
00551   goal_joint_state_group->getGroupStateValues(goal_joint_values);
00552   std::vector<int> goal_coords;
00553   convertJointAnglesToCoord(goal_joint_values, goal_coords);
00554   goal_pose_ = goal_state.getLinkState(tip_link_state_->getName())->getGlobalLinkTransform();
00555   int goal_xyz[3];
00556   if(!planning_parameters_.use_standard_collision_checking_) {
00557     if(!getGridXYZInt(goal_pose_, goal_xyz)) {
00558       std::cerr << "Bad goal pose" << std::endl;
00559       mres.error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
00560       return false;
00561     }
00562   } else {
00563     goal_xyz[0] = 0.0;
00564     goal_xyz[1] = 0.0;
00565     goal_xyz[2] = 0.0;
00566   }
00567   std::vector<std::string> goal_dofs = goal_joint_state_group->getJointModelGroup()->getActiveDOFNames();
00568   for(unsigned int i = 0; i < goal_dofs.size(); i++) {
00569     ROS_DEBUG_STREAM("Start " << goal_dofs[i] << " pos " << start_joint_values[i]);
00570   }
00571   for(unsigned int i = 0; i < goal_dofs.size(); i++) {
00572     ROS_DEBUG_STREAM("Goal " << goal_dofs[i] << " pos " << goal_joint_values[i]);
00573   }
00574   //std::cerr << "Running bfs with goal " << goal_xyz[0] << " " <<  goal_xyz[1] << " " << goal_xyz[2] << std::endl;
00575   if(planning_parameters_.use_bfs_) {
00576     bfs_->run(goal_xyz[0], goal_xyz[1], goal_xyz[2]);
00577     // std::cerr << "Got start " << start_xyz[0] << " " <<  start_xyz[1] << " " << start_xyz[2] << " cost "
00578     //           << getBFSCostToGoal(start_xyz[0], start_xyz[1], start_xyz[2]) << std::endl;
00579   }
00580   goal_constraint_set_.clear();
00581   goal_constraint_set_.add(mreq.motion_plan_request.goal_constraints[0]);
00582   planning_data_.goal_hash_entry_ = planning_data_.addHashEntry(goal_coords,
00583                                                                 goal_joint_values,
00584                                                                 goal_xyz,
00585                                                                 0);
00586   path_constraint_set_.clear();
00587   path_constraint_set_.add(mreq.motion_plan_request.path_constraints);
00588   return true;
00589 }
00590 
00591 void EnvironmentChain3D::setMotionPrimitives(const std::string& group_name) {
00592   possible_actions_.clear();
00593   if(!joint_state_group_) {
00594     ROS_ERROR_STREAM("Can't set motion primitives as joint state group not set");
00595   }
00596   const planning_models::RobotModel::JointModelGroup* jmg = joint_state_group_->getJointModelGroup();
00597   for(unsigned int i = 0; i < jmg->getActiveDOFNames().size(); i++) {
00598     const planning_models::RobotModel::JointModel* joint = jmg->getJointModel(jmg->getActiveDOFNames()[i]);
00599     boost::shared_ptr<JointMotionWrapper> jmw(new JointMotionWrapper(joint));
00600     joint_motion_wrappers_.push_back(jmw);
00601     //TODO - figure out which DOFs have something to do with end effector position
00602     if(!planning_parameters_.use_bfs_ || i < 4) {
00603       boost::shared_ptr<SingleJointMotionPrimitive> sing_pos(new SingleJointMotionPrimitive(jmw, i, planning_parameters_.joint_motion_primitive_distance_));
00604       boost::shared_ptr<SingleJointMotionPrimitive> sing_neg(new SingleJointMotionPrimitive(jmw, i, -planning_parameters_.joint_motion_primitive_distance_));
00605       possible_actions_.push_back(sing_pos);
00606       possible_actions_.push_back(sing_neg);
00607     }
00608   }
00609   determineMaximumEndEffectorTravel();
00610 }
00611 
00612 void EnvironmentChain3D::determineMaximumEndEffectorTravel() {
00613   planning_models::RobotState *def(state_);
00614   def.setToDefaultValues();
00615   planning_models::RobotState *::JointStateGroup* jsg = def.getJointStateGroup(planning_group_);
00616   planning_models::RobotState *::LinkState* tip_link_state = def.getLinkState(jsg->getJointModelGroup()->getLinkModelNames().back());
00617   std::vector<double> default_values;
00618   jsg->getGroupStateValues(default_values);
00619   Eigen::Affine3d default_pose = tip_link_state->getGlobalLinkTransform();
00620   double default_x = default_pose.translation().x();
00621   double default_y = default_pose.translation().y();
00622   double default_z = default_pose.translation().z();
00623   double max_dist = 0.0;
00624   for(unsigned int i = 0; i < possible_actions_.size(); i++) {
00625     std::vector<double> succ_joint_angles;
00626     if(!possible_actions_[i]->generateSuccessorState(default_values, succ_joint_angles)) {
00627       ROS_ERROR_STREAM("Can't move from default state");
00628       continue;
00629     }
00630     jsg->setStateValues(succ_joint_angles);
00631     Eigen::Affine3d motion_pose = tip_link_state->getGlobalLinkTransform();
00632     double motion_x = motion_pose.translation().x();
00633     double motion_y = motion_pose.translation().y();
00634     double motion_z = motion_pose.translation().z();
00635     double dist = getEuclideanDistance(default_x, default_y, default_z,
00636                                        motion_x, motion_y, motion_z);
00637     //std::cerr << "Motion " << i << " dist " << dist << std::endl;
00638     if(dist > max_dist) {
00639       max_dist = dist;
00640     }
00641   }
00642   maximum_distance_for_motion_ = ceil(max_dist/angle_discretization_);
00643   //std::cerr << "Maximum distance is " << maximum_distance_for_motion_ << std::endl;
00644 }
00645 
00646 int EnvironmentChain3D::calculateCost(EnvChain3DHashEntry* HashEntry1, EnvChain3DHashEntry* HashEntry2)
00647 {
00648   //if(prms_.use_uniform_cost_)
00649   if(planning_parameters_.use_bfs_) {
00650     return JOINT_DIST_MULT*(maximum_distance_for_motion_*1.0);
00651   } else {
00652     return JOINT_DIST_MULT;
00653   }
00654   //return .05;//prms_.cost_multiplier_;
00655   //  else
00656   //   {
00657   //     // Max's suggestion is to just put a high cost on being close to
00658   //     // obstacles but don't provide some sort of gradient
00659   //     if(int(HashEntry2->dist) < 7) // in cells
00660   //       return prms_.cost_multiplier_ * prms_.range1_cost_;
00661   //     else if(int(HashEntry2->dist) < 12)
00662   //       return prms_.cost_multiplier_ * prms_.range2_cost_;
00663   //     else if(int(HashEntry2->dist) < 17)
00664   //       return prms_.cost_multiplier_ * prms_.range3_cost_;
00665   //     else
00666   //       return prms_.cost_multiplier_;
00667   //   }
00668   // }
00669 }
00670 
00671 // double EnvironmentChain3D::getEpsilon()
00672 // {
00673 //   return 10.0;
00674 //   //printf("%0.3f\n",prms_.epsilon_);fflush(stdout);
00675 //   //return prms_.epsilon_;
00676 // }
00677 
00678 // int EnvironmentChain3D::getEdgeCost(int FromStateID, int ToStateID)
00679 // {
00680 // #if DEBUG
00681 //   if(FromStateID >= (int)EnvChain.StateID2CoordTable.size()
00682 //       || ToStateID >= (int)EnvChain.StateID2CoordTable.size())
00683 //   {
00684 //     std::cerr <<("ERROR in EnvChain... function: stateID illegal\n");
00685 //     throw new SBPL_Exception();
00686 //   }
00687 // #endif
00688 
00689 //   //get X, Y for the state
00690 //   EnvChain3DHashEntry* FromHashEntry = EnvChain.StateID2CoordTable[FromStateID];
00691 //   EnvChain3DHashEntry* ToHashEntry = EnvChain.StateID2CoordTable[ToStateID];
00692 
00693 //   return cost(FromHashEntry, ToHashEntry, false);
00694 // }
00695 
00696 int EnvironmentChain3D::getBFSCostToGoal(int x, int y, int z) const
00697 {
00698   //std::cerr << "Getting cost for " << x << " " << y << " " << z << std::endl;
00699   //TODO - deal with cost_per_cell
00700   int cost = (floor(bfs_->getDistance(x,y,z)/(maximum_distance_for_motion_)))*JOINT_DIST_MULT;
00701   //std::cerr << "Cost is " << cost << std::endl;
00702   return cost;
00703   //* .05;//prms_.cost_per_cell_;
00704 }
00705 
00706 int EnvironmentChain3D::getJointDistanceIntegerSum(const std::vector<double>& angles1,
00707                                                    const std::vector<double>& angles2,
00708                                                    double delta) const
00709 {
00710   if(angles1.size() != angles2.size()) {
00711     std::cerr << "Angles aren't the same size!!!" << std::endl;
00712     return INT_MAX;
00713   }
00714   int dist = 0;
00715   for(unsigned int i = 0; i < angles1.size(); i++) {
00716     dist += joint_motion_wrappers_[i]->getIntegerDistance(angles1[i], angles2[i], delta);
00717   }
00718   return dist;
00719 }
00720 
00721 int EnvironmentChain3D::getJointDistanceIntegerMax(const std::vector<double>& angles1,
00722                                                    const std::vector<double>& angles2,
00723                                                    double delta) const
00724 {
00725   if(angles1.size() != angles2.size()) {
00726     std::cerr << "Angles aren't the same size!!!" << std::endl;
00727     return INT_MAX;
00728   }
00729   int max_dist = 0;
00730   for(unsigned int i = 0; i < angles1.size(); i++) {
00731     int dist = joint_motion_wrappers_[i]->getIntegerDistance(angles1[i], angles2[i], delta);
00732     if(dist > max_dist) {
00733       max_dist = dist;
00734     }
00735   }
00736   return max_dist;
00737 }
00738 
00739 double EnvironmentChain3D::getJointDistanceDoubleSum(const std::vector<double>& angles1,
00740                                                      const std::vector<double>& angles2) const
00741 {
00742   if(angles1.size() != angles2.size()) {
00743     return DBL_MAX;
00744   }
00745   double dist = 0.0;
00746   for(unsigned int i = 0; i < angles1.size(); i++) {
00747     double jdist = joint_motion_wrappers_[i]->getDoubleDistance(angles1[i], angles2[i]);
00748     //std::cerr << "Joint " << i << " angle1 " << angles1[i] << " " << angles2[i] << " distance " << jdist << std::endl;
00749     dist += jdist;
00750   }
00751   return dist;
00752 }
00753 
00754 // double EnvironmentChain3D::getJointDistanceMax(const std::vector<double>& angles1,
00755 //                                                const std::vector<double>& angles2)
00756 // {
00757 //   if(angles1.size() != angles2.size()) {
00758 //     return DBL_MAX;
00759 //   }
00760 //   double max_dist = 0.0;
00761 //   for(unsigned int i = 0; i < angles1.size(); i++) {
00762 //     double dist;
00763 //     if(joint_is_continuous_[i]) {
00764 //       if(planning_data_.state_ID_to_coord_table_.size() < PRINT_HEURISTIC_UNDER) {
00765 //         ROS_INFO_STREAM("Dist for cont joint " << i << " from " << angles1[i] << " to " << angles2[i] << " is " <<
00766 //                         planning_models::shortestAngularDistance(angles1[i],angles2[i]));
00767 //       }
00768 //       dist = fabs(planning_models::shortestAngularDistance(angles1[i],angles2[i]));
00769 //     } else {
00770 //       if(planning_data_.state_ID_to_coord_table_.size() < PRINT_HEURISTIC_UNDER) {
00771 //         ROS_INFO_STREAM("Dist for reg joint " << i << " from " << angles1[i] << " to " << angles2[i] << " is " <<
00772 //                         fabs(angles1[i]-angles2[i]));
00773 //       }
00774 //       dist = fabs(angles1[i]-angles2[i]);
00775 //     }
00776 //     if(max_dist < dist) {
00777 //       max_dist = dist;
00778 //     }
00779 //   }
00780 //   return max_dist;
00781 // }
00782 
00783 int EnvironmentChain3D::getEndEffectorHeuristic(int from_stateID, int to_stateID)
00784 {
00785   boost::this_thread::interruption_point();
00786   EnvChain3DHashEntry* from_hash_entry = planning_data_.state_ID_to_coord_table_[from_stateID];
00787   EnvChain3DHashEntry* to_hash_entry = planning_data_.state_ID_to_coord_table_[to_stateID];
00788   //if(planning_data_.state_ID_to_coord_table_.size() < PRINT_HEURISTIC_UNDER) {
00789   //std::cerr << " Dist " << dist << " heur " << getBFSCostToGoal(from_hash_entry->xyz[0], from_hash_entry->xyz[1], from_hash_entry->xyz[2]) << std::endl;
00790   if(planning_parameters_.use_bfs_) {
00791     return getBFSCostToGoal(from_hash_entry->xyz[0],
00792                             from_hash_entry->xyz[1],
00793                             from_hash_entry->xyz[2]);
00794   } else {
00795     return getJointDistanceIntegerSum(from_hash_entry->angles,
00796                                       to_hash_entry->angles,
00797                                       planning_parameters_.joint_motion_primitive_distance_)*JOINT_DIST_MULT;
00798   }
00799   //return getBFSCostToGoal(from_hash_entry->xyz[0], from_hash_entry->xyz[1], from_hash_entry->xyz[2]);
00800   //else
00801   //{
00802   // double x, y, z;
00803   // if(!gsr_->dfce_->distance_field_->gridToWorld(from_hash_entry->xyz[0],
00804   //                                               from_hash_entry->xyz[1],
00805   //                                               from_hash_entry->xyz[2],
00806   //                                               x,y,z)) {
00807   //   std::cerr << "problem" << std::endl;
00808   //   return 1000000;
00809   // }
00810   // return getEuclideanDistance(x, y, z, goal_pose_.translation().x(), goal_pose_.translation().y(), goal_pose_.translation().z())*1000.0;
00811   // heur =  getEuclideanDistance(x, y, z, env_chain_config_.goal.xyz[0],env_chain_config_.goal.xyz[1], env_chain_config_.goal.xyz[2]) * prms_.cost_per_meter_;
00812   //}
00813 }
00814 
00815 bool EnvironmentChain3D::getGridXYZInt(const Eigen::Affine3d& pose,
00816                                        int(&xyz)[3]) const
00817 {
00818   if(!gsr_ || !gsr_->dfce_->distance_field_) {
00819     ROS_WARN_STREAM("No distance field cache entry available");
00820     return false;
00821   }
00822   if(!gsr_->dfce_->distance_field_->worldToGrid(pose.translation().x(),
00823                                                 pose.translation().y(),
00824                                                 pose.translation().z(),
00825                                                 xyz[0],
00826                                                 xyz[1],
00827                                                 xyz[2])) {
00828     ROS_WARN_STREAM("Pose out of bounds");
00829     return false;
00830   }
00831   return true;
00832 }
00833 
00834 bool EnvironmentChain3D::populateTrajectoryFromStateIDSequence(const std::vector<int>& state_ids,
00835                                                                trajectory_msgs::JointTrajectory& traj) const
00836 {
00837   traj.joint_names = joint_state_group_->getJointModelGroup()->getActiveDOFNames();
00838   std::vector<std::vector<double> > angle_vector;
00839   if(!planning_data_.convertFromStateIDsToAngles(state_ids,
00840                                                  angle_vector)) {
00841     return false;
00842   }
00843   if(planning_parameters_.interpolation_distance_ >= planning_parameters_.joint_motion_primitive_distance_) {
00844     std::map<int, std::map<int, std::vector<std::vector<double> > > >::const_iterator it = generated_interpolations_map_.find(*(state_ids.end()-2));
00845     std::vector< std::vector<double> > end_points;
00846     if(it != generated_interpolations_map_.end()) {
00847       std::map<int, std::vector<std::vector<double> > >::const_iterator it2 = it->second.find(state_ids.back());
00848       if(it2 == it->second.end()) {
00849         std::cerr << "No interpolated segment connecting state id " << (*state_ids.end()-2) << " and goal " << state_ids.back() << std::endl;
00850       } else {
00851         end_points = it2->second;
00852       }
00853     } else {
00854       std::cerr << "No interpolated segment connecting state id " << (*state_ids.end()-2) << " and goal " << state_ids.back() << std::endl;
00855     }
00856     traj.points.resize(end_points.size()+angle_vector.size());
00857     for(unsigned int i = 0; i < angle_vector.size()-1; i++) {
00858       traj.points[i].positions = angle_vector[i];
00859     }
00860     for(unsigned int i = 0; i < end_points.size(); i++) {
00861       traj.points[i+angle_vector.size()-1].positions = end_points[i];
00862     }
00863     traj.points.back().positions = angle_vector.back();
00864     for(unsigned int i = 0; i < traj.points.back().positions.size(); i++) {
00865       ROS_DEBUG_STREAM("Last " << i << " " << traj.points.back().positions[i]);
00866     }
00867     std::cerr << "Original path " << angle_vector.size() << " end path " << end_points.size() << std::endl;
00868   } else {
00869     std::cerr << "Num states " << state_ids.size() << std::endl;
00870     for(unsigned int i = 0; i < state_ids.size()-1; i++) {
00871       trajectory_msgs::JointTrajectoryPoint statep;
00872       statep.positions = angle_vector[i];
00873       ROS_DEBUG_STREAM("State id " << state_ids[i]);
00874       //if(traj.points.size() > 0) {
00875         // std::cerr << "State " << i << " id " << state_ids[i] << " dist "
00876         //           <<  getJointDistanceIntegerMax(traj.points.back().positions,
00877         //                                          statep.positions,
00878         //                                          INTERPOLATION_DISTANCE) << std::endl;
00879       //}
00880       traj.points.push_back(statep);
00881       std::map<int, std::map<int, std::vector<std::vector<double> > > >::const_iterator it = generated_interpolations_map_.find(state_ids[i]);
00882       if(it != generated_interpolations_map_.end()) {
00883         std::map<int, std::vector<std::vector<double> > >::const_iterator it2 = it->second.find(state_ids[i+1]);
00884         if(it2 == it->second.end()) {
00885           std::cerr << "No interpolated segment connecting state id " << state_ids[i] << " and state " << state_ids[i+1] << std::endl;
00886           continue;
00887         } else {
00888           for(unsigned int j = 0; j < it2->second.size(); j++) {
00889             trajectory_msgs::JointTrajectoryPoint p;
00890             p.positions = it2->second[j];
00891             // std::cerr << "Interp " << getJointDistanceIntegerMax(traj.points.back().positions,
00892             //                                                      p.positions,
00893             //                                                      INTERPOLATION_DISTANCE) << std::endl;
00894             traj.points.push_back(p);
00895           }
00896         }
00897       } else {
00898         std::cerr << "No interpolated segment connecting state id " << state_ids[i] << " and state " << state_ids[i+1] << std::endl;
00899         continue;
00900       }
00901     }
00902     //last point
00903     trajectory_msgs::JointTrajectoryPoint statep;
00904     statep.positions = angle_vector.back();
00905     // std::cerr << "Last " << getJointDistanceIntegerMax(traj.points.back().positions,
00906     //                                                    statep.positions,
00907     //                                                    INTERPOLATION_DISTANCE) << std::endl;
00908 
00909     traj.points.push_back(statep);
00910   }
00911   std::cerr << "Resulting path is " << traj.points.size() << std::endl;
00912   return true;
00913 }
00914 
00915 bool EnvironmentChain3D::getPlaneBFSMarker(visualization_msgs::Marker& plane_marker,
00916                                            double z_val)
00917 {
00918   if(!gsr_ || !gsr_->dfce_ || !gsr_->dfce_->distance_field_) {
00919     return false;
00920   }
00921   plane_marker.header.frame_id = planning_scene_->getPlanningFrame();
00922   plane_marker.header.stamp = ros::Time::now();
00923   plane_marker.ns = "bfs_plane";
00924   plane_marker.id = 0;
00925   plane_marker.type = visualization_msgs::Marker::CUBE_LIST;
00926   plane_marker.action = visualization_msgs::Marker::ADD;
00927   plane_marker.points.resize(1);
00928   std_msgs::ColorRGBA wall_color;
00929   wall_color.r = wall_color.a = 1.0;
00930   plane_marker.colors.resize(1);
00931   plane_marker.colors[0] = wall_color;
00932   plane_marker.points[0].x = 1.0;
00933   plane_marker.pose.orientation.w = 1.0;
00934   plane_marker.color = wall_color;
00935   plane_marker.scale.x = plane_marker.scale.y = plane_marker.scale.z = gsr_->dfce_->distance_field_->getResolution();
00936   plane_marker.points.resize((gsr_->dfce_->distance_field_->getXNumCells()-2)*(gsr_->dfce_->distance_field_->getYNumCells()-2));
00937   plane_marker.colors.resize((gsr_->dfce_->distance_field_->getXNumCells()-2)*(gsr_->dfce_->distance_field_->getYNumCells()-2));
00938   //TODO - deal if 0,0 is not valid for x and y
00939   int x_val_temp, y_val_temp;
00940   int z_val_int;
00941   gsr_->dfce_->distance_field_->worldToGrid(0.0, 0.0, z_val, x_val_temp, y_val_temp, z_val_int);
00942   std_msgs::ColorRGBA dist_color;
00943   dist_color.g = dist_color.a = 1.0;
00944   unsigned int count = 0;
00945   for(int i = 0; i < gsr_->dfce_->distance_field_->getXNumCells()-2; i++) {
00946     for(int j = 0; j < gsr_->dfce_->distance_field_->getYNumCells()-2; j++, count++) {
00947       gsr_->dfce_->distance_field_->gridToWorld(i, j, z_val_int,
00948                                                 plane_marker.points[count].x,
00949                                                 plane_marker.points[count].y,
00950                                                 plane_marker.points[count].z);
00951       //ROS_INFO_STREAM("Point " << count << " point " << plane_marker.points[count]);
00952       if(bfs_->isWall(i, j, z_val_int)) {
00953         plane_marker.colors[count] = wall_color;
00954         } else {
00955         int dist = bfs_->getDistance(i,j, z_val_int);
00956         if(dist < 40) {
00957           plane_marker.colors[count] = dist_color;
00958           plane_marker.colors[count].g = (40-dist)/40.0;
00959         }
00960       }
00961     }
00962   }
00963   return true;
00964 }
00965 
00966 bool EnvironmentChain3D::interpolateAndCollisionCheck(const std::vector<double> angles1,
00967                                                       const std::vector<double> angles2,
00968                                                       std::vector<std::vector<double> >& state_values)
00969 {
00970   static bool print_first = false;
00971   state_values.clear();
00972   interpolation_joint_state_group_1_->setStateValues(angles1);
00973   interpolation_joint_state_group_2_->setStateValues(angles2);
00974 
00975   interpolation_joint_state_group_temp_->setStateValues(angles1);
00976 
00977   collision_detection::CollisionRequest req;
00978   req.group_name = planning_group_;
00979 
00980   int maximum_moves = getJointDistanceIntegerMax(angles1, angles2, planning_parameters_.interpolation_distance_);
00981   if(print_first) {
00982     std::cerr << "Maximum moves " << maximum_moves << std::endl;
00983     for(unsigned int i = 0; i < angles1.size(); i++) {
00984       std::cerr << "Start " << i << " " << angles1[i] << std::endl;
00985     }
00986     for(unsigned int i = 0; i < angles2.size(); i++) {
00987       std::cerr << "End " << i << " " << angles2[i] << std::endl;
00988     }
00989   }
00990   for(int i = 1; i < maximum_moves; i++) {
00991     interpolation_joint_state_group_1_->interpolate(interpolation_joint_state_group_2_,
00992                                                     (1.0/(maximum_moves*1.0))*i,
00993                                                     interpolation_joint_state_group_temp_);
00994     ros::WallTime before_coll = ros::WallTime::now();
00995     collision_detection::CollisionResult res;
00996     if(!planning_parameters_.use_standard_collision_checking_) {
00997       hy_world_->checkCollisionDistanceField(req,
00998                                              res,
00999                                              *hy_robot_->getCollisionRobotDistanceField().get(),
01000                                              interpolation_state_temp_,
01001                                              gsr_);
01002     } else {
01003       planning_scene_->checkCollision(req, res, interpolation_state_temp_);
01004     }
01005     planning_statistics_.coll_checks_++;
01006     ros::WallDuration dur(ros::WallTime::now()-before_coll);
01007     planning_statistics_.total_coll_check_time_ += dur;
01008     if(res.collision) {
01009       return false;
01010     }
01011     state_values.resize(state_values.size()+1);
01012     interpolation_joint_state_group_temp_->getGroupStateValues(state_values.back());
01013     if(print_first) {
01014       for(unsigned int j = 0; j < state_values.back().size(); j++) {
01015         std::cerr << "Interp " << i << " " << j << " " << state_values.back()[j] << std::endl;
01016       }
01017     }
01018   }
01019   print_first = false;
01020   return true;
01021 }
01022 
01023 void EnvironmentChain3D::attemptShortcut(const trajectory_msgs::JointTrajectory& traj_in,
01024                                          trajectory_msgs::JointTrajectory& traj_out)
01025 {
01026   unsigned int last_point_ind = 0;
01027   unsigned int current_point_ind = 1;
01028   unsigned int last_good_start_ind = 0;
01029   unsigned int last_good_end_ind = 1;
01030   traj_out = traj_in;
01031   traj_out.points.clear();
01032   traj_out.points.push_back(traj_in.points.front());
01033   std::vector<std::vector<double> > last_good_segment_values;
01034   if(traj_in.points.size() == 1) {
01035     traj_out = traj_in;
01036     return;
01037   }
01038   if(planning_parameters_.attempt_full_shortcut_) {
01039     std::vector<std::vector<double> > full_shortcut;
01040     //std::cerr << "Checking" << std::endl;
01041     if(interpolateAndCollisionCheck(traj_in.points.front().positions,
01042                                     traj_in.points.back().positions,
01043                                     full_shortcut)) {
01044       std::cerr << "Full shortcut has " << full_shortcut.size() << " points " << std::endl;
01045       for(unsigned int i = 0; i < full_shortcut.size(); i++) {
01046         trajectory_msgs::JointTrajectoryPoint jtp;
01047         jtp.positions = full_shortcut[i];
01048         traj_out.points.push_back(jtp);
01049       }
01050       traj_out.points.push_back(traj_in.points.back());
01051       std::cerr << "Full shortcut worked" << std::endl;
01052       return;
01053     }
01054   }
01055 
01056   while(1) {
01057     //std::cerr << "Checking from " << last_point_ind << " to " << current_point_ind << std::endl;
01058     const trajectory_msgs::JointTrajectoryPoint& start_point = traj_in.points[last_point_ind];
01059     const trajectory_msgs::JointTrajectoryPoint& end_point = traj_in.points[current_point_ind];
01060     std::vector<std::vector<double> > segment_values;
01061     //if we can go from start to end then keep going
01062     if(interpolateAndCollisionCheck(start_point.positions,
01063                                     end_point.positions,
01064                                     segment_values)) {
01065       last_good_start_ind = last_point_ind;
01066       last_good_end_ind = current_point_ind;
01067       last_good_segment_values = segment_values;
01068       current_point_ind++;
01069       //std::cerr << "Interpolation ok" << std::endl;
01070     } else {
01071       //first case - start and end are separated by single point, so we copy the end in
01072       if(last_good_end_ind-last_good_start_ind == 1) {
01073         traj_out.points.push_back(traj_in.points[last_good_end_ind]);
01074       } else {
01075         for(unsigned int i = 0; i < last_good_segment_values.size(); i++) {
01076           trajectory_msgs::JointTrajectoryPoint jtp;
01077           jtp.positions = last_good_segment_values[i];
01078           traj_out.points.push_back(jtp);
01079         }
01080       }
01081       last_good_start_ind = last_good_end_ind;
01082       last_point_ind = last_good_end_ind;
01083       current_point_ind = last_good_end_ind+1;
01084       last_good_segment_values.clear();
01085       //std::cerr << "Interpolation not ok" << std::endl;
01086     }
01087     if(current_point_ind >= traj_in.points.size()) {
01088       if(last_good_segment_values.size() > 0) {
01089         for(unsigned int i = 0; i < last_good_segment_values.size(); i++) {
01090           trajectory_msgs::JointTrajectoryPoint jtp;
01091           jtp.positions = last_good_segment_values[i];
01092           traj_out.points.push_back(jtp);
01093         }
01094       }
01095       traj_out.points.push_back(traj_in.points.back());
01096       break;
01097     }
01098   }
01099 }
01100 
01101 }


sbpl_interface
Author(s): Gil Jones
autogenerated on Mon Oct 6 2014 11:11:34