51 using std::placeholders::_1;
52 using std::placeholders::_2;
53 using std::placeholders::_3;
55 service_ =
context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::ApplyPlanningScene>(
56 APPLY_PLANNING_SCENE_SERVICE_NAME,
57 [
this](
const std::shared_ptr<rmw_request_id_t>& request_header,
58 const std::shared_ptr<moveit_msgs::srv::ApplyPlanningScene::Request>& req,
59 const std::shared_ptr<moveit_msgs::srv::ApplyPlanningScene::Response>& res) {
60 return applyScene(request_header, req, res);
64bool ApplyPlanningSceneService::applyScene(
const std::shared_ptr<rmw_request_id_t>& ,
65 const std::shared_ptr<moveit_msgs::srv::ApplyPlanningScene::Request>& req,
66 const std::shared_ptr<moveit_msgs::srv::ApplyPlanningScene::Response>& res)
68 if (!
context_->planning_scene_monitor_)
70 RCLCPP_ERROR(
moveit::getLogger(
"moveit.ros.move_group.apply_planning_scene_service"),
71 "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_
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.