From 5532bde88ca93161847163161d95c8df87e77ea5 Mon Sep 17 00:00:00 2001
From: Rohan Budhiraja <budhiraja@laas.fr>
Date: Tue, 12 Apr 2016 20:32:57 +0200
Subject: [PATCH] fix ros package version + fix jrl_map ros_param

---
 package.xml         |  2 +-
 src/robot_model.cpp | 24 +-----------------------
 src/sot_loader.cpp  |  2 --
 3 files changed, 2 insertions(+), 26 deletions(-)

diff --git a/package.xml b/package.xml
index 6174c77..a7d9331 100644
--- a/package.xml
+++ b/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>dynamic_graph_bridge</name>
-  <version>2.0.0</version>
+  <version>3.0.0</version>
   <description>
 
      ROS bindings for dynamic graph.
diff --git a/src/robot_model.cpp b/src/robot_model.cpp
index e4afa19..b183bc3 100644
--- a/src/robot_model.cpp
+++ b/src/robot_model.cpp
@@ -77,7 +77,7 @@ void RosRobotModel::loadUrdf (const std::string& filename)
   
   XmlRpc::XmlRpcValue JointsNamesByRank_;
   JointsNamesByRank_.setSize(m_model.names.size());
-  std::vector<std::string>::const_iterator it = m_model.names.begin();
+  std::vector<std::string>::const_iterator it = m_model.names.begin()+1; //the first name is universe
   for (int i=0;it!=m_model.names.end();++it, ++i)  JointsNamesByRank_[i]= (*it);
   nh.setParam(jointsParameterName_, JointsNamesByRank_);
 }
@@ -123,29 +123,7 @@ void RosRobotModel::loadFromParameterServer()
     for (int i=0;it!=m_model.names.end();++it, ++i) JointsNamesByRank_[i]= (*it);
     nh.setParam(jointsParameterName_, JointsNamesByRank_);
 }
-  /*  
-namespace
-{
-
-vectorN convertVector(const ml::Vector& v)
-{
-    vectorN res (v.size());
-    for (unsigned i = 0; i < v.size(); ++i)
-        res[i] = v(i);
-    return res;
-}
-
-ml::Vector convertVector(const vectorN& v)
-{
-    ml::Vector res;
-    res.resize((unsigned int)v.size());
-    for (unsigned i = 0; i < v.size(); ++i)
-        res(i) = v[i];
-    return res;
-}
 
-} // end of anonymous namespace.
-*/
 Vector RosRobotModel::curConf() const
 {
 
diff --git a/src/sot_loader.cpp b/src/sot_loader.cpp
index 96cf677..3d0661d 100644
--- a/src/sot_loader.cpp
+++ b/src/sot_loader.cpp
@@ -221,7 +221,6 @@ SotLoader::readControl(map<string,dgs::ControlValues> &controlValues)
                 << std::endl;
       exit(-1);
     }
-
   // Publish the data.
   joint_state_.header.stamp = ros::Time::now();  
   for(int i=0;i<nbOfJoints_;i++)
@@ -235,7 +234,6 @@ SotLoader::readControl(map<string,dgs::ControlValues> &controlValues)
     }
 
   joint_pub_.publish(joint_state_);  
-
   
 }
 
-- 
GitLab