moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
planning_scene_interface.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: Ioan Sucan */
36
37#pragma once
38
41#include <moveit_msgs/msg/object_color.hpp>
42#include <moveit_msgs/msg/collision_object.hpp>
43#include <moveit_msgs/msg/attached_collision_object.hpp>
44#include <moveit_msgs/msg/planning_scene.hpp>
45
46namespace moveit
47{
48namespace planning_interface
49{
50MOVEIT_CLASS_FORWARD(PlanningSceneInterface); // Defines PlanningSceneInterfacePtr, ConstPtr, WeakPtr... etc
51
53{
54public:
60 explicit PlanningSceneInterface(const std::string& ns = "", bool wait = true);
62
70 std::vector<std::string> getKnownObjectNames(bool with_type = false);
71
75 std::vector<std::string> getKnownObjectNamesInROI(double minx, double miny, double minz, double maxx, double maxy,
76 double maxz, bool with_type, std::vector<std::string>& types);
77
81 std::vector<std::string> getKnownObjectNamesInROI(double minx, double miny, double minz, double maxx, double maxy,
82 double maxz, bool with_type = false)
83 {
84 std::vector<std::string> empty_vector_string;
85 return getKnownObjectNamesInROI(minx, miny, minz, maxx, maxy, maxz, with_type, empty_vector_string);
86 };
87
89 std::map<std::string, geometry_msgs::msg::Pose> getObjectPoses(const std::vector<std::string>& object_ids);
90
93 std::map<std::string, moveit_msgs::msg::CollisionObject>
94 getObjects(const std::vector<std::string>& object_ids = std::vector<std::string>());
95
98 std::map<std::string, moveit_msgs::msg::AttachedCollisionObject>
99 getAttachedObjects(const std::vector<std::string>& object_ids = std::vector<std::string>());
100
103 bool applyCollisionObject(const moveit_msgs::msg::CollisionObject& collision_object);
104
107 bool applyCollisionObject(const moveit_msgs::msg::CollisionObject& collision_object,
108 const std_msgs::msg::ColorRGBA& object_color);
109
114 const std::vector<moveit_msgs::msg::CollisionObject>& collision_objects,
115 const std::vector<moveit_msgs::msg::ObjectColor>& object_colors = std::vector<moveit_msgs::msg::ObjectColor>());
116
119 bool applyAttachedCollisionObject(const moveit_msgs::msg::AttachedCollisionObject& attached_collision_object);
120
124 const std::vector<moveit_msgs::msg::AttachedCollisionObject>& attached_collision_objects);
125
128 bool applyPlanningScene(const moveit_msgs::msg::PlanningScene& ps);
129
135 void addCollisionObjects(const std::vector<moveit_msgs::msg::CollisionObject>& collision_objects,
136 const std::vector<moveit_msgs::msg::ObjectColor>& object_colors =
137 std::vector<moveit_msgs::msg::ObjectColor>()) const;
138
143 void removeCollisionObjects(const std::vector<std::string>& object_ids) const;
144
147private:
148 class PlanningSceneInterfaceImpl;
149 PlanningSceneInterfaceImpl* impl_;
150};
151} // namespace planning_interface
152} // namespace moveit
#define MOVEIT_CLASS_FORWARD(C)
bool applyAttachedCollisionObject(const moveit_msgs::msg::AttachedCollisionObject &attached_collision_object)
Apply attached collision object to the planning scene of the move_group node synchronously....
std::map< std::string, moveit_msgs::msg::AttachedCollisionObject > getAttachedObjects(const std::vector< std::string > &object_ids=std::vector< std::string >())
Get the attached objects identified by the given object ids list. If no ids are provided,...
bool applyPlanningScene(const moveit_msgs::msg::PlanningScene &ps)
Update the planning_scene of the move_group node with the given ps synchronously. Other PlanningScene...
std::vector< std::string > getKnownObjectNames(bool with_type=false)
Get the names of all known objects in the world. If with_type is set to true, only return objects tha...
bool applyAttachedCollisionObjects(const std::vector< moveit_msgs::msg::AttachedCollisionObject > &attached_collision_objects)
Apply attached collision objects to the planning scene of the move_group node synchronously....
std::map< std::string, moveit_msgs::msg::CollisionObject > getObjects(const std::vector< std::string > &object_ids=std::vector< std::string >())
Get the objects identified by the given object ids list. If no ids are provided, return all the known...
std::vector< std::string > getKnownObjectNamesInROI(double minx, double miny, double minz, double maxx, double maxy, double maxz, bool with_type, std::vector< std::string > &types)
Get the names of known objects in the world that are located within a bounding region (specified in t...
void removeCollisionObjects(const std::vector< std::string > &object_ids) const
Remove collision objects from the world via /planning_scene.
std::map< std::string, geometry_msgs::msg::Pose > getObjectPoses(const std::vector< std::string > &object_ids)
Get the poses from the objects identified by the given object ids list.
std::vector< std::string > getKnownObjectNamesInROI(double minx, double miny, double minz, double maxx, double maxy, double maxz, bool with_type=false)
Get the names of known objects in the world that are located within a bounding region (specified in t...
bool applyCollisionObject(const moveit_msgs::msg::CollisionObject &collision_object)
Apply collision object to the planning scene of the move_group node synchronously....
bool applyCollisionObjects(const std::vector< moveit_msgs::msg::CollisionObject > &collision_objects, const std::vector< moveit_msgs::msg::ObjectColor > &object_colors=std::vector< moveit_msgs::msg::ObjectColor >())
Apply collision objects to the planning scene of the move_group node synchronously....
void addCollisionObjects(const std::vector< moveit_msgs::msg::CollisionObject > &collision_objects, const std::vector< moveit_msgs::msg::ObjectColor > &object_colors=std::vector< moveit_msgs::msg::ObjectColor >()) const
Add collision objects to the world via /planning_scene. Make sure object.operation is set to object....
Main namespace for MoveIt.
Definition exceptions.h:43
This namespace includes the base class for MoveIt planners.