00001 /* 00002 * GenericKiller.cpp 00003 * 00004 * Created on: Aug 13, 2012 00005 * Author: tnestmeyer 00006 */ 00007 00008 #include "GenericKiller.hpp" 00009 00010 #include <telekyb_base/TeleKyb.hpp> 00011 00012 namespace TELEKYB_NAMESPACE { 00013 00014 GenericKiller::GenericKiller() 00015 { 00016 msgTimer.reset(); 00017 sub = n.subscribe<ShapeShifter>(options.tTopicName->getValue(), 10, &GenericKiller::callback, this); 00018 } 00019 00020 GenericKiller::~GenericKiller() { 00021 00022 } 00023 00024 // run 00025 void GenericKiller::run() { 00026 00027 // 1/4 of the message timeout 00028 Time sleepTime(options.tTimeOut->getValue()/4); 00029 00030 while (ros::ok()) { 00031 00032 if (msgTimer.getElapsed().toDSec() > options.tTimeOut->getValue()) { 00033 ROS_WARN("No Message received within timeout. Killing Process %s", options.tProcessName->getValue().c_str()); 00034 // kill the process 00035 std::string killCall = std::string("killall ") + options.tProcessName->getValue(); 00036 if (system(killCall.c_str()) < 0) { 00037 ROS_ERROR("An error occurred while trying to execute \"%s\"", killCall.c_str()); 00038 } 00039 00040 // break 00041 break; 00042 } 00043 00044 sleepTime.sleep(); 00045 } 00046 } 00047 00048 00049 void GenericKiller::callback(const boost::shared_ptr<ShapeShifter const>& msg) 00050 { 00051 // Received Message // reset msgTimer 00052 msgTimer.reset(); 00053 } 00054 00055 00056 00057 } /* namespace telekyb */ 00058 00059 00060 int main(int argc, char **argv) { 00061 telekyb::TeleKyb::init(argc,argv, "generic_killer", ros::init_options::AnonymousName); 00062 00063 telekyb::GenericKiller *g = new telekyb::GenericKiller(); 00064 00065 if (ros::ok()) { 00066 g->run(); 00067 } 00068 00069 delete g; 00070 00071 telekyb::TeleKyb::shutdown(); 00072 return 0; 00073 } 00074