From 8c45dc1c49b81256e5dba884c98c9e958bcdb368 Mon Sep 17 00:00:00 2001 From: William Emfinger Date: Mon, 9 Apr 2018 10:59:28 -0500 Subject: [PATCH] updated component base class destructor to contain log flushing in destructor. shifted ros::init around in main. --- src/rosmod_actor/src/rosmod_actor/component.cpp | 8 +++++++- src/rosmod_actor/src/rosmod_actor/main.cpp | 16 ++++++++-------- 2 files changed, 15 insertions(+), 9 deletions(-) diff --git a/src/rosmod_actor/src/rosmod_actor/component.cpp b/src/rosmod_actor/src/rosmod_actor/component.cpp index 9e2808b..87c5dee 100644 --- a/src/rosmod_actor/src/rosmod_actor/component.cpp +++ b/src/rosmod_actor/src/rosmod_actor/component.cpp @@ -26,8 +26,14 @@ Component::Component(Json::Value& _config) { // Destructor Component::~Component() { + std::cout << "~Component() for " << + config["Name"].asString() << + " - writing out logs!" << "\n"; comp_queue.disable(); - init_timer.stop(); + // make sure all user logs are written + logger->write(); + // make sure all trace logs are written + trace->write(); } // Component Operation Queue Handler diff --git a/src/rosmod_actor/src/rosmod_actor/main.cpp b/src/rosmod_actor/src/rosmod_actor/main.cpp index 536fa9d..5714af6 100644 --- a/src/rosmod_actor/src/rosmod_actor/main.cpp +++ b/src/rosmod_actor/src/rosmod_actor/main.cpp @@ -84,9 +84,17 @@ int main(int argc, char **argv) ROS_ERROR_STREAM("Unhandled exception caught trying to open / parse config file!"); } + nodeName = root["Name"].asString(); + ros::init(argc, argv, nodeName.c_str(), ros::init_options::NoSigintHandler); + signal(SIGINT, rosmod_actor_SigInt_handler); + ROS_INFO_STREAM( std::string("Root Node name: ") << root["Name"].asString() << std::endl); ROS_INFO_STREAM( std::string("Root Node priority: ") << root["Priority"].asInt() << std::endl); + // Create Node Handle + ros::NodeHandle n; + ROS_INFO_STREAM(nodeName << " thread id = " << boost::this_thread::get_id()); + int ret; pthread_t this_thread = pthread_self(); @@ -117,14 +125,6 @@ int main(int argc, char **argv) ROS_INFO_STREAM("SCHED_RR OK" << std::endl); // Print thread scheduling priority ROS_INFO_STREAM("Thread priority is " << params.sched_priority << std::endl); - - nodeName = root["Name"].asString(); - ros::init(argc, argv, nodeName.c_str(), ros::init_options::NoSigintHandler); - signal(SIGINT, rosmod_actor_SigInt_handler); - // Create Node Handle - ros::NodeHandle n; - - ROS_INFO_STREAM(nodeName << " thread id = " << boost::this_thread::get_id()); for (unsigned int i = 0; i < root["Component Instances"].size(); i++) { std::string libraryLocation = root["Component Instances"][i]["Definition"].asString();