From b645e4ca683313866fb4b9fbb61d5aad0239d912 Mon Sep 17 00:00:00 2001 From: Olivier Stasse Date: Wed, 6 Feb 2019 20:06:13 +0100 Subject: [PATCH] Remove useless thread. --- .../dynamic_graph_bridge/sot_loader_basic.hh | 5 ++++ src/sot_loader_basic.cpp | 28 ++++++------------- 2 files changed, 13 insertions(+), 20 deletions(-) diff --git a/include/dynamic_graph_bridge/sot_loader_basic.hh b/include/dynamic_graph_bridge/sot_loader_basic.hh index 1631975..85de433 100644 --- a/include/dynamic_graph_bridge/sot_loader_basic.hh +++ b/include/dynamic_graph_bridge/sot_loader_basic.hh @@ -71,7 +71,12 @@ protected: /// \brief Coefficient between parallel joints and the state vector. std::vector coefficient_parallel_joints_; + /// Advertises start_dynamic_graph services + ros::ServiceServer service_start_; + /// Advertises stop_dynamic_graph services + ros::ServiceServer service_stop_; + // Joint state publication. ros::Publisher joint_pub_; diff --git a/src/sot_loader_basic.cpp b/src/sot_loader_basic.cpp index 9898308..9fd1a85 100644 --- a/src/sot_loader_basic.cpp +++ b/src/sot_loader_basic.cpp @@ -37,24 +37,6 @@ using namespace std; using namespace dynamicgraph::sot; namespace po = boost::program_options; -void createRosSpin(SotLoaderBasic *aSotLoaderBasic) -{ - ROS_INFO("createRosSpin started\n"); - ros::NodeHandle n; - - ros::ServiceServer service = n.advertiseService("start_dynamic_graph", - &SotLoaderBasic::start_dg, - aSotLoaderBasic); - - ros::ServiceServer service2 = n.advertiseService("stop_dynamic_graph", - &SotLoaderBasic::stop_dg, - aSotLoaderBasic); - - - ros::waitForShutdown(); -} - - SotLoaderBasic::SotLoaderBasic(): dynamic_graph_stopped_(true), sotRobotControllerLibrary_(0) @@ -78,9 +60,15 @@ int SotLoaderBasic::initPublication() void SotLoaderBasic::initializeRosNode(int , char *[]) { ROS_INFO("Ready to start dynamic graph."); - boost::unique_lock lock(mut); - boost::thread thr2(createRosSpin,this); + ros::NodeHandle n; + service_start_ = n.advertiseService("start_dynamic_graph", + &SotLoaderBasic::start_dg, + this); + service_stop_ = n.advertiseService("stop_dynamic_graph", + &SotLoaderBasic::stop_dg, + this); + }