Public Member Functions | |
void | addCollisionObjects (const std::vector< moveit_msgs::CollisionObject > &collision_objects) const |
bool | applyPlanningScene (const moveit_msgs::PlanningScene &planning_scene) |
std::map< std::string, moveit_msgs::AttachedCollisionObject > | getAttachedObjects (const std::vector< std::string > &object_ids) |
std::vector< std::string > | getKnownObjectNames (bool with_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) |
std::map< std::string, geometry_msgs::Pose > | getObjectPoses (const std::vector< std::string > &object_ids) |
std::map< std::string, moveit_msgs::CollisionObject > | getObjects (const std::vector< std::string > &object_ids) |
PlanningSceneInterfaceImpl () | |
void | removeCollisionObjects (const std::vector< std::string > &object_ids) const |
Private Attributes | |
ros::ServiceClient | apply_planning_scene_service_ |
ros::NodeHandle | node_handle_ |
ros::Publisher | planning_scene_diff_publisher_ |
ros::ServiceClient | planning_scene_service_ |
robot_model::RobotModelConstPtr | robot_model_ |
Definition at line 48 of file planning_scene_interface.cpp.
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::PlanningSceneInterfaceImpl | ( | ) | [inline] |
Definition at line 51 of file planning_scene_interface.cpp.
void moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::addCollisionObjects | ( | const std::vector< moveit_msgs::CollisionObject > & | collision_objects | ) | const [inline] |
Definition at line 230 of file planning_scene_interface.cpp.
bool moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::applyPlanningScene | ( | const moveit_msgs::PlanningScene & | planning_scene | ) | [inline] |
Definition at line 217 of file planning_scene_interface.cpp.
std::map<std::string, moveit_msgs::AttachedCollisionObject> moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::getAttachedObjects | ( | const std::vector< std::string > & | object_ids | ) | [inline] |
Definition at line 191 of file planning_scene_interface.cpp.
std::vector<std::string> moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::getKnownObjectNames | ( | bool | with_type | ) | [inline] |
Definition at line 60 of file planning_scene_interface.cpp.
std::vector<std::string> moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::getKnownObjectNamesInROI | ( | double | minx, |
double | miny, | ||
double | minz, | ||
double | maxx, | ||
double | maxy, | ||
double | maxz, | ||
bool | with_type, | ||
std::vector< std::string > & | types | ||
) | [inline] |
Definition at line 82 of file planning_scene_interface.cpp.
std::map<std::string, geometry_msgs::Pose> moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::getObjectPoses | ( | const std::vector< std::string > & | object_ids | ) | [inline] |
Definition at line 135 of file planning_scene_interface.cpp.
std::map<std::string, moveit_msgs::CollisionObject> moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::getObjects | ( | const std::vector< std::string > & | object_ids | ) | [inline] |
Definition at line 166 of file planning_scene_interface.cpp.
void moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::removeCollisionObjects | ( | const std::vector< std::string > & | object_ids | ) | const [inline] |
Definition at line 238 of file planning_scene_interface.cpp.
ros::ServiceClient moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::apply_planning_scene_service_ [private] |
Definition at line 255 of file planning_scene_interface.cpp.
ros::NodeHandle moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::node_handle_ [private] |
Definition at line 253 of file planning_scene_interface.cpp.
ros::Publisher moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::planning_scene_diff_publisher_ [private] |
Definition at line 256 of file planning_scene_interface.cpp.
ros::ServiceClient moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::planning_scene_service_ [private] |
Definition at line 254 of file planning_scene_interface.cpp.
robot_model::RobotModelConstPtr moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::robot_model_ [private] |
Definition at line 257 of file planning_scene_interface.cpp.