39 #include <moveit_msgs/srv/get_planning_scene.hpp>
40 #include <moveit_msgs/srv/apply_planning_scene.hpp>
42 #include <rclcpp/executors.hpp>
43 #include <rclcpp/future_return_code.hpp>
49 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros.planning_scene_interface.planning_scene_interface");
57 options.arguments({
"--ros-args",
"-r",
58 "__node:=" + std::string(
"planning_scene_interface_") +
59 std::to_string(
reinterpret_cast<std::size_t
>(
this)) });
60 node_ = rclcpp::Node::make_shared(
"_", ns,
options);
61 planning_scene_diff_publisher_ = node_->create_publisher<moveit_msgs::msg::PlanningScene>(
"planning_scene", 1);
62 planning_scene_service_ =
63 node_->create_client<moveit_msgs::srv::GetPlanningScene>(move_group::GET_PLANNING_SCENE_SERVICE_NAME);
64 apply_planning_scene_service_ =
65 node_->create_client<moveit_msgs::srv::ApplyPlanningScene>(move_group::APPLY_PLANNING_SCENE_SERVICE_NAME);
69 waitForService(std::static_pointer_cast<rclcpp::ClientBase>(planning_scene_service_));
70 waitForService(std::static_pointer_cast<rclcpp::ClientBase>(apply_planning_scene_service_));
76 auto request = std::make_shared<moveit_msgs::srv::GetPlanningScene::Request>();
77 moveit_msgs::srv::GetPlanningScene::Response::SharedPtr response;
78 std::vector<std::string> result;
79 request->components.components = request->components.WORLD_OBJECT_NAMES;
81 auto res = planning_scene_service_->async_send_request(request);
82 if (rclcpp::spin_until_future_complete(node_, res) != rclcpp::FutureReturnCode::SUCCESS)
90 for (
const moveit_msgs::msg::CollisionObject& collision_object : response->scene.world.collision_objects)
91 if (!collision_object.type.key.empty())
92 result.push_back(collision_object.id);
96 for (
const moveit_msgs::msg::CollisionObject& collision_object : response->scene.world.collision_objects)
97 result.push_back(collision_object.id);
103 double maxz,
bool with_type, std::vector<std::string>& types)
105 auto request = std::make_shared<moveit_msgs::srv::GetPlanningScene::Request>();
106 moveit_msgs::srv::GetPlanningScene::Response::SharedPtr response;
107 std::vector<std::string> result;
108 request->components.components = request->components.WORLD_OBJECT_GEOMETRY;
110 auto res = planning_scene_service_->async_send_request(request);
111 if (rclcpp::spin_until_future_complete(node_, res) != rclcpp::FutureReturnCode::SUCCESS)
113 RCLCPP_WARN(
LOGGER,
"Could not call planning scene service to get object names");
116 response = res.get();
118 for (
const moveit_msgs::msg::CollisionObject& collision_object : response->scene.world.collision_objects)
120 if (with_type && collision_object.type.key.empty())
122 if (collision_object.mesh_poses.empty() && collision_object.primitive_poses.empty())
125 for (
const geometry_msgs::msg::Pose& mesh_pose : collision_object.mesh_poses)
126 if (!(mesh_pose.position.x >= minx && mesh_pose.position.x <= maxx && mesh_pose.position.y >= miny &&
127 mesh_pose.position.y <= maxy && mesh_pose.position.z >= minz && mesh_pose.position.z <= maxz))
132 for (
const geometry_msgs::msg::Pose& primitive_pose : collision_object.primitive_poses)
133 if (!(primitive_pose.position.x >= minx && primitive_pose.position.x <= maxx &&
134 primitive_pose.position.y >= miny && primitive_pose.position.y <= maxy &&
135 primitive_pose.position.z >= minz && primitive_pose.position.z <= maxz))
142 result.push_back(collision_object.id);
144 types.push_back(collision_object.type.key);
150 std::map<std::string, geometry_msgs::msg::Pose>
getObjectPoses(
const std::vector<std::string>& object_ids)
152 auto request = std::make_shared<moveit_msgs::srv::GetPlanningScene::Request>();
153 moveit_msgs::srv::GetPlanningScene::Response::SharedPtr response;
154 std::map<std::string, geometry_msgs::msg::Pose> result;
155 request->components.components = request->components.WORLD_OBJECT_GEOMETRY;
157 auto res = planning_scene_service_->async_send_request(request);
158 if (rclcpp::spin_until_future_complete(node_, res) == rclcpp::FutureReturnCode::SUCCESS)
160 response = res.get();
161 for (
const moveit_msgs::msg::CollisionObject& collision_object : response->scene.world.collision_objects)
163 if (std::find(object_ids.begin(), object_ids.end(), collision_object.id) != object_ids.end())
165 result[collision_object.id] = collision_object.pose;
172 std::map<std::string, moveit_msgs::msg::CollisionObject>
getObjects(
const std::vector<std::string>& object_ids)
174 auto request = std::make_shared<moveit_msgs::srv::GetPlanningScene::Request>();
175 moveit_msgs::srv::GetPlanningScene::Response::SharedPtr response;
176 std::map<std::string, moveit_msgs::msg::CollisionObject> result;
177 request->components.components = request->components.WORLD_OBJECT_GEOMETRY;
179 auto res = planning_scene_service_->async_send_request(request);
180 if (rclcpp::spin_until_future_complete(node_, res) != rclcpp::FutureReturnCode::SUCCESS)
182 RCLCPP_WARN(
LOGGER,
"Could not call planning scene service to get object geometries");
185 response = res.get();
187 for (
const moveit_msgs::msg::CollisionObject& collision_object : response->scene.world.collision_objects)
189 if (object_ids.empty() || std::find(object_ids.begin(), object_ids.end(), collision_object.id) != object_ids.end())
191 result[collision_object.id] = collision_object;
197 std::map<std::string, moveit_msgs::msg::AttachedCollisionObject>
200 auto request = std::make_shared<moveit_msgs::srv::GetPlanningScene::Request>();
201 moveit_msgs::srv::GetPlanningScene::Response::SharedPtr response;
202 std::map<std::string, moveit_msgs::msg::AttachedCollisionObject> result;
203 request->components.components = request->components.ROBOT_STATE_ATTACHED_OBJECTS;
205 auto res = planning_scene_service_->async_send_request(request);
206 if (rclcpp::spin_until_future_complete(node_, res) != rclcpp::FutureReturnCode::SUCCESS)
208 RCLCPP_WARN(
LOGGER,
"Could not call planning scene service to get attached object geometries");
211 response = res.get();
213 for (
const moveit_msgs::msg::AttachedCollisionObject& attached_collision_object :
214 response->scene.robot_state.attached_collision_objects)
216 if (object_ids.empty() ||
217 std::find(object_ids.begin(), object_ids.end(), attached_collision_object.object.id) != object_ids.end())
219 result[attached_collision_object.object.id] = attached_collision_object;
227 auto request = std::make_shared<moveit_msgs::srv::ApplyPlanningScene::Request>();
228 moveit_msgs::srv::ApplyPlanningScene::Response::SharedPtr response;
231 auto res = apply_planning_scene_service_->async_send_request(request);
232 if (rclcpp::spin_until_future_complete(node_, res) != rclcpp::FutureReturnCode::SUCCESS)
234 RCLCPP_WARN(
LOGGER,
"Failed to call ApplyPlanningScene service");
236 response = res.get();
237 return response->success;
241 const std::vector<moveit_msgs::msg::ObjectColor>& object_colors)
const
249 if (
planning_scene.object_colors[i].id.empty() && i < collision_objects.size())
262 moveit_msgs::msg::CollisionObject object;
263 for (
const std::string& object_id : object_ids)
265 object.id = object_id;
266 object.operation =
object.REMOVE;
274 void waitForService(
const std::shared_ptr<rclcpp::ClientBase>& srv)
278 std::chrono::duration<double>
d(5.0);
279 srv->wait_for_service(std::chrono::duration_cast<std::chrono::nanoseconds>(
d));
280 if (!srv->service_is_ready())
282 RCLCPP_WARN_STREAM(
LOGGER,
"service '" << srv->get_service_name() <<
"' not advertised yet. Continue waiting...");
283 srv->wait_for_service();
287 rclcpp::Node::SharedPtr node_;
288 rclcpp::Client<moveit_msgs::srv::GetPlanningScene>::SharedPtr planning_scene_service_;
289 rclcpp::Client<moveit_msgs::srv::ApplyPlanningScene>::SharedPtr apply_planning_scene_service_;
290 rclcpp::Publisher<moveit_msgs::msg::PlanningScene>::SharedPtr planning_scene_diff_publisher_;
291 moveit::core::RobotModelConstPtr robot_model_;
310 double maxx,
double maxy,
double maxz,
312 std::vector<std::string>& types)
317 std::map<std::string, geometry_msgs::msg::Pose>
323 std::map<std::string, moveit_msgs::msg::CollisionObject>
329 std::map<std::string, moveit_msgs::msg::AttachedCollisionObject>
337 moveit_msgs::msg::PlanningScene ps;
338 ps.robot_state.is_diff =
true;
340 ps.world.collision_objects.reserve(1);
341 ps.world.collision_objects.push_back(collision_object);
346 const std_msgs::msg::ColorRGBA& object_color)
348 moveit_msgs::msg::PlanningScene ps;
349 ps.robot_state.is_diff =
true;
351 ps.world.collision_objects.reserve(1);
352 ps.world.collision_objects.push_back(collision_object);
353 moveit_msgs::msg::ObjectColor oc;
354 oc.id = collision_object.id;
355 oc.color = object_color;
356 ps.object_colors.push_back(oc);
361 const std::vector<moveit_msgs::msg::CollisionObject>& collision_objects,
362 const std::vector<moveit_msgs::msg::ObjectColor>& object_colors)
364 moveit_msgs::msg::PlanningScene ps;
365 ps.robot_state.is_diff =
true;
367 ps.world.collision_objects = collision_objects;
368 ps.object_colors = object_colors;
370 for (
size_t i = 0; i < ps.object_colors.size(); ++i)
372 if (ps.object_colors[i].id.empty() && i < collision_objects.size())
373 ps.object_colors[i].id = collision_objects[i].id;
382 const moveit_msgs::msg::AttachedCollisionObject& collision_object)
384 moveit_msgs::msg::PlanningScene ps;
385 ps.robot_state.is_diff =
true;
387 ps.robot_state.attached_collision_objects.reserve(1);
388 ps.robot_state.attached_collision_objects.push_back(collision_object);
393 const std::vector<moveit_msgs::msg::AttachedCollisionObject>& collision_objects)
395 moveit_msgs::msg::PlanningScene ps;
396 ps.robot_state.is_diff =
true;
398 ps.robot_state.attached_collision_objects = collision_objects;
408 const std::vector<moveit_msgs::msg::ObjectColor>& object_colors)
const
std::map< std::string, moveit_msgs::msg::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::msg::Pose > getObjectPoses(const std::vector< std::string > &object_ids)
std::map< std::string, moveit_msgs::msg::CollisionObject > getObjects(const std::vector< std::string > &object_ids)
bool applyPlanningScene(const moveit_msgs::msg::PlanningScene &planning_scene)
void removeCollisionObjects(const std::vector< std::string > &object_ids) const
void addCollisionObjects(const std::vector< moveit_msgs::msg::CollisionObject > &collision_objects, const std::vector< moveit_msgs::msg::ObjectColor > &object_colors) const
PlanningSceneInterfaceImpl(const std::string &ns="", bool wait=true)
bool applyAttachedCollisionObject(const moveit_msgs::msg::AttachedCollisionObject &attached_collision_object)
Apply attached collision object to the planning scene of the move_group node synchronously....
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,...
bool applyPlanningScene(const moveit_msgs::msg::PlanningScene &ps)
Update the planning_scene of the move_group node with the given ps synchronously. Other PlanningScene...
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 tha...
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....
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...
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 t...
PlanningSceneInterface(const std::string &ns="", bool wait=true)
void removeCollisionObjects(const std::vector< std::string > &object_ids) const
Remove collision objects from the world via /planning_scene.
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.
~PlanningSceneInterface()
bool applyCollisionObject(const moveit_msgs::msg::CollisionObject &collision_object)
Apply collision object to the planning scene of the move_group node synchronously....
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....
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....
const rclcpp::Logger LOGGER
Main namespace for MoveIt.
This namespace includes the base class for MoveIt planners.
This namespace includes the central class for representing planning contexts.