collision_tools.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, 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: Ioan Sucan */
36 
37 #pragma once
38 
40 #include <moveit_msgs/CostSource.h>
41 #include <moveit_msgs/ContactInformation.h>
42 #include <visualization_msgs/MarkerArray.h>
43 
44 namespace collision_detection
45 {
46 void getCollisionMarkersFromContacts(visualization_msgs::MarkerArray& arr, const std::string& frame_id,
47  const CollisionResult::ContactMap& con, const std_msgs::ColorRGBA& color,
48  const ros::Duration& lifetime, const double radius = 0.035);
49 
50 void getCollisionMarkersFromContacts(visualization_msgs::MarkerArray& arr, const std::string& frame_id,
51  const CollisionResult::ContactMap& con);
52 
54 void getCostMarkers(visualization_msgs::MarkerArray& arr, const std::string& frame_id,
55  std::set<CostSource>& cost_sources);
56 
57 void getCostMarkers(visualization_msgs::MarkerArray& arr, const std::string& frame_id,
58  std::set<CostSource>& cost_sources, const std_msgs::ColorRGBA& color,
59  const ros::Duration& lifetime);
60 
61 double getTotalCost(const std::set<CostSource>& cost_sources);
62 
63 void removeCostSources(std::set<CostSource>& cost_sources, const std::set<CostSource>& cost_sources_to_remove,
64  double overlap_fraction);
65 void intersectCostSources(std::set<CostSource>& cost_sources, const std::set<CostSource>& a,
66  const std::set<CostSource>& b);
67 void removeOverlapping(std::set<CostSource>& cost_sources, double overlap_fraction);
68 
69 bool getSensorPositioning(geometry_msgs::Point& point, const std::set<CostSource>& cost_sources);
70 
71 void costSourceToMsg(const CostSource& cost_source, moveit_msgs::CostSource& msg);
72 void contactToMsg(const Contact& contact, moveit_msgs::ContactInformation& msg);
73 } // namespace collision_detection
collision_detection::getTotalCost
double getTotalCost(const std::set< CostSource > &cost_sources)
Definition: collision_tools.cpp:179
collision_detection::CollisionResult::ContactMap
std::map< std::pair< std::string, std::string >, std::vector< Contact > > ContactMap
Definition: include/moveit/collision_detection/collision_common.h:387
collision_detection::removeCostSources
void removeCostSources(std::set< CostSource > &cost_sources, const std::set< CostSource > &cost_sources_to_remove, double overlap_fraction)
Definition: collision_tools.cpp:240
collision_detection::costSourceToMsg
void costSourceToMsg(const CostSource &cost_source, moveit_msgs::CostSource &msg)
Definition: collision_tools.cpp:293
collision_detection::contactToMsg
void contactToMsg(const Contact &contact, moveit_msgs::ContactInformation &msg)
Definition: collision_tools.cpp:304
collision_detection::removeOverlapping
void removeOverlapping(std::set< CostSource > &cost_sources, double overlap_fraction)
Definition: collision_tools.cpp:210
collision_common.h
collision_detection::getCostMarkers
void getCostMarkers(visualization_msgs::MarkerArray &arr, const std::string &frame_id, std::set< CostSource > &cost_sources)
Definition: collision_tools.cpp:74
point
std::chrono::system_clock::time_point point
collision_detection::intersectCostSources
void intersectCostSources(std::set< CostSource > &cost_sources, const std::set< CostSource > &a, const std::set< CostSource > &b)
Definition: collision_tools.cpp:187
collision_detection::getSensorPositioning
bool getSensorPositioning(geometry_msgs::Point &point, const std::set< CostSource > &cost_sources)
Definition: collision_tools.cpp:166
ros::Duration
collision_detection::getCollisionMarkersFromContacts
void getCollisionMarkersFromContacts(visualization_msgs::MarkerArray &arr, const std::string &frame_id, const CollisionResult::ContactMap &con, const std_msgs::ColorRGBA &color, const ros::Duration &lifetime, const double radius=0.035)
Definition: collision_tools.cpp:127
collision_detection
Definition: collision_detector_allocator_allvalid.h:42


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sat Dec 21 2024 03:23:41