service_server.cpp
Go to the documentation of this file.
00001 /******************************************************************************
00002  * \file
00003  *
00004  * $Id: but_service_server.cpp 556 2012-04-11 16:10:40Z xlokaj03 $
00005  *
00006  * Copyright (C) Brno University of Technology
00007  *
00008  * This file is part of software developed by dcgm-robotics@FIT group.
00009  *
00010  * Author: Tomas Lokaj (xlokaj03@stud.fit.vutbr.cz)
00011  * Supervised by: Michal Spanel (spanel@fit.vutbr.cz)
00012  * Date: 18/02/2012
00013  * 
00014  * This file is free software: you can redistribute it and/or modify
00015  * it under the terms of the GNU Lesser General Public License as published by
00016  * the Free Software Foundation, either version 3 of the License, or
00017  * (at your option) any later version.
00018  * 
00019  * This file is distributed in the hope that it will be useful,
00020  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00021  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00022  * GNU Lesser General Public License for more details.
00023  * 
00024  * You should have received a copy of the GNU Lesser General Public License
00025  * along with this file.  If not, see <http://www.gnu.org/licenses/>.
00026  */
00027 
00028 #include <srs_ui_but/but_services/service_server.h>
00029 
00030 namespace srs_ui_but
00031 {
00032 
00033 // Point cloud data handler
00034 srs_ui_but::PointCloudTools * pcTools;
00035 
00036 bool getClosestPoint(GetClosestPoint::Request &req, GetClosestPoint::Response &res)
00037 {
00038   ROS_INFO("Getting closest point");
00039 
00040   res.closest_point_data = pcTools->getClosestPoint(req.link);
00041   res.topic = pcTools->getPointCloudTopic();
00042 
00043   if (!res.closest_point_data.status)
00044   {
00045     ROS_WARN("Cannot get closest point!");
00046     return false;
00047   }
00048 
00049   ROS_INFO("..... DONE");
00050   return true;
00051 }
00052 
00053 bool setPointCloudTopic(SetPointCloudTopic::Request &req, SetPointCloudTopic::Response &res)
00054 {
00055   ROS_INFO("Setting point cloud topic to: %s", req.topic.c_str());
00056 
00057   pcTools->setPointCloudTopic(req.topic);
00058 
00059   ROS_INFO("..... DONE");
00060   return true;
00061 }
00062 
00063 }
00064 
00065 /*
00066  * Main function
00067  */
00068 int main(int argc, char **argv)
00069 {
00070 
00071   // ROS initialization (the last argument is the name of the node)
00072   ros::init(argc, argv, "but_service_server");
00073 
00074   // NodeHandle is the main access point to communications with the ROS system
00075   ros::NodeHandle n;
00076 
00077   // Point Cloud data handler
00078   srs_ui_but::pcTools = new srs_ui_but::PointCloudTools();
00079 
00080   // Create and advertise this service over ROS
00081   ros::ServiceServer getClosestPointService = n.advertiseService(srs_ui_but::GetClosestPoint_SRV, srs_ui_but::getClosestPoint);
00082   ros::ServiceServer setPointCloudTopicService = n.advertiseService(srs_ui_but::SetPointCloudTopic_SRV, srs_ui_but::setPointCloudTopic);
00083 
00084   ROS_INFO("BUT Service Server ready!");
00085 
00086   // Enters a loop, calling message callbacks
00087   ros::spin();
00088 
00089   return 0;
00090 }


srs_ui_but
Author(s): Vit Stancl (stancl@fit.vutbr.cz), Michal Spanel (spanel@fit.vutbr.cz), Tomas Lokaj
autogenerated on Mon Oct 6 2014 08:49:30