24 #include <boost/algorithm/string.hpp>
25 #include <boost/lexical_cast.hpp>
67 const std::string name,
68 bool calibrate_x,
bool calibrate_y,
bool calibrate_z,
69 bool calibrate_roll,
bool calibrate_pitch,
bool calibrate_yaw)
105 const std::string name,
106 double x,
double y,
double z,
107 double roll,
double pitch,
double yaw)
111 KDL::Rotation
r = KDL::Rotation::RPY(roll, pitch, yaw);
153 bool has_offset =
false;
192 std::ifstream
f(filename.c_str());
193 while (std::getline(
f, line))
195 std::istringstream str(line.c_str());
198 if (str >>
param >> value)
202 std::cout <<
"Loading '" <<
param <<
"' with value " << value << std::endl;
212 std::stringstream ss;
222 const double precision = 8;
224 TiXmlDocument xml_doc;
225 xml_doc.Parse(
urdf.c_str());
227 TiXmlElement *robot_xml = xml_doc.FirstChildElement(
"robot");
236 for (TiXmlElement* joint_xml = robot_xml->FirstChildElement(
"joint"); joint_xml; joint_xml = joint_xml->NextSiblingElement(
"joint"))
238 const char *
name = joint_xml->Attribute(
"name");
241 double offset =
get(std::string(
name));
244 TiXmlElement *calibration_xml = joint_xml->FirstChildElement(
"calibration");
249 const char * rising_position_str = calibration_xml->Attribute(
"rising");
250 if (rising_position_str != NULL)
254 offset += double(boost::lexical_cast<double>(rising_position_str));
255 calibration_xml->SetDoubleAttribute(
"rising", offset);
257 catch (boost::bad_lexical_cast &e)
263 const char * falling_position_str = calibration_xml->Attribute(
"falling");
264 if (falling_position_str != NULL)
268 offset += double(boost::lexical_cast<double>(falling_position_str));
269 calibration_xml->SetDoubleAttribute(
"falling", offset);
271 catch (boost::bad_lexical_cast &e)
280 calibration_xml =
new TiXmlElement(
"calibration");
281 calibration_xml->SetDoubleAttribute(
"rising", offset);
282 TiXmlNode * calibration = calibration_xml->Clone();
283 joint_xml->InsertEndChild(*calibration);
287 KDL::Frame frame_offset;
291 std::vector<double> xyz(3, 0.0);
292 std::vector<double> rpy(3, 0.0);
295 std::stringstream xyz_ss, rpy_ss;
297 TiXmlElement *origin_xml = joint_xml->FirstChildElement(
"origin");
301 const char * xyz_str = origin_xml->Attribute(
"xyz");
302 const char * rpy_str = origin_xml->Attribute(
"rpy");
305 std::vector<std::string> xyz_pieces;
306 boost::split(xyz_pieces, xyz_str, boost::is_any_of(
" "));
309 std::vector<std::string> rpy_pieces;
310 boost::split(rpy_pieces, rpy_str, boost::is_any_of(
" "));
312 KDL::Frame origin(KDL::Rotation::Identity(), KDL::Vector::Zero());
313 if (xyz_pieces.size() == 3)
315 origin.p = KDL::Vector(boost::lexical_cast<double>(xyz_pieces[0]), boost::lexical_cast<double>(xyz_pieces[1]), boost::lexical_cast<double>(xyz_pieces[2]));
318 if (rpy_pieces.size() == 3)
320 origin.M = KDL::Rotation::RPY(boost::lexical_cast<double>(rpy_pieces[0]), boost::lexical_cast<double>(rpy_pieces[1]), boost::lexical_cast<double>(rpy_pieces[2]));
324 origin = origin * frame_offset;
326 xyz[0] = origin.p.x();
327 xyz[1] = origin.p.y();
328 xyz[2] = origin.p.z();
331 origin.M.GetRPY(rpy[0], rpy[1], rpy[2]);
334 for (
int i = 0; i < 3; ++i)
338 xyz_ss << std::fixed << std::setprecision(precision) << xyz[i];
342 for (
int i = 0; i < 3; ++i)
346 rpy_ss << std::fixed << std::setprecision(precision) << rpy[i];
350 origin_xml->SetAttribute(
"xyz", xyz_ss.str());
351 origin_xml->SetAttribute(
"rpy", rpy_ss.str());
355 xyz[0] = frame_offset.p.x();
356 xyz[1] = frame_offset.p.y();
357 xyz[2] = frame_offset.p.z();
360 frame_offset.M.GetRPY(rpy[0], rpy[1], rpy[2]);
363 origin_xml =
new TiXmlElement(
"origin");
366 for (
int i = 0; i < 3; ++i)
370 xyz_ss << std::fixed << std::setprecision(precision) << xyz[i];
372 origin_xml->SetAttribute(
"xyz", xyz_ss.str());
375 for (
int i = 0; i < 3; ++i)
379 rpy_ss << std::fixed << std::setprecision(precision) << rpy[i];
381 origin_xml->SetAttribute(
"rpy", rpy_ss.str());
383 TiXmlNode * origin = origin_xml->Clone();
384 joint_xml->InsertEndChild(*origin);
390 TiXmlPrinter printer;
391 printer.SetIndent(
" ");
392 xml_doc.Accept(&printer);
393 std::string new_urdf = printer.CStr();