|
void | addCollisionObjects (const std::vector< moveit_msgs::CollisionObject > &collision_objects, const std::vector< moveit_msgs::ObjectColor > &object_colors) 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 (const std::string &ns="") |
|
void | removeCollisionObjects (const std::vector< std::string > &object_ids) const |
|
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::PlanningSceneInterfaceImpl |
( |
const std::string & |
ns = "" | ) |
|
|
inlineexplicit |
void moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::addCollisionObjects |
( |
const std::vector< moveit_msgs::CollisionObject > & |
collision_objects, |
|
|
const std::vector< moveit_msgs::ObjectColor > & |
object_colors |
|
) |
| const |
|
inline |
bool moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::applyPlanningScene |
( |
const moveit_msgs::PlanningScene & |
planning_scene | ) |
|
|
inline |
std::map<std::string, moveit_msgs::AttachedCollisionObject> moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::getAttachedObjects |
( |
const std::vector< std::string > & |
object_ids | ) |
|
|
inline |
std::vector<std::string> moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::getKnownObjectNames |
( |
bool |
with_type | ) |
|
|
inline |
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 |
std::map<std::string, geometry_msgs::Pose> moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::getObjectPoses |
( |
const std::vector< std::string > & |
object_ids | ) |
|
|
inline |
std::map<std::string, moveit_msgs::CollisionObject> moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::getObjects |
( |
const std::vector< std::string > & |
object_ids | ) |
|
|
inline |
void moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::removeCollisionObjects |
( |
const std::vector< std::string > & |
object_ids | ) |
const |
|
inline |
ros::ServiceClient moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::apply_planning_scene_service_ |
|
private |
ros::NodeHandle moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::node_handle_ |
|
private |
ros::Publisher moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::planning_scene_diff_publisher_ |
|
private |
ros::ServiceClient moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::planning_scene_service_ |
|
private |
robot_model::RobotModelConstPtr moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::robot_model_ |
|
private |
The documentation for this class was generated from the following file: