moveit2
The MoveIt Motion Planning Framework for ROS 2.
semantic_world.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, 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: Sachin Chitta */
36 
37 #pragma once
38 
39 #include <rclcpp/rclcpp.hpp>
42 #include <object_recognition_msgs/msg/table_array.hpp>
43 #include <moveit_msgs/msg/collision_object.hpp>
44 #include <mutex>
45 
46 namespace shapes
47 {
48 MOVEIT_CLASS_FORWARD(Shape); // Defines ShapePtr, ConstPtr, WeakPtr... etc
49 }
50 
51 namespace moveit
52 {
53 namespace semantic_world
54 {
55 MOVEIT_CLASS_FORWARD(SemanticWorld); // Defines SemanticWorldPtr, ConstPtr, WeakPtr... etc
56 
61 {
62 public:
64  typedef std::function<void()> TableCallbackFn;
65 
70  SemanticWorld(const rclcpp::Node::SharedPtr& node, const planning_scene::PlanningSceneConstPtr& planning_scene);
71 
75  object_recognition_msgs::msg::TableArray getTablesInROI(double minx, double miny, double minz, double maxx,
76  double maxy, double maxz) const;
77 
81  std::vector<std::string> getTableNamesInROI(double minx, double miny, double minz, double maxx, double maxy,
82  double maxz) const;
83 
89  std::vector<geometry_msgs::msg::PoseStamped>
90  generatePlacePoses(const std::string& table_name, const shapes::ShapeConstPtr& object_shape,
91  const geometry_msgs::msg::Quaternion& object_orientation, double resolution,
92  double delta_height = 0.01, unsigned int num_heights = 2) const;
93 
99  std::vector<geometry_msgs::msg::PoseStamped>
100  generatePlacePoses(const object_recognition_msgs::msg::Table& table, const shapes::ShapeConstPtr& object_shape,
101  const geometry_msgs::msg::Quaternion& object_orientation, double resolution,
102  double delta_height = 0.01, unsigned int num_heights = 2) const;
110  std::vector<geometry_msgs::msg::PoseStamped> generatePlacePoses(const object_recognition_msgs::msg::Table& table,
111  double resolution, double height_above_table,
112  double delta_height = 0.01,
113  unsigned int num_heights = 2,
114  double min_distance_from_edge = 0.10) const;
115 
116  void clear();
117 
119 
120  visualization_msgs::msg::MarkerArray
121  getPlaceLocationsMarker(const std::vector<geometry_msgs::msg::PoseStamped>& poses) const;
122 
123  void addTableCallback(const TableCallbackFn& table_callback)
124  {
125  table_callback_ = table_callback;
126  }
127 
128  std::string findObjectTable(const geometry_msgs::msg::Pose& pose, double min_distance_from_edge = 0.0,
129  double min_vertical_offset = 0.0) const;
130 
131  bool isInsideTableContour(const geometry_msgs::msg::Pose& pose, const object_recognition_msgs::msg::Table& table,
132  double min_distance_from_edge = 0.0, double min_vertical_offset = 0.0) const;
133 
134 private:
135  shapes::Mesh* createSolidMeshFromPlanarPolygon(const shapes::Mesh& polygon, double thickness) const;
136 
137  shapes::Mesh* orientPlanarPolygon(const shapes::Mesh& polygon) const;
138 
139  void tableCallback(const object_recognition_msgs::msg::TableArray::ConstSharedPtr& msg);
140 
141  void transformTableArray(object_recognition_msgs::msg::TableArray& table_array) const;
142 
143  planning_scene::PlanningSceneConstPtr planning_scene_;
144 
145  rclcpp::Node::SharedPtr node_handle_;
146 
147  object_recognition_msgs::msg::TableArray table_array_;
148 
149  std::vector<geometry_msgs::msg::PoseStamped> place_poses_;
150 
151  std::map<std::string, object_recognition_msgs::msg::Table> current_tables_in_collision_world_;
152 
153  rclcpp::Subscription<object_recognition_msgs::msg::TableArray>::SharedPtr table_subscriber_;
154 
155  rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr visualization_publisher_;
156  rclcpp::Publisher<moveit_msgs::msg::CollisionObject>::SharedPtr collision_object_publisher_;
157 
158  TableCallbackFn table_callback_;
159 
160  rclcpp::Publisher<moveit_msgs::msg::PlanningScene>::SharedPtr planning_scene_diff_publisher_;
161 };
162 } // namespace semantic_world
163 } // namespace moveit
A (simple) semantic world representation for pick and place and other tasks.
std::vector< std::string > getTableNamesInROI(double minx, double miny, double minz, double maxx, double maxy, double maxz) const
Get all the tables within a region of interest.
object_recognition_msgs::msg::TableArray getTablesInROI(double minx, double miny, double minz, double maxx, double maxy, double maxz) const
Get all the tables within a region of interest.
visualization_msgs::msg::MarkerArray getPlaceLocationsMarker(const std::vector< geometry_msgs::msg::PoseStamped > &poses) const
std::string findObjectTable(const geometry_msgs::msg::Pose &pose, double min_distance_from_edge=0.0, double min_vertical_offset=0.0) const
std::vector< geometry_msgs::msg::PoseStamped > generatePlacePoses(const std::string &table_name, const shapes::ShapeConstPtr &object_shape, const geometry_msgs::msg::Quaternion &object_orientation, double resolution, double delta_height=0.01, unsigned int num_heights=2) const
Generate possible place poses on the table for a given object. This chooses appropriate values for mi...
bool isInsideTableContour(const geometry_msgs::msg::Pose &pose, const object_recognition_msgs::msg::Table &table, double min_distance_from_edge=0.0, double min_vertical_offset=0.0) const
void addTableCallback(const TableCallbackFn &table_callback)
std::function< void()> TableCallbackFn
The signature for a callback on receiving table messages.
SemanticWorld(const rclcpp::Node::SharedPtr &node, const planning_scene::PlanningSceneConstPtr &planning_scene)
A (simple) semantic world representation for pick and place and other tasks. Currently this is used o...
MOVEIT_CLASS_FORWARD(SemanticWorld)
Main namespace for MoveIt.
Definition: exceptions.h:43
This namespace includes the central class for representing planning contexts.
Definition: world.h:49
MOVEIT_CLASS_FORWARD(Shape)