Skip to content

Commit

Permalink
Remove useless thread.
Browse files Browse the repository at this point in the history
  • Loading branch information
olivier-stasse committed Feb 6, 2019
1 parent df773fd commit b645e4c
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 20 deletions.
5 changes: 5 additions & 0 deletions include/dynamic_graph_bridge/sot_loader_basic.hh
Expand Up @@ -71,7 +71,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_;

Expand Down
28 changes: 8 additions & 20 deletions src/sot_loader_basic.cpp
Expand Up @@ -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)
Expand All @@ -78,9 +60,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);

}


Expand Down

0 comments on commit b645e4c

Please sign in to comment.