Classes | Public Member Functions | Private Attributes
moveit::planning_interface::PlanningSceneInterface Class Reference

#include <planning_scene_interface.h>

List of all members.

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)
void addCollisionObjects (const std::vector< moveit_msgs::CollisionObject > &collision_objects) const
 Add collision objects to the world 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.

Private Attributes

PlanningSceneInterfaceImplimpl_

Detailed Description

Definition at line 49 of file planning_scene_interface.h.


Constructor & Destructor Documentation

Definition at line 192 of file planning_scene_interface.cpp.

Definition at line 197 of file planning_scene_interface.cpp.


Member Function Documentation

void moveit::planning_interface::PlanningSceneInterface::addCollisionObjects ( const std::vector< moveit_msgs::CollisionObject > &  collision_objects) const

Add collision objects to the world Make sure object.operation is set to object.ADD.

Definition at line 217 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 202 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 207 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 69 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)

Definition at line 212 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.

Definition at line 222 of file planning_scene_interface.cpp.


Member Data Documentation

Definition at line 88 of file planning_scene_interface.h.


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


planning_interface
Author(s): Ioan Sucan
autogenerated on Wed Aug 26 2015 12:44:13