collision_common_distance_field.h
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: E. Gil Jones */
00036 
00037 #ifndef MOVEIT_COLLISION_DETECTION_DISTANCE_FIELD_COLLISION_COMMON_
00038 #define MOVEIT_COLLISION_DETECTION_DISTANCE_FIELD_COLLISION_COMMON_
00039 
00040 #include <moveit/robot_state/robot_state.h>
00041 #include <moveit/collision_detection/collision_common.h>
00042 #include <moveit/collision_detection/collision_world.h>
00043 #include <moveit/collision_distance_field/collision_distance_field_types.h>
00044 
00045 namespace collision_detection
00046 {
00047 struct DistanceFieldCacheEntry;
00048 
00055 struct GroupStateRepresentation
00056 {
00057   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00058 
00059   GroupStateRepresentation(){};
00060   GroupStateRepresentation(const GroupStateRepresentation& gsr)
00061   {
00062     link_body_decompositions_.resize(gsr.link_body_decompositions_.size());
00063     for (unsigned int i = 0; i < gsr.link_body_decompositions_.size(); i++)
00064     {
00065       if (gsr.link_body_decompositions_[i])
00066       {
00067         link_body_decompositions_[i].reset(new PosedBodySphereDecomposition(*gsr.link_body_decompositions_[i]));
00068       }
00069     }
00070 
00071     link_distance_fields_.assign(gsr.link_distance_fields_.begin(), gsr.link_distance_fields_.end());
00072 
00073     attached_body_decompositions_.resize(gsr.attached_body_decompositions_.size());
00074     for (unsigned int i = 0; i < gsr.attached_body_decompositions_.size(); i++)
00075     {
00076       (*attached_body_decompositions_[i]) = (*gsr.attached_body_decompositions_[i]);
00077     }
00078     gradients_ = gsr.gradients_;
00079   }
00080 
00082   boost::shared_ptr<const DistanceFieldCacheEntry> dfce_;
00083 
00088   std::vector<PosedBodySphereDecompositionPtr> link_body_decompositions_;
00089 
00092   std::vector<PosedBodySphereDecompositionVectorPtr> attached_body_decompositions_;
00093 
00095   std::vector<PosedDistanceFieldPtr> link_distance_fields_;
00096 
00100   std::vector<GradientInfo> gradients_;
00101 };
00102 
00109 struct DistanceFieldCacheEntry
00110 {
00111   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00112 
00114   std::string group_name_;
00116   boost::shared_ptr<robot_state::RobotState> state_;
00121   std::vector<unsigned int> state_check_indices_;
00126   std::vector<double> state_values_;
00127   /* the acm used when generating this dfce.  This dfce cannot be used to check
00128    * collisions with a different acm. */
00129   collision_detection::AllowedCollisionMatrix acm_;
00132   boost::shared_ptr<distance_field::DistanceField> distance_field_;
00135   boost::shared_ptr<GroupStateRepresentation> pregenerated_group_state_representation_;
00139   std::vector<std::string> link_names_;
00141   std::vector<bool> link_has_geometry_;
00147   std::vector<unsigned int> link_body_indices_;
00150   std::vector<unsigned int> link_state_indices_;
00152   std::vector<std::string> attached_body_names_;
00155   std::vector<unsigned int> attached_body_link_state_indices_;
00158   std::vector<bool> self_collision_enabled_;
00164   std::vector<std::vector<bool>> intra_group_collision_enabled_;
00165 };
00166 
00167 BodyDecompositionConstPtr getBodyDecompositionCacheEntry(const shapes::ShapeConstPtr& shape, double resolution);
00168 
00169 PosedBodyPointDecompositionVectorPtr getCollisionObjectPointDecomposition(const collision_detection::World::Object& obj,
00170                                                                           double resolution);
00171 
00172 PosedBodySphereDecompositionVectorPtr getAttachedBodySphereDecomposition(const robot_state::AttachedBody* att,
00173                                                                          double resolution);
00174 
00175 PosedBodyPointDecompositionVectorPtr getAttachedBodyPointDecomposition(const robot_state::AttachedBody* att,
00176                                                                        double resolution);
00177 
00178 void getBodySphereVisualizationMarkers(boost::shared_ptr<const collision_detection::GroupStateRepresentation>& gsr,
00179                                        std::string reference_frame, visualization_msgs::MarkerArray& body_marker_array);
00180 }
00181 #endif


moveit_experimental
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley , Jorge Nicho
autogenerated on Mon Jul 24 2017 02:21:02