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/ObjectColor.h>
42 #include <moveit_msgs/CollisionObject.h>
43 #include <moveit_msgs/AttachedCollisionObject.h>
44 #include <moveit_msgs/PlanningScene.h>
45 
46 namespace moveit
47 {
48 namespace planning_interface
49 {
50 MOVEIT_CLASS_FORWARD(PlanningSceneInterface); // Defines PlanningSceneInterfacePtr, ConstPtr, WeakPtr... etc
51 
52 class PlanningSceneInterface
53 {
54 public:
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::Pose> getObjectPoses(const std::vector<std::string>& object_ids);
90 
93  std::map<std::string, moveit_msgs::CollisionObject>
94  getObjects(const std::vector<std::string>& object_ids = std::vector<std::string>());
95 
98  std::map<std::string, moveit_msgs::AttachedCollisionObject>
99  getAttachedObjects(const std::vector<std::string>& object_ids = std::vector<std::string>());
100 
103  bool applyCollisionObject(const moveit_msgs::CollisionObject& collision_object);
104 
107  bool applyCollisionObject(const moveit_msgs::CollisionObject& collision_object,
108  const std_msgs::ColorRGBA& object_color);
109 
114  const std::vector<moveit_msgs::CollisionObject>& collision_objects,
115  const std::vector<moveit_msgs::ObjectColor>& object_colors = std::vector<moveit_msgs::ObjectColor>());
116 
119  bool applyAttachedCollisionObject(const moveit_msgs::AttachedCollisionObject& attached_collision_object);
120 
123  bool
124  applyAttachedCollisionObjects(const std::vector<moveit_msgs::AttachedCollisionObject>& attached_collision_objects);
125 
127  moveit_msgs::PlanningScene getPlanningSceneMsg(uint32_t components);
128 
131  bool applyPlanningScene(const moveit_msgs::PlanningScene& ps);
132 
138  void addCollisionObjects(
139  const std::vector<moveit_msgs::CollisionObject>& collision_objects,
140  const std::vector<moveit_msgs::ObjectColor>& object_colors = std::vector<moveit_msgs::ObjectColor>()) const;
141 
146  void removeCollisionObjects(const std::vector<std::string>& object_ids) const;
147 
152  bool clear();
153 
156 private:
159 };
160 } // namespace planning_interface
161 } // namespace moveit
moveit::planning_interface::PlanningSceneInterface::applyAttachedCollisionObject
bool applyAttachedCollisionObject(const moveit_msgs::AttachedCollisionObject &attached_collision_object)
Apply attached collision object to the planning scene of the move_group node synchronously....
Definition: planning_scene_interface/src/planning_scene_interface.cpp:472
moveit::planning_interface::PlanningSceneInterface::clear
bool clear()
Remove all the collision and attached objects from the world via the planning scene of the move_group...
Definition: planning_scene_interface/src/planning_scene_interface.cpp:513
moveit::planning_interface::PlanningSceneInterface::applyAttachedCollisionObjects
bool applyAttachedCollisionObjects(const std::vector< moveit_msgs::AttachedCollisionObject > &attached_collision_objects)
Apply attached collision objects to the planning scene of the move_group node synchronously....
Definition: planning_scene_interface/src/planning_scene_interface.cpp:482
moveit::planning_interface::PlanningSceneInterface::getKnownObjectNames
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...
Definition: planning_scene_interface/src/planning_scene_interface.cpp:396
robot_state.h
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterface
PlanningSceneInterface(const std::string &ns="", bool wait=true)
Definition: planning_scene_interface/src/planning_scene_interface.cpp:386
moveit::planning_interface::PlanningSceneInterface::applyPlanningScene
bool applyPlanningScene(const moveit_msgs::PlanningScene &ps)
Update the planning_scene of the move_group node with the given ps synchronously. Other PlanningScene...
Definition: planning_scene_interface/src/planning_scene_interface.cpp:497
moveit::planning_interface::PlanningSceneInterface::getObjectPoses
std::map< std::string, geometry_msgs::Pose > getObjectPoses(const std::vector< std::string > &object_ids)
Get the poses from the objects identified by the given object ids list.
Definition: planning_scene_interface/src/planning_scene_interface.cpp:410
moveit::planning_interface::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(MoveGroupInterface)
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl
Definition: planning_scene_interface/src/planning_scene_interface.cpp:115
moveit::planning_interface::PlanningSceneInterface::impl_
PlanningSceneInterfaceImpl * impl_
Definition: planning_scene_interface.h:221
moveit::planning_interface::PlanningSceneInterface::~PlanningSceneInterface
~PlanningSceneInterface()
Definition: planning_scene_interface/src/planning_scene_interface.cpp:391
moveit::planning_interface::PlanningSceneInterface::removeCollisionObjects
void removeCollisionObjects(const std::vector< std::string > &object_ids) const
Remove collision objects from the world via /planning_scene.
Definition: planning_scene_interface/src/planning_scene_interface.cpp:508
moveit
moveit::planning_interface::PlanningSceneInterface::getObjects
std::map< std::string, moveit_msgs::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...
Definition: planning_scene_interface/src/planning_scene_interface.cpp:416
class_forward.h
moveit::planning_interface::PlanningSceneInterface::applyCollisionObjects
bool applyCollisionObjects(const std::vector< moveit_msgs::CollisionObject > &collision_objects, const std::vector< moveit_msgs::ObjectColor > &object_colors=std::vector< moveit_msgs::ObjectColor >())
Apply collision objects to the planning scene of the move_group node synchronously....
Definition: planning_scene_interface/src/planning_scene_interface.cpp:452
planning_interface
moveit::planning_interface::PlanningSceneInterface::getAttachedObjects
std::map< std::string, moveit_msgs::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,...
Definition: planning_scene_interface/src/planning_scene_interface.cpp:422
moveit::planning_interface::PlanningSceneInterface::applyCollisionObject
bool applyCollisionObject(const moveit_msgs::CollisionObject &collision_object)
Apply collision object to the planning scene of the move_group node synchronously....
Definition: planning_scene_interface/src/planning_scene_interface.cpp:427
moveit::planning_interface::PlanningSceneInterface::addCollisionObjects
void addCollisionObjects(const std::vector< moveit_msgs::CollisionObject > &collision_objects, const std::vector< moveit_msgs::ObjectColor > &object_colors=std::vector< moveit_msgs::ObjectColor >()) const
Add collision objects to the world via /planning_scene. Make sure object.operation is set to object....
Definition: planning_scene_interface/src/planning_scene_interface.cpp:502
moveit::planning_interface::PlanningSceneInterface::getKnownObjectNamesInROI
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...
Definition: planning_scene_interface/src/planning_scene_interface.cpp:401
moveit::planning_interface::PlanningSceneInterface::getPlanningSceneMsg
moveit_msgs::PlanningScene getPlanningSceneMsg(uint32_t components)
Get given components from move_group's PlanningScene.
Definition: planning_scene_interface/src/planning_scene_interface.cpp:492


planning_interface
Author(s): Ioan Sucan
autogenerated on Sun Mar 3 2024 03:25:15