Skip to content
Snippets Groups Projects
Commit 5532bde8 authored by Rohan Budhiraja's avatar Rohan Budhiraja
Browse files

fix ros package version + fix jrl_map ros_param

parent 11f6b32c
No related branches found
No related tags found
No related merge requests found
<package>
<name>dynamic_graph_bridge</name>
<version>2.0.0</version>
<version>3.0.0</version>
<description>
ROS bindings for dynamic graph.
......
......@@ -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
{
......
......@@ -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_);
}
......
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