moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Classes | Public Member Functions | List of all members
moveit::planning_interface::PlanningSceneInterface Class Reference

#include <planning_scene_interface.h>

Classes

class  PlanningSceneInterfaceImpl
 

Public Member Functions

 PlanningSceneInterface (const std::string &ns="", bool wait=true)
 
 ~PlanningSceneInterface ()
 
Manage the world
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 that have a known type.
 
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 the frame reported by getPlanningFrame()).
 
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 the frame reported by getPlanningFrame()). If with_type is set to true, only return objects that have a known type.
 
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::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 objects.
 
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, return all the attached objects.
 
bool applyCollisionObject (const moveit_msgs::msg::CollisionObject &collision_object)
 Apply collision object to the planning scene of the move_group node synchronously. Other PlanningSceneMonitors will NOT receive the update unless they subscribe to move_group's monitored scene.
 
bool applyCollisionObject (const moveit_msgs::msg::CollisionObject &collision_object, const std_msgs::msg::ColorRGBA &object_color)
 Apply collision object to the planning scene of the move_group node synchronously. Other PlanningSceneMonitors will NOT receive the update unless they subscribe to move_group's monitored scene.
 
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. Other PlanningSceneMonitors will NOT receive the update unless they subscribe to move_group's monitored scene. If object_colors do not specify an id, the corresponding object id from collision_objects is used.
 
bool applyAttachedCollisionObject (const moveit_msgs::msg::AttachedCollisionObject &attached_collision_object)
 Apply attached collision object to the planning scene of the move_group node synchronously. Other PlanningSceneMonitors will NOT receive the update unless they subscribe to move_group's monitored scene.
 
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. Other PlanningSceneMonitors will NOT receive the update unless they subscribe to move_group's monitored scene.
 
bool applyPlanningScene (const moveit_msgs::msg::PlanningScene &ps)
 Update the planning_scene of the move_group node with the given ps synchronously. Other PlanningSceneMonitors will NOT receive the update unless they subscribe to move_group's monitored scene.
 
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.ADD.
 
void removeCollisionObjects (const std::vector< std::string > &object_ids) const
 Remove collision objects from the world via /planning_scene.
 

Detailed Description

Definition at line 52 of file planning_scene_interface.h.

Constructor & Destructor Documentation

◆ PlanningSceneInterface()

moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterface ( const std::string &  ns = "",
bool  wait = true 
)
explicit
Parameters
ns.Namespace in which all MoveIt related topics and services are discovered
wait.Wait for services if they are not announced in ROS. If this is false, the constructor throws std::runtime_error instead.

Definition at line 305 of file planning_scene_interface.cpp.

◆ ~PlanningSceneInterface()

moveit::planning_interface::PlanningSceneInterface::~PlanningSceneInterface ( )

Definition at line 310 of file planning_scene_interface.cpp.

Member Function Documentation

◆ addCollisionObjects()

void moveit::planning_interface::PlanningSceneInterface::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.ADD.

The update runs asynchronously. If you need the objects to be available directly after you called this function, consider using applyCollisionObjects instead.

Definition at line 422 of file planning_scene_interface.cpp.

Here is the call graph for this function:

◆ applyAttachedCollisionObject()

bool moveit::planning_interface::PlanningSceneInterface::applyAttachedCollisionObject ( const moveit_msgs::msg::AttachedCollisionObject &  attached_collision_object)

Apply attached collision object to the planning scene of the move_group node synchronously. Other PlanningSceneMonitors will NOT receive the update unless they subscribe to move_group's monitored scene.

Definition at line 396 of file planning_scene_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ applyAttachedCollisionObjects()

bool moveit::planning_interface::PlanningSceneInterface::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. Other PlanningSceneMonitors will NOT receive the update unless they subscribe to move_group's monitored scene.

Definition at line 407 of file planning_scene_interface.cpp.

Here is the call graph for this function:

◆ applyCollisionObject() [1/2]

bool moveit::planning_interface::PlanningSceneInterface::applyCollisionObject ( const moveit_msgs::msg::CollisionObject &  collision_object)

Apply collision object to the planning scene of the move_group node synchronously. Other PlanningSceneMonitors will NOT receive the update unless they subscribe to move_group's monitored scene.

Definition at line 346 of file planning_scene_interface.cpp.

Here is the call graph for this function:

◆ applyCollisionObject() [2/2]

bool moveit::planning_interface::PlanningSceneInterface::applyCollisionObject ( const moveit_msgs::msg::CollisionObject &  collision_object,
const std_msgs::msg::ColorRGBA &  object_color 
)

Apply collision object to the planning scene of the move_group node synchronously. Other PlanningSceneMonitors will NOT receive the update unless they subscribe to move_group's monitored scene.

Definition at line 356 of file planning_scene_interface.cpp.

Here is the call graph for this function:

◆ applyCollisionObjects()

bool moveit::planning_interface::PlanningSceneInterface::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. Other PlanningSceneMonitors will NOT receive the update unless they subscribe to move_group's monitored scene. If object_colors do not specify an id, the corresponding object id from collision_objects is used.

Definition at line 371 of file planning_scene_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ applyPlanningScene()

bool moveit::planning_interface::PlanningSceneInterface::applyPlanningScene ( const moveit_msgs::msg::PlanningScene &  ps)

Update the planning_scene of the move_group node with the given ps synchronously. Other PlanningSceneMonitors will NOT receive the update unless they subscribe to move_group's monitored scene.

Definition at line 417 of file planning_scene_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getAttachedObjects()

std::map< std::string, moveit_msgs::msg::AttachedCollisionObject > moveit::planning_interface::PlanningSceneInterface::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, return all the attached objects.

Definition at line 341 of file planning_scene_interface.cpp.

Here is the call graph for this function:

◆ getKnownObjectNames()

std::vector< std::string > moveit::planning_interface::PlanningSceneInterface::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 that have a known type.

Definition at line 315 of file planning_scene_interface.cpp.

Here is the call graph for this function:

◆ getKnownObjectNamesInROI() [1/2]

std::vector< std::string > moveit::planning_interface::PlanningSceneInterface::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 the frame reported by getPlanningFrame()).

  • If with_type is set to true, only return objects that have a known type.

Definition at line 320 of file planning_scene_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getKnownObjectNamesInROI() [2/2]

std::vector< std::string > moveit::planning_interface::PlanningSceneInterface::getKnownObjectNamesInROI ( double  minx,
double  miny,
double  minz,
double  maxx,
double  maxy,
double  maxz,
bool  with_type = false 
)
inline

Get the names of known objects in the world that are located within a bounding region (specified in the frame reported by getPlanningFrame()). If with_type is set to true, only return objects that have a known type.

Definition at line 81 of file planning_scene_interface.h.

Here is the call graph for this function:

◆ getObjectPoses()

std::map< std::string, geometry_msgs::msg::Pose > moveit::planning_interface::PlanningSceneInterface::getObjectPoses ( const std::vector< std::string > &  object_ids)

Get the poses from the objects identified by the given object ids list.

Definition at line 329 of file planning_scene_interface.cpp.

Here is the call graph for this function:

◆ getObjects()

std::map< std::string, moveit_msgs::msg::CollisionObject > moveit::planning_interface::PlanningSceneInterface::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 objects.

Definition at line 335 of file planning_scene_interface.cpp.

Here is the call graph for this function:

◆ removeCollisionObjects()

void moveit::planning_interface::PlanningSceneInterface::removeCollisionObjects ( const std::vector< std::string > &  object_ids) const

Remove collision objects from the world via /planning_scene.

The update runs asynchronously. If you need the objects to be removed directly after you called this function, consider using applyCollisionObjects instead.

Definition at line 428 of file planning_scene_interface.cpp.

Here is the call graph for this function:

The documentation for this class was generated from the following files: