51 if (!
context_->planning_scene_monitor_)
53 ROS_ERROR(
"Cannot clear octomap since planning_scene_monitor_ does not exist.");
58 context_->planning_scene_monitor_->clearOctomap();
virtual void initialize()
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
MoveGroupContextPtr context_
bool clearOctomap(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
ros::ServiceServer service_
ros::NodeHandle root_node_handle_
static const std::string CLEAR_OCTOMAP_SERVICE_NAME
CLASS_LOADER_REGISTER_CLASS(Dog, Base)