#include <planning_scene_interface.h>
Classes | |
class | PlanningSceneInterfaceImpl |
Public Member Functions | |
PlanningSceneInterface () | |
~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()). + 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=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::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::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::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::CollisionObject &collision_objects) |
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::CollisionObject > &collision_objects) |
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. | |
bool | applyAttachedCollisionObject (const moveit_msgs::AttachedCollisionObject &attached_collision_objects) |
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::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::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::CollisionObject > &collision_objects) 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. | |
Private Attributes | |
PlanningSceneInterfaceImpl * | impl_ |
Definition at line 52 of file planning_scene_interface.h.
Definition at line 260 of file planning_scene_interface.cpp.
Definition at line 265 of file planning_scene_interface.cpp.
void moveit::planning_interface::PlanningSceneInterface::addCollisionObjects | ( | const std::vector< moveit_msgs::CollisionObject > & | collision_objects | ) | 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 345 of file planning_scene_interface.cpp.
bool moveit::planning_interface::PlanningSceneInterface::applyAttachedCollisionObject | ( | const moveit_msgs::AttachedCollisionObject & | attached_collision_objects | ) |
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 320 of file planning_scene_interface.cpp.
bool moveit::planning_interface::PlanningSceneInterface::applyAttachedCollisionObjects | ( | const std::vector< moveit_msgs::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 330 of file planning_scene_interface.cpp.
bool moveit::planning_interface::PlanningSceneInterface::applyCollisionObject | ( | const moveit_msgs::CollisionObject & | collision_objects | ) |
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 301 of file planning_scene_interface.cpp.
bool moveit::planning_interface::PlanningSceneInterface::applyCollisionObjects | ( | const std::vector< moveit_msgs::CollisionObject > & | collision_objects | ) |
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.
Definition at line 311 of file planning_scene_interface.cpp.
bool moveit::planning_interface::PlanningSceneInterface::applyPlanningScene | ( | const moveit_msgs::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 340 of file planning_scene_interface.cpp.
std::map< std::string, moveit_msgs::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 296 of file planning_scene_interface.cpp.
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 270 of file planning_scene_interface.cpp.
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 275 of file planning_scene_interface.cpp.
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 76 of file planning_scene_interface.h.
std::map< std::string, geometry_msgs::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 284 of file planning_scene_interface.cpp.
std::map< std::string, moveit_msgs::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 290 of file planning_scene_interface.cpp.
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 351 of file planning_scene_interface.cpp.
Definition at line 133 of file planning_scene_interface.h.