diff --git a/include/dynamic_graph_bridge/sot_loader_basic.hh b/include/dynamic_graph_bridge/sot_loader_basic.hh index b561d48a859513ab815807dbb8b07ce8e372e458..11cc15de8c32786ae17819809c254ae3dafc4fdd 100644 --- a/include/dynamic_graph_bridge/sot_loader_basic.hh +++ b/include/dynamic_graph_bridge/sot_loader_basic.hh @@ -73,6 +73,12 @@ protected: /// \brief Coefficient between parallel joints and the state vector. std::vector<double> 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_; @@ -83,7 +89,6 @@ protected: int nbOfJoints_; parallel_joints_to_state_vector_t::size_type nbOfParallelJoints_; - public: SotLoaderBasic(); ~SotLoaderBasic() {}; diff --git a/src/sot_loader_basic.cpp b/src/sot_loader_basic.cpp index 4193a9bd8781f0fd369b9bf6cd63b99a3c3ebabe..e30b940e4477357c2abd25f648f9b59f8db59ee4 100644 --- a/src/sot_loader_basic.cpp +++ b/src/sot_loader_basic.cpp @@ -35,24 +35,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) @@ -76,8 +58,15 @@ int SotLoaderBasic::initPublication() void SotLoaderBasic::initializeRosNode(int , char *[]) { ROS_INFO("Ready to start dynamic graph."); - boost::unique_lock<boost::mutex> 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); }