51 moveit_msgs::ApplyPlanningScene::Response& res)
53 if (!
context_->planning_scene_monitor_)
55 ROS_ERROR(
"Cannot apply PlanningScene as no scene is monitored.");
58 context_->planning_scene_monitor_->updateFrameTransforms();
59 res.success =
context_->planning_scene_monitor_->newPlanningSceneMessage(req.scene);
virtual void initialize()
bool applyScene(moveit_msgs::ApplyPlanningScene::Request &req, moveit_msgs::ApplyPlanningScene::Response &res)
ApplyPlanningSceneService()
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
static const std::string APPLY_PLANNING_SCENE_SERVICE_NAME
MoveGroupContextPtr context_
ros::ServiceServer service_
ros::NodeHandle root_node_handle_
CLASS_LOADER_REGISTER_CLASS(Dog, Base)