moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#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. More... | |
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()). More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
void | removeCollisionObjects (const std::vector< std::string > &object_ids) const |
Remove collision objects from the world via /planning_scene. More... | |
Definition at line 52 of file planning_scene_interface.h.
|
explicit |
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 294 of file planning_scene_interface.cpp.
moveit::planning_interface::PlanningSceneInterface::~PlanningSceneInterface | ( | ) |
Definition at line 299 of file planning_scene_interface.cpp.
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 407 of file planning_scene_interface.cpp.
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 381 of file planning_scene_interface.cpp.
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 392 of file planning_scene_interface.cpp.
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 335 of file planning_scene_interface.cpp.
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 345 of file planning_scene_interface.cpp.
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 360 of file planning_scene_interface.cpp.
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 402 of file planning_scene_interface.cpp.
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 330 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 304 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()).
Definition at line 309 of file planning_scene_interface.cpp.
|
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.
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 318 of file planning_scene_interface.cpp.
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 324 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 413 of file planning_scene_interface.cpp.