collision_robot_hybrid.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: E. Gil Jones */
36 
37 #ifndef MOVEIT_COLLISION_DISTANCE_FIELD_COLLISION_ROBOT_HYBRID_H_
38 #define MOVEIT_COLLISION_DISTANCE_FIELD_COLLISION_ROBOT_HYBRID_H_
39 
44 
45 #include <boost/thread/mutex.hpp>
46 
47 namespace collision_detection
48 {
50 {
51 public:
53 
54  CollisionRobotHybrid(const robot_model::RobotModelConstPtr& robot_model);
55 
56  CollisionRobotHybrid(const robot_model::RobotModelConstPtr& robot_model,
57  const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions,
58  double size_x = DEFAULT_SIZE_X, double size_y = DEFAULT_SIZE_Y, double size_z = DEFAULT_SIZE_Z,
59  bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD,
60  double resolution = DEFAULT_RESOLUTION, double collision_tolerance = DEFAULT_COLLISION_TOLERANCE,
61  double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE, double padding = 0.0,
62  double scale = 1.0);
63 
64  CollisionRobotHybrid(const CollisionRobotHybrid& other);
65 
66  void initializeRobotDistanceField(const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions,
67  double size_x, double size_y, double size_z, bool use_signed_distance_field,
68  double resolution, double collision_tolerance, double max_propogation_distance)
69  {
70  crobot_distance_->initialize(link_body_decompositions, Eigen::Vector3d(size_x, size_y, size_z),
71  Eigen::Vector3d(0, 0, 0), use_signed_distance_field, resolution, collision_tolerance,
72  max_propogation_distance);
73  }
74 
77  const robot_state::RobotState& state) const;
78 
81  GroupStateRepresentationPtr& gsr) const;
82 
86 
90  GroupStateRepresentationPtr& gsr) const;
91  const CollisionRobotDistanceFieldConstPtr getCollisionRobotDistanceField() const
92  {
93  return crobot_distance_;
94  }
95 
96 protected:
97  CollisionRobotDistanceFieldPtr crobot_distance_;
98 };
99 }
100 
101 #endif
Core components of MoveIt!
static const double DEFAULT_RESOLUTION
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:90
CollisionRobotDistanceFieldPtr crobot_distance_
static const double DEFAULT_MAX_PROPOGATION_DISTANCE
Generic interface to collision detection.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW CollisionRobotHybrid(const robot_model::RobotModelConstPtr &robot_model)
static const double DEFAULT_COLLISION_TOLERANCE
static const double resolution
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
void checkSelfCollisionDistanceField(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const robot_state::RobotState &state) const
const CollisionRobotDistanceFieldConstPtr getCollisionRobotDistanceField() const
void initializeRobotDistanceField(const std::map< std::string, std::vector< CollisionSphere >> &link_body_decompositions, double size_x, double size_y, double size_z, bool use_signed_distance_field, double resolution, double collision_tolerance, double max_propogation_distance)
static const bool DEFAULT_USE_SIGNED_DISTANCE_FIELD
Representation of a robot&#39;s state. This includes position, velocity, acceleration and effort...
Definition: robot_state.h:123


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Fri Oct 11 2019 03:56:04