Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021 #include <actionlib/server/simple_action_server.h>
00022 #include <tug_ist_diagnosis_msgs/DiagnosisRepairAction.h>
00023 #include <string>
00024 #include <stdlib.h>
00025 int i;
00026 using namespace std;
00027
00028 typedef actionlib::SimpleActionServer<tug_ist_diagnosis_msgs::DiagnosisRepairAction> switchServer;
00029
00030
00031 void startnode(const tug_ist_diagnosis_msgs::DiagnosisRepairGoalConstPtr& goal, switchServer* as)
00032 {
00033 i++;
00034 tug_ist_diagnosis_msgs::DiagnosisRepairResult result_;
00035 string command("roslaunch tug_ist_diagnosis_launch " + goal->parameter[0] + ".launch &");
00036 ROS_INFO("START NODE Server Started. for %s",goal->parameter[0].c_str());
00037 int k = system(command.c_str());
00038 sleep(3);
00039 result_.result = i;
00040 as->setSucceeded(result_);
00041 ROS_INFO("START NODE Server Finished.");
00042
00043 }
00044
00045
00046 void stopnode(const tug_ist_diagnosis_msgs::DiagnosisRepairGoalConstPtr& goal, switchServer* as)
00047 {
00048 tug_ist_diagnosis_msgs::DiagnosisRepairResult result_;
00049 ROS_INFO("STOP NODE Server Started.");
00050 string command("rosnode kill /" + goal->parameter[0]);
00051 int k=system(command.c_str());
00052 sleep(3);
00053 result_.result = k;
00054 as->setSucceeded(result_);
00055 ROS_INFO("STOP NODE Server Finished.");
00056 }
00057
00058
00059
00060 int main( int argc, char **argv)
00061 {
00062 ros::init(argc, argv, "node_action_server_node");
00063 ros::NodeHandle n;
00064
00065 switchServer pserver(n, "start_node", boost::bind(&startnode, _1, &pserver), false);
00066 switchServer sserver(n, "stop_node", boost::bind(&stopnode, _1, &sserver), false);
00067
00068 pserver.start();
00069 sserver.start();
00070
00071 ROS_INFO("start_node and stop_node Servers are now up.....");
00072 ros::spin();
00073
00074 }