environment_chain3d.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, 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  */
00029 
00032 #ifndef _ENVIRONMENT_CHAIN3D_H_
00033 #define _ENVIRONMENT_CHAIN3D_H_
00034 
00035 #include <time.h>
00036 #include <stdio.h>
00037 #include <sys/types.h>
00038 #include <sys/stat.h>
00039 #include <unistd.h>
00040 #include <fstream>
00041 #include <vector>
00042 #include <string>
00043 #include <list>
00044 #include <algorithm>
00045 
00046 #include <sbpl/headers.h>
00047 #include <sbpl_interface/bfs3d/BFS_3D.h>
00048 #include <planning_scene/planning_scene.h>
00049 #include <collision_distance_field/collision_robot_hybrid.h>
00050 #include <collision_distance_field/collision_world_hybrid.h>
00051 #include <sbpl_interface/environment_chain3d_types.h>
00052 #include <moveit_msgs/GetMotionPlan.h>
00053 
00054 #include <Eigen/Core>
00055 
00056 static const double DEFAULT_INTERPOLATION_DISTANCE=.05;
00057 static const double DEFAULT_JOINT_MOTION_PRIMITIVE_DISTANCE=.2;
00058 
00059 namespace sbpl_interface {
00060 
00061 struct PlanningStatistics {
00062 
00063   PlanningStatistics() :
00064     total_expansions_(0),
00065     coll_checks_(0)
00066   {
00067   }
00068 
00069   unsigned int total_expansions_;
00070   ros::WallDuration total_expansion_time_;
00071   ros::WallDuration total_coll_check_time_;
00072   unsigned int coll_checks_;
00073   ros::WallDuration total_planning_time_;
00074 };
00075 
00076 struct PlanningParameters {
00077 
00078   PlanningParameters() :
00079     use_bfs_(true),
00080     use_standard_collision_checking_(false),
00081     attempt_full_shortcut_(true),
00082     interpolation_distance_(DEFAULT_INTERPOLATION_DISTANCE),
00083     joint_motion_primitive_distance_(DEFAULT_JOINT_MOTION_PRIMITIVE_DISTANCE)
00084   {
00085   }
00086 
00087   bool use_bfs_;
00088   bool use_standard_collision_checking_;
00089   bool attempt_full_shortcut_;
00090   double interpolation_distance_;
00091   double joint_motion_primitive_distance_;
00092 };
00093 
00095 class EnvironmentChain3D: public DiscreteSpaceInformation
00096 {
00097 public:
00098 
00099   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00100 
00104   EnvironmentChain3D(const planning_scene::PlanningSceneConstPtr& planning_scene);
00105 
00109   ~EnvironmentChain3D();
00110 
00111   //
00112   // Pure virtual functions from DiscreteSpaceInformation
00113   //
00114 
00120   virtual bool InitializeEnv(const char* sEnvFile);
00121 
00126   virtual bool InitializeMDPCfg(MDPConfig *MDPCfg);
00127 
00134   virtual int GetFromToHeuristic(int FromStateID, int ToStateID);
00135 
00141   virtual int GetGoalHeuristic(int stateID);
00142 
00148   virtual int GetStartHeuristic(int stateID);
00149 
00161   virtual void GetSuccs(int SourceStateID, vector<int>* SuccIDV, vector<int>* CostV);
00162 
00164   virtual void GetPreds(int TargetStateID, vector<int>* PredIDV, vector<int>* CostV);
00165 
00167   virtual void SetAllActionsandAllOutcomes(CMDPSTATE* state);
00168 
00170   virtual void SetAllPreds(CMDPSTATE* state);
00171 
00176   virtual int SizeofCreatedEnv();
00177 
00184   virtual void PrintState(int stateID, bool bVerbose, FILE* fOut=NULL);
00185 
00187   virtual void PrintEnv_Config(FILE* fOut);
00188 
00189   //
00190   // Overloaded virtual functions from DiscreteSpaceInformation
00191   //
00192 
00200   virtual void getExpandedStates(std::vector<std::vector<double> >* ara_states) {};
00201 
00209   virtual bool AreEquivalent(int StateID1, int StateID2);
00210 
00211   bool setupForMotionPlan(const planning_scene::PlanningSceneConstPtr& planning_scene,
00212                           const moveit_msgs::GetMotionPlan::Request &req,
00213                           moveit_msgs::GetMotionPlan::Response& res,
00214                           const PlanningParameters& params);
00215 
00216   const EnvChain3DPlanningData& getPlanningData() const {
00217     return planning_data_;
00218   }
00219 
00220   bool populateTrajectoryFromStateIDSequence(const std::vector<int>& state_ids,
00221                                              trajectory_msgs::JointTrajectory& traj) const;
00222 
00223 
00224   const PlanningStatistics& getPlanningStatistics() const {
00225     return planning_statistics_;
00226   }
00227 
00228   bool getPlaneBFSMarker(visualization_msgs::Marker& plane_marker,
00229                          double z_val);
00230 
00231 
00232   const Eigen::Affine3d& getGoalPose() const {
00233     return goal_pose_;
00234   }
00235 
00236   void attemptShortcut(const trajectory_msgs::JointTrajectory& traj_in,
00237                        trajectory_msgs::JointTrajectory& traj_out);
00238 
00239 protected:
00240 
00241   bool getGridXYZInt(const Eigen::Affine3d& pose,
00242                      int(&xyz)[3]) const;
00243 
00244   void getMotionPrimitives(const std::string& group);
00245 
00246   planning_scene::PlanningSceneConstPtr planning_scene_;
00247 
00248   double angle_discretization_;
00249   BFS_3D *bfs_;
00250 
00251   std::vector<boost::shared_ptr<JointMotionWrapper> > joint_motion_wrappers_;
00252   std::vector<boost::shared_ptr<JointMotionPrimitive> > possible_actions_;
00253   planning_models::RobotState *state_;
00254   const collision_detection::CollisionWorldHybrid* hy_world_;
00255   const collision_detection::CollisionRobotHybrid* hy_robot_;
00256   planning_models::RobotState *::JointStateGroup* joint_state_group_;
00257   boost::shared_ptr<collision_detection::GroupStateRepresentation> gsr_;
00258   //boost::shared_ptr<kinematics::KinematicsBase> kinematics_solver_;
00259   const planning_models::RobotState *::LinkState* tip_link_state_;
00260   EnvChain3DPlanningData planning_data_;
00261   kinematic_constraints::KinematicConstraintSet goal_constraint_set_;
00262   kinematic_constraints::KinematicConstraintSet path_constraint_set_;
00263   std::string planning_group_;
00264   Eigen::Affine3d goal_pose_;
00265   PlanningStatistics planning_statistics_;
00266   PlanningParameters planning_parameters_;
00267   int maximum_distance_for_motion_;
00268 
00269   planning_models::RobotState *interpolation_state_1_;
00270   planning_models::RobotState *interpolation_state_2_;
00271   planning_models::RobotState *interpolation_state_temp_;
00272   planning_models::RobotState *::JointStateGroup* interpolation_joint_state_group_1_;
00273   planning_models::RobotState *::JointStateGroup* interpolation_joint_state_group_2_;
00274   planning_models::RobotState *::JointStateGroup* interpolation_joint_state_group_temp_;
00275   std::map<int, std::map<int, std::vector<std::vector<double> > > > generated_interpolations_map_;
00276 
00277   void setMotionPrimitives(const std::string& group_name);
00278   void determineMaximumEndEffectorTravel();
00279 
00280   void convertCoordToJointAngles(const std::vector<int> &coord, std::vector<double> &angles);
00281   void convertJointAnglesToCoord(const std::vector<double> &angle, std::vector<int> &coord);
00282 
00283   int calculateCost(EnvChain3DHashEntry* HashEntry1, EnvChain3DHashEntry* HashEntry2);
00284   int getBFSCostToGoal(int x, int y, int z) const;
00285   int getEndEffectorHeuristic(int FromStateID, int ToStateID);
00286 
00287   double getJointDistanceDoubleSum(const std::vector<double>& angles1,
00288                                    const std::vector<double>& angles2) const;
00289 
00290   int getJointDistanceIntegerSum(const std::vector<double>& angles1,
00291                                  const std::vector<double>& angles2,
00292                                  double delta) const;
00293 
00294   int getJointDistanceIntegerMax(const std::vector<double>& angles1,
00295                                  const std::vector<double>& angles2,
00296                                  double delta) const;
00297 
00298   // double getJointDistanceMax(const std::vector<double>& angles1,
00299   //                            const std::vector<double>& angles2);
00300 
00301 
00302   bool interpolateAndCollisionCheck(const std::vector<double> angles1,
00303                                     const std::vector<double> angles2,
00304                                     std::vector<std::vector<double> >& state_values);
00305 
00306   inline double getEuclideanDistance(double x1, double y1, double z1, double x2, double y2, double z2) const
00307   {
00308     return sqrt((x1-x2)*(x1-x2) + (y1-y2)*(y1-y2) + (z1-z2)*(z1-z2));
00309   }
00310 
00311   //temp
00312   double closest_to_goal_;
00313 };
00314 
00315 //angles are counterclockwise from 0 to 360 in radians, 0 is the center of bin 0, ...
00316 inline void EnvironmentChain3D::convertCoordToJointAngles(const std::vector<int> &coord, std::vector<double> &angles)
00317 {
00318   angles.resize(coord.size());
00319   for(size_t i = 0; i < coord.size(); i++)
00320     angles[i] = coord[i]*angle_discretization_;
00321 }
00322 
00323 inline void EnvironmentChain3D::convertJointAnglesToCoord(const std::vector<double> &angle, std::vector<int> &coord)
00324 {
00325   coord.resize(angle.size());
00326   for(unsigned int i = 0; i < angle.size(); i++)
00327   {
00328     //NOTE: Added 3/1/09
00329     double pos_angle = angle[i];
00330     if(pos_angle < 0.0)
00331       pos_angle += 2*M_PI;
00332 
00333     coord[i] = (int)((pos_angle + angle_discretization_*0.5)/angle_discretization_);
00334   }
00335 }
00336 
00337 // inline double EnvironmentChain3D::getEuclideanDistance(double x1, double y1, double z1, double x2, double y2, double z2) const
00338 // {
00339 //   return sqrt((x1-x2)*(x1-x2) + (y1-y2)*(y1-y2) + (z1-z2)*(z1-z2));
00340 // }
00341 
00342 } //namespace
00343 
00344 #endif


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