@@ -37,24 +37,6 @@ using namespace std;
3737using  namespace  dynamicgraph ::sot;  
3838namespace  po  =  boost::program_options;
3939
40- void  createRosSpin (SotLoaderBasic *aSotLoaderBasic)
41- {
42-   ROS_INFO (" createRosSpin started\n " 
43-   ros::NodeHandle n;
44- 
45-   ros::ServiceServer service = n.advertiseService (" start_dynamic_graph" 
46-                                                   &SotLoaderBasic::start_dg,
47-                                                   aSotLoaderBasic);
48- 
49-   ros::ServiceServer service2 = n.advertiseService (" stop_dynamic_graph" 
50-                                                   &SotLoaderBasic::stop_dg,
51-                                                   aSotLoaderBasic);
52- 
53- 
54-   ros::waitForShutdown ();
55- }
56- 
57- 
5840SotLoaderBasic::SotLoaderBasic ():
5941  dynamic_graph_stopped_(true ),
6042  sotRobotControllerLibrary_(0 )
@@ -78,9 +60,15 @@ int SotLoaderBasic::initPublication()
7860void  SotLoaderBasic::initializeRosNode (int  , char  *[])
7961{
8062  ROS_INFO (" Ready to start dynamic graph." 
81-   boost::unique_lock<boost::mutex> lock (mut);
82-   boost::thread thr2 (createRosSpin,this );
63+   ros::NodeHandle n;
64+   service_start_ = n.advertiseService (" start_dynamic_graph" 
65+                                      &SotLoaderBasic::start_dg,
66+                                      this );
8367
68+   service_stop_  = n.advertiseService (" stop_dynamic_graph" 
69+                                      &SotLoaderBasic::stop_dg,
70+                                      this );
71+   
8472}   
8573
8674
0 commit comments