compute_default_collisions.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 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: Dave Coleman */
36 
37 #pragma once
38 
39 #include <map>
41 namespace planning_scene
42 {
43 MOVEIT_CLASS_FORWARD(PlanningScene); // Defines PlanningScenePtr, ConstPtr, WeakPtr... etc
44 }
45 
47 {
53 {
60 };
61 
66 {
67  // by default all link pairs are NOT disabled for collision checking
71 };
72 
76 typedef std::map<std::pair<std::string, std::string>, LinkPairData> LinkPairMap;
77 
87 LinkPairMap computeDefaultCollisions(const planning_scene::PlanningSceneConstPtr& parent_scene, unsigned int* progress,
88  const bool include_never_colliding, const unsigned int trials,
89  const double min_collision_faction, const bool verbose);
90 
96 void computeLinkPairs(const planning_scene::PlanningScene& scene, LinkPairMap& link_pairs);
97 
103 const std::string disabledReasonToString(DisabledReason reason);
104 
110 DisabledReason disabledReasonFromString(const std::string& reason);
111 } // namespace moveit_setup_assistant
moveit_setup_assistant::NEVER
@ NEVER
Definition: compute_default_collisions.h:54
planning_scene::PlanningScene
moveit_setup_assistant::ALWAYS
@ ALWAYS
Definition: compute_default_collisions.h:57
moveit_setup_assistant::DEFAULT
@ DEFAULT
Definition: compute_default_collisions.h:55
moveit_setup_assistant::USER
@ USER
Definition: compute_default_collisions.h:58
moveit_setup_assistant::ADJACENT
@ ADJACENT
Definition: compute_default_collisions.h:56
moveit_setup_assistant::LinkPairData::LinkPairData
LinkPairData()
Definition: compute_default_collisions.h:68
planning_scene::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(PlanningScene)
moveit_setup_assistant::NOT_DISABLED
@ NOT_DISABLED
Definition: compute_default_collisions.h:59
moveit_setup_assistant::computeDefaultCollisions
LinkPairMap computeDefaultCollisions(const planning_scene::PlanningSceneConstPtr &parent_scene, unsigned int *progress, const bool include_never_colliding, const unsigned int trials, const double min_collision_faction, const bool verbose)
Generate an adjacency list of links that are always and never in collision, to speed up collision det...
Definition: compute_default_collisions.cpp:205
moveit_setup_assistant::LinkPairData::disable_check
bool disable_check
Definition: compute_default_collisions.h:70
moveit_setup_assistant
Definition: compute_default_collisions.h:46
moveit_setup_assistant::disabledReasonToString
const std::string disabledReasonToString(DisabledReason reason)
Converts a reason for disabling a link pair into a string.
Definition: compute_default_collisions.cpp:685
moveit_setup_assistant::DisabledReason
DisabledReason
Reasons for disabling link pairs. Append "in collision" for understanding. NOT_DISABLED means the lin...
Definition: compute_default_collisions.h:52
class_forward.h
moveit_setup_assistant::computeLinkPairs
void computeLinkPairs(const planning_scene::PlanningScene &scene, LinkPairMap &link_pairs)
Generate a list of unique link pairs for all links with geometry. Order pairs alphabetically....
Definition: compute_default_collisions.cpp:352
planning_scene
moveit_setup_assistant::LinkPairData::reason
DisabledReason reason
Definition: compute_default_collisions.h:68
moveit_setup_assistant::LinkPairData
Store details on a pair of links.
Definition: compute_default_collisions.h:65
moveit_setup_assistant::disabledReasonFromString
DisabledReason disabledReasonFromString(const std::string &reason)
Converts a string reason for disabling a link pair into a struct data type.
Definition: compute_default_collisions.cpp:693
moveit_setup_assistant::LinkPairMap
std::map< std::pair< std::string, std::string >, LinkPairData > LinkPairMap
LinkPairMap is an adjacency list structure containing links in string-based form. Used for disabled l...
Definition: compute_default_collisions.h:76


moveit_setup_assistant
Author(s): Dave Coleman
autogenerated on Sat May 3 2025 02:28:04