ros_service_ui.cpp
Go to the documentation of this file.
00001 /* This file is part of RGBDSLAM.
00002  * 
00003  * RGBDSLAM is free software: you can redistribute it and/or modify
00004  * it under the terms of the GNU General Public License as published by
00005  * the Free Software Foundation, either version 3 of the License, or
00006  * (at your option) any later version.
00007  * 
00008  * RGBDSLAM is distributed in the hope that it will be useful,
00009  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00010  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00011  * GNU General Public License for more details.
00012  * 
00013  * You should have received a copy of the GNU General Public License
00014  * along with RGBDSLAM.  If not, see <http://www.gnu.org/licenses/>.
00015  */
00016 #include <QtGui>
00017 #include <QPixmap>
00018 #include <QFont>
00019 #include <QIcon>
00020 #include <QKeySequence>
00021 #include "ros_service_ui.h"
00022 #include <limits>
00023 #include "ros/ros.h"
00024 
00025 RosUi::RosUi(const char* service_namespace) : filename("quicksave.pcd"), record_on(false)
00026 {
00027     ros::NodeHandle n(service_namespace);
00028     server   = n.advertiseService("ros_ui",   &RosUi::services,   this);
00029     server_b = n.advertiseService("ros_ui_b", &RosUi::services_b, this);
00030     server_f = n.advertiseService("ros_ui_f", &RosUi::services_f, this);
00031     server_s = n.advertiseService("ros_ui_s", &RosUi::services_s, this);
00032     this->pause_on = ParameterServer::instance()->get<bool>("start_paused");
00033 }
00034 
00035 
00036 void RosUi::sendFinished() {
00037     ROS_INFO("Finished Sending");
00038 }
00039 
00040 
00041 void RosUi::pause(bool _pause_on) {
00042     if(this->pause_on == _pause_on){
00043         return;
00044     }
00045     this->pause_on = _pause_on;
00046     Q_EMIT togglePause();
00047     if(!_pause_on) {
00048         ROS_INFO("Processing.");
00049     } else {
00050         ROS_INFO("Stopped processing.");
00051     }
00052 }
00053 
00054 
00055 bool RosUi::services(rgbdslam::rgbdslam_ros_ui::Request  &req,
00056                      rgbdslam::rgbdslam_ros_ui::Response &res )
00057 {
00058   ROS_INFO_STREAM("Got Service Request. Command: " << req.command);
00059   if     (req.command == "reset"          ){ Q_EMIT reset(); }
00060   else if(req.command == "quick_save"     ){ Q_EMIT saveAllClouds(filename); }
00061   else if(req.command == "save_g2o_graph" ){ Q_EMIT saveG2OGraph("graph.g2o"); }
00062   else if(req.command == "save_trajectory"){ Q_EMIT saveTrajectory("trajectory"); }
00063   else if(req.command == "send_all"       ){ Q_EMIT sendAllClouds();}
00064   else if(req.command == "frame"          ){ Q_EMIT getOneFrame(); }
00065   else if(req.command == "delete_frame"   ){ Q_EMIT deleteLastFrame(); }
00066   else if(req.command == "optimize"       ){ Q_EMIT optimizeGraph(); }
00067   else if(req.command == "reload_config"  ){ ParameterServer::instance()->getValues();}
00068     else{
00069       ROS_ERROR("Invalid service call command: %s", req.command.c_str());
00070       ROS_ERROR("RGBDSLAM's services have changed in Feb '13, please revise your service calls");
00071       ROS_INFO("Valid commands are: {\n - reset\n - frame\n - quick_save\n -  send_all\n -  delete_frame\n -  optimize\n -  reload_config\n - save_trajectory\n}");
00072         return false;
00073     }
00074     return true;
00075 }
00076 
00077 bool RosUi::services_b(rgbdslam::rgbdslam_ros_ui_b::Request  &req,
00078                        rgbdslam::rgbdslam_ros_ui_b::Response &res )
00079 {
00080   ROS_INFO_STREAM("Got Service Request. Command: " << req.command << ". Value: " << ( req.value ? "True" : "False"));
00081   if     (req.command == "pause"            ){ pause(req.value); }
00082   else if(req.command == "mapping"          ){ Q_EMIT toggleMapping(req.value); }
00083   else if(req.command == "store_pointclouds"){ toggleCloudStorage(req.value); }
00084     else{
00085       ROS_ERROR("Invalid service call commands: %s", req.command.c_str());
00086         ROS_ERROR("Valid commands are: {pause, record, mapping, store_pointclouds}");
00087         return false;
00088     }
00089   return true;
00090 }
00091 
00092 bool RosUi::services_s(rgbdslam::rgbdslam_ros_ui_s::Request  &req,
00093                        rgbdslam::rgbdslam_ros_ui_s::Response &res )
00094 {
00095     ROS_INFO_STREAM("Got Service Request. Command: " << req.command << ". Value: " << req.value );
00096     QString filename = QString::fromStdString(req.value);
00097     if     (req.command == "save_octomap"   ){ Q_EMIT saveOctomapSig(filename); }
00098     else if(req.command == "save_cloud"     ){ Q_EMIT saveAllClouds(filename); }
00099     else if(req.command == "save_g2o_graph" ){ Q_EMIT saveG2OGraph(filename); }
00100     else if(req.command == "save_trajectory"){ Q_EMIT saveTrajectory(filename); }
00101     else if(req.command == "save_features"  ){ Q_EMIT saveAllFeatures(filename); }
00102     else if(req.command == "save_individual"){ Q_EMIT saveIndividualClouds(filename); }
00103     else{
00104         ROS_ERROR("Invalid service call command: %s", req.command.c_str());
00105         ROS_INFO("Valid commands are: {\n - save_octomap\n -  save_cloud\n -  save_g2o_graph\n -  save_trajectory\n -  save_features\n -  save_individual\n}");
00106         return false;
00107     }
00108     return true;
00109 }
00110 bool RosUi::services_f(rgbdslam::rgbdslam_ros_ui_f::Request  &req,
00111                        rgbdslam::rgbdslam_ros_ui_f::Response &res )
00112 {
00113     ROS_INFO_STREAM("Got Service Request. Command: " << req.command << ". Value: " << req.value );
00114     if(req.command == "set_max"){
00115         Q_EMIT setMaxDepth(req.value/100.0);
00116         return true;
00117     }
00118     else{
00119         ROS_ERROR("Command is set_max");
00120         return false;
00121     }
00122 }
00123 
00124 void RosUi::toggleCloudStorage(bool storage) {
00125   ParameterServer::instance()->set("store_pointclouds", storage);
00126   ROS_INFO_COND(storage, "Point clouds will be stored");
00127   ROS_INFO_COND(!storage, "Point clouds will not be stored");
00128 }


rgbdslam_v2
Author(s): Felix Endres, Juergen Hess, Nikolas Engelhard
autogenerated on Thu Jun 6 2019 21:49:45