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>
76 double maxz,
bool with_type, std::vector<std::string>& types);
82 double maxz,
bool with_type =
false)
84 std::vector<std::string> empty_vector_string;
89 std::map<std::string, geometry_msgs::msg::Pose>
getObjectPoses(
const std::vector<std::string>& object_ids);
93 std::map<std::string, moveit_msgs::msg::CollisionObject>
94 getObjects(
const std::vector<std::string>& object_ids = std::vector<std::string>());
98 std::map<std::string, moveit_msgs::msg::AttachedCollisionObject>
99 getAttachedObjects(
const std::vector<std::string>& object_ids = std::vector<std::string>());
108 const std_msgs::msg::ColorRGBA& object_color);
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>());
124 const std::vector<moveit_msgs::msg::AttachedCollisionObject>& attached_collision_objects);
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;
148 class PlanningSceneInterfaceImpl;
149 PlanningSceneInterfaceImpl* impl_;
#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...
~PlanningSceneInterface()
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.
This namespace includes the base class for MoveIt planners.