moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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/msg/cost_source.hpp>
41#include <moveit_msgs/msg/contact_information.hpp>
42#include <visualization_msgs/msg/marker_array.hpp>
43
44#include <rclcpp/rclcpp.hpp>
45#include <rcl/time.h>
46#include <rclcpp/clock.hpp>
47#include <rclcpp/time.hpp>
48
49namespace collision_detection
50{
51void getCollisionMarkersFromContacts(visualization_msgs::msg::MarkerArray& arr, const std::string& frame_id,
52 const CollisionResult::ContactMap& con, const std_msgs::msg::ColorRGBA& color,
53 const rclcpp::Duration& lifetime, const double radius = 0.035);
54
55void getCollisionMarkersFromContacts(visualization_msgs::msg::MarkerArray& arr, const std::string& frame_id,
57
59void getCostMarkers(visualization_msgs::msg::MarkerArray& arr, const std::string& frame_id,
60 std::set<CostSource>& cost_sources);
61
62void getCostMarkers(visualization_msgs::msg::MarkerArray& arr, const std::string& frame_id,
63 std::set<CostSource>& cost_sources, const std_msgs::msg::ColorRGBA& color,
64 const rclcpp::Duration& lifetime);
65
66double getTotalCost(const std::set<CostSource>& cost_sources);
67
68void removeCostSources(std::set<CostSource>& cost_sources, const std::set<CostSource>& cost_sources_to_remove,
69 double overlap_fraction);
70void intersectCostSources(std::set<CostSource>& cost_sources, const std::set<CostSource>& a,
71 const std::set<CostSource>& b);
72void removeOverlapping(std::set<CostSource>& cost_sources, double overlap_fraction);
73
74bool getSensorPositioning(geometry_msgs::msg::Point& point, const std::set<CostSource>& cost_sources);
75
76void costSourceToMsg(const CostSource& cost_source, moveit_msgs::msg::CostSource& msg);
77void contactToMsg(const Contact& contact, moveit_msgs::msg::ContactInformation& msg);
78} // namespace collision_detection
bool getSensorPositioning(geometry_msgs::msg::Point &point, const std::set< CostSource > &cost_sources)
double getTotalCost(const std::set< CostSource > &cost_sources)
void getCollisionMarkersFromContacts(visualization_msgs::msg::MarkerArray &arr, const std::string &frame_id, const CollisionResult::ContactMap &con, const std_msgs::msg::ColorRGBA &color, const rclcpp::Duration &lifetime, const double radius=0.035)
void getCostMarkers(visualization_msgs::msg::MarkerArray &arr, const std::string &frame_id, std::set< CostSource > &cost_sources)
void intersectCostSources(std::set< CostSource > &cost_sources, const std::set< CostSource > &a, const std::set< CostSource > &b)
void removeCostSources(std::set< CostSource > &cost_sources, const std::set< CostSource > &cost_sources_to_remove, double overlap_fraction)
void contactToMsg(const Contact &contact, moveit_msgs::msg::ContactInformation &msg)
void removeOverlapping(std::set< CostSource > &cost_sources, double overlap_fraction)
void costSourceToMsg(const CostSource &cost_source, moveit_msgs::msg::CostSource &msg)
std::map< std::pair< std::string, std::string >, std::vector< Contact > > ContactMap
A map returning the pairs of body ids in contact, plus their contact details.