43 static const rclcpp::Logger
LOGGER =
44 rclcpp::get_logger(
"moveit_move_group_default_capabilities.apply_planning_scene_service_capability");
52 using std::placeholders::_1;
53 using std::placeholders::_2;
54 using std::placeholders::_3;
56 service_ =
context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::ApplyPlanningScene>(
57 APPLY_PLANNING_SCENE_SERVICE_NAME,
58 [
this](
const std::shared_ptr<rmw_request_id_t>& request_header,
59 const std::shared_ptr<moveit_msgs::srv::ApplyPlanningScene::Request>& req,
60 const std::shared_ptr<moveit_msgs::srv::ApplyPlanningScene::Response>& res) {
61 return applyScene(request_header, req, res);
65 bool ApplyPlanningSceneService::applyScene(
const std::shared_ptr<rmw_request_id_t>& ,
66 const std::shared_ptr<moveit_msgs::srv::ApplyPlanningScene::Request>& req,
67 const std::shared_ptr<moveit_msgs::srv::ApplyPlanningScene::Response>& res)
69 if (!
context_->planning_scene_monitor_)
71 RCLCPP_ERROR(LOGGER,
"Cannot apply PlanningScene as no scene is monitored.");
74 context_->planning_scene_monitor_->updateFrameTransforms();
75 res->success =
context_->planning_scene_monitor_->newPlanningSceneMessage(req->scene);
80 #include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
ApplyPlanningSceneService()
void initialize() override
MoveGroupContextPtr context_
const rclcpp::Logger LOGGER