Skip to content
Snippets Groups Projects
Commit b645e4ca authored by Olivier Stasse's avatar Olivier Stasse
Browse files

Remove useless thread.

parent df773fd8
No related branches found
Tags v2.5
No related merge requests found
Pipeline #10184 failed
......@@ -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_;
......
......@@ -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<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);
}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment