52 moveit_msgs::GetPlanningScene::Response& res)
54 if (req.components.components & moveit_msgs::PlanningSceneComponents::TRANSFORMS)
55 context_->planning_scene_monitor_->updateFrameTransforms();
57 ps->getPlanningSceneMsg(res.scene, req.components);
ros::ServiceServer get_scene_service_
static const std::string GET_PLANNING_SCENE_SERVICE_NAME
bool getPlanningSceneService(moveit_msgs::GetPlanningScene::Request &req, moveit_msgs::GetPlanningScene::Response &res)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
MoveGroupContextPtr context_
ros::NodeHandle root_node_handle_
MoveGroupGetPlanningSceneService()
virtual void initialize()
CLASS_LOADER_REGISTER_CLASS(Dog, Base)