Newer
Older
//
//
#ifndef __pinocchio_parser_srdf_hxx__
#define __pinocchio_parser_srdf_hxx__
#include "pinocchio/parsers/srdf.hpp"
#include "pinocchio/multibody/model.hpp"
#include "pinocchio/multibody/geometry.hpp"
#include <iostream>
// Read XML file with boost
#include <boost/property_tree/xml_parser.hpp>
#include <boost/property_tree/ptree.hpp>
#include <fstream>
#include <sstream>
#include <boost/foreach.hpp>
{
namespace srdf
{
#ifdef PINOCCHIO_WITH_HPP_FCL
namespace details
{
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
void removeCollisionPairs(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
GeometryModel & geomModel,
std::istream & stream,
const bool verbose = false)
{
// Read xml stream
using boost::property_tree::ptree;
ptree pt;
read_xml(stream, pt);
// Iterate over collision pairs
BOOST_FOREACH(const ptree::value_type & v, pt.get_child("robot"))
{
if (v.first == "disable_collisions")
{
const std::string link1 = v.second.get<std::string>("<xmlattr>.link1");
const std::string link2 = v.second.get<std::string>("<xmlattr>.link2");
// Check first if the two bodies exist in model
if (!model.existBodyName(link1) || !model.existBodyName(link2))
{
if (verbose)
std::cout << "It seems that " << link1 << " or " << link2 << " do not exist in model. Skip." << std::endl;
continue;
}
const typename Model::FrameIndex frame_id1 = model.getBodyId(link1);
const typename Model::FrameIndex frame_id2 = model.getBodyId(link2);
// Malformed SRDF
if (frame_id1 == frame_id2)
{
if (verbose)
std::cout << "Cannot disable collision between " << link1 << " and " << link2 << std::endl;
continue;
}
typedef GeometryModel::CollisionPairVector CollisionPairVector;
bool didRemove = false;
for(CollisionPairVector::iterator _colPair = geomModel.collisionPairs.begin();
_colPair != geomModel.collisionPairs.end(); ) {
const CollisionPair& colPair (*_colPair);
bool remove =
(
(geomModel.geometryObjects[colPair.first ].parentFrame == frame_id1)
&& (geomModel.geometryObjects[colPair.second].parentFrame == frame_id2)
) || (
(geomModel.geometryObjects[colPair.second].parentFrame == frame_id1)
&& (geomModel.geometryObjects[colPair.first ].parentFrame == frame_id2)
);
if (remove) {
_colPair = geomModel.collisionPairs.erase(_colPair);
didRemove = true;
} else {
++_colPair;
}
}
if(didRemove && verbose)
std::cout << "Remove collision pair (" << link1 << "," << link2 << ")" << std::endl;
}
} // BOOST_FOREACH
}
} // namespace details
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
void removeCollisionPairs(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
GeometryModel & geomModel,
const std::string & filename,
const bool verbose) throw (std::invalid_argument)
{
// Check extension
const std::string extension = filename.substr(filename.find_last_of('.')+1);
if (extension != "srdf")
{
const std::string exception_message (filename + " does not have the right extension.");
throw std::invalid_argument(exception_message);
}
// Open file
std::ifstream srdf_stream(filename.c_str());
if (! srdf_stream.is_open())
{
const std::string exception_message (filename + " does not seem to be a valid file.");
throw std::invalid_argument(exception_message);
}
details::removeCollisionPairs(model, geomModel, srdf_stream, verbose);
}
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
void removeCollisionPairsFromXML(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
GeometryModel & geomModel,
const std::string & xmlString,
const bool verbose)
{
std::istringstream srdf_stream(xmlString);
details::removeCollisionPairs(model, geomModel, srdf_stream, verbose);
}
#endif // ifdef PINOCCHIO_WITH_HPP_FCL
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
bool loadRotorParameters(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const std::string & filename,
const bool verbose) throw (std::invalid_argument)
typedef ModelTpl<Scalar,Options,JointCollectionTpl> Model;
typedef typename Model::JointModel JointModel;
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
// Check extension
const std::string extension = filename.substr(filename.find_last_of('.')+1);
if (extension != "srdf")
{
const std::string exception_message (filename + " does not have the right extension.");
throw std::invalid_argument(exception_message);
}
// Open file
std::ifstream srdf_stream(filename.c_str());
if (! srdf_stream.is_open())
{
const std::string exception_message (filename + " does not seem to be a valid file.");
throw std::invalid_argument(exception_message);
}
// Read xml stream
using boost::property_tree::ptree;
ptree pt;
read_xml(srdf_stream, pt);
// Iterate over all tags directly children of robot
BOOST_FOREACH(const ptree::value_type & v, pt.get_child("robot"))
{
// if we encounter a tag rotor_params
if (v.first == "rotor_params")
{
// Iterate over all the joint tags
BOOST_FOREACH(const ptree::value_type & joint, v.second)
{
if (joint.first == "joint")
{
std::string joint_name = joint.second.get<std::string>("<xmlattr>.name");
const Scalar rotor_mass = (Scalar)joint.second.get<double>("<xmlattr>.mass");
const Scalar rotor_gr = (Scalar)joint.second.get<double>("<xmlattr>.gear_ratio");
if (verbose)
{
std::cout << "(" << joint_name << " , " <<
rotor_mass << " , " << rotor_gr << ")" << std::endl;
}
// Search in model the joint and its config id
typename Model::JointIndex joint_id = model.getJointId(joint_name);
if (joint_id != model.joints.size()) // != model.njoints
{
const JointModel & joint = model.joints[joint_id];
assert(joint.nv()==1);
model.rotorInertia(joint.idx_v()) = rotor_mass;
model.rotorGearRatio(joint.idx_v()) = rotor_gr; // joint with 1 dof
}
else
{
if (verbose) std::cout << "The Joint " << joint_name << " was not found in model" << std::endl;
}
}
}
return true;
}
}
assert(false && "no rotor params found in the srdf file");
return false; // warning : uninitialized vector is returned
}
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
typename ModelTpl<Scalar,Options,JointCollectionTpl>::ConfigVectorType
getNeutralConfiguration(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const std::string & filename,
const bool verbose) throw (std::invalid_argument)
{
typedef ModelTpl<Scalar,Options,JointCollectionTpl> Model;
typedef typename Model::JointModel JointModel;
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
// Check extension
const std::string extension = filename.substr(filename.find_last_of('.')+1);
if (extension != "srdf")
{
const std::string exception_message (filename + " does not have the right extension.");
throw std::invalid_argument(exception_message);
}
// Open file
std::ifstream srdf_stream(filename.c_str());
if (! srdf_stream.is_open())
{
const std::string exception_message (filename + " does not seem to be a valid file.");
throw std::invalid_argument(exception_message);
}
// Read xml stream
using boost::property_tree::ptree;
ptree pt;
read_xml(srdf_stream, pt);
// Iterate over all tags directly children of robot
BOOST_FOREACH(const ptree::value_type & v, pt.get_child("robot"))
{
// if we encounter a tag group_state
if (v.first == "group_state")
{
const std::string name = v.second.get<std::string>("<xmlattr>.name");
// Ensure that it is the half_sitting tag
if( name == "half_sitting")
{
// Iterate over all the joint tags
BOOST_FOREACH(const ptree::value_type & joint_tag, v.second)
{
if (joint_tag.first == "joint")
{
std::string joint_name = joint_tag.second.get<std::string>("<xmlattr>.name");
typename Model::JointIndex joint_id = model.getJointId(joint_name);
// Search in model the joint and its config id
if (joint_id != model.joints.size()) // != model.njoints
{
const JointModel & joint = model.joints[joint_id];
typename Model::ConfigVectorType joint_config(joint.nq());
const std::string joint_val = joint_tag.second.get<std::string>("<xmlattr>.value");
std::istringstream config_string(joint_val);
std::vector<double> config_vec((std::istream_iterator<double>(config_string)), std::istream_iterator<double>());
joint_config = Eigen::Map<typename Model::ConfigVectorType>(config_vec.data(), config_vec.size());
model.neutralConfiguration.segment(joint.idx_q(),joint.nq()) = joint_config;
if (verbose)
{
std::cout << "(" << joint_name << " , " << joint_config.transpose() << ")" << std::endl;
}
}
else
{
if (verbose) std::cout << "The Joint " << joint_name << " was not found in model" << std::endl;
}
}
}
return model.neutralConfiguration;
}
}
} // BOOST_FOREACH
assert(false && "no half_sitting configuration found in the srdf file"); // Should we throw something here ?
return ModelTpl<Scalar,Options,JointCollectionTpl>::ConfigVectorType::Constant(model.nq,(Scalar)NAN); // warning : uninitialized vector is returned
}
}
} // namespace pinocchio
#endif // ifndef __pinocchio_parser_srdf_hxx__