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)
115 set(std::string(name).append(
"_x"), x);
116 set(std::string(name).append(
"_y"), y);
117 set(std::string(name).append(
"_z"), z);
118 set(std::string(name).append(
"_a"), a);
119 set(std::string(name).append(
"_b"), b);
120 set(std::string(name).append(
"_c"), c);
153 bool has_offset =
false;
166 offset.
p.
x(
get(std::string(name).
append(
"_x")));
167 offset.
p.
y(
get(std::string(name).
append(
"_y")));
168 offset.
p.
z(
get(std::string(name).
append(
"_z")));
171 get(std::string(name).
append(
"_a")),
172 get(std::string(name).
append(
"_b")),
173 get(std::string(name).
append(
"_c")));
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)
201 param.erase(param.size() - 1);
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");
248 const char * rising_position_str = calibration_xml->Attribute(
"rising");
249 if (rising_position_str != NULL)
253 offset += double(boost::lexical_cast<double>(rising_position_str));
254 calibration_xml->SetDoubleAttribute(
"rising", offset);
256 catch (boost::bad_lexical_cast &e)
269 calibration_xml =
new TiXmlElement(
"calibration");
270 calibration_xml->SetDoubleAttribute(
"rising", offset);
271 TiXmlNode * calibration = calibration_xml->Clone();
272 joint_xml->InsertEndChild(*calibration);
277 bool has_update =
getFrame(name, frame_offset);
280 std::vector<double> xyz(3, 0.0);
281 std::vector<double> rpy(3, 0.0);
284 std::stringstream xyz_ss, rpy_ss;
286 TiXmlElement *origin_xml = joint_xml->FirstChildElement(
"origin");
290 const char * xyz_str = origin_xml->Attribute(
"xyz");
291 const char * rpy_str = origin_xml->Attribute(
"rpy");
294 std::vector<std::string> xyz_pieces;
295 boost::split(xyz_pieces, xyz_str, boost::is_any_of(
" "));
298 std::vector<std::string> rpy_pieces;
299 boost::split(rpy_pieces, rpy_str, boost::is_any_of(
" "));
302 if (xyz_pieces.size() == 3)
304 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]));
307 if (rpy_pieces.size() == 3)
309 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]));
313 origin = origin * frame_offset;
315 xyz[0] = origin.
p.
x();
316 xyz[1] = origin.
p.
y();
317 xyz[2] = origin.
p.
z();
320 origin.
M.
GetRPY(rpy[0], rpy[1], rpy[2]);
323 for (
int i = 0; i < 3; ++i)
327 xyz_ss << std::fixed << std::setprecision(precision) << xyz[i];
331 for (
int i = 0; i < 3; ++i)
335 rpy_ss << std::fixed << std::setprecision(precision) << rpy[i];
339 origin_xml->SetAttribute(
"xyz", xyz_ss.str());
340 origin_xml->SetAttribute(
"rpy", rpy_ss.str());
344 xyz[0] = frame_offset.
p.
x();
345 xyz[1] = frame_offset.
p.
y();
346 xyz[2] = frame_offset.
p.
z();
349 frame_offset.
M.
GetRPY(rpy[0], rpy[1], rpy[2]);
352 origin_xml =
new TiXmlElement(
"origin");
355 for (
int i = 0; i < 3; ++i)
359 xyz_ss << std::fixed << std::setprecision(precision) << xyz[i];
361 origin_xml->SetAttribute(
"xyz", xyz_ss.str());
364 for (
int i = 0; i < 3; ++i)
368 rpy_ss << std::fixed << std::setprecision(precision) << rpy[i];
370 origin_xml->SetAttribute(
"rpy", rpy_ss.str());
372 TiXmlNode * origin = origin_xml->Clone();
373 joint_xml->InsertEndChild(*origin);
379 TiXmlPrinter printer;
380 printer.SetIndent(
" ");
381 xml_doc.Accept(&printer);
382 std::string new_urdf = printer.CStr();
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
bool set(const std::string name, double value)
Set the values for a single parameter.
bool getFrame(const std::string name, KDL::Frame &offset) const
Get the offset for a frame calibration.
std::vector< std::string > parameter_names_
std::string getOffsetYAML()
Get all the current offsets as a YAML.
std::vector< std::string > frame_names_
bool initialize(double *free_params)
Initialize the free_params.
std::vector< double > parameter_offsets_
bool add(const std::string name)
Tell the parser we wish to calibrate an active joint or other single parameter.
static Rotation RPY(double roll, double pitch, double yaw)
bool setFrame(const std::string name, double x, double y, double z, double roll, double pitch, double yaw)
Set the values for a frame.
static Rotation Identity()
Calibration code lives under this namespace.
double get(const std::string name) const
Get the offset.
void GetRPY(double &roll, double &pitch, double &yaw) const
void axis_magnitude_from_rotation(const KDL::Rotation &r, double &x, double &y, double &z)
Converts from KDL::Rotation to angle-axis-with-integrated-magnitude.
KDL::Rotation rotation_from_axis_magnitude(const double x, const double y, const double z)
Converts our angle-axis-with-integrated-magnitude representation to a KDL::Rotation.
bool addFrame(const std::string name, bool calibrate_x, bool calibrate_y, bool calibrate_z, bool calibrate_roll, bool calibrate_pitch, bool calibrate_yaw)
Tell the parser we wish to calibrate a fixed joint.
std::string updateURDF(const std::string &urdf)
Update the urdf with the new offsets.
bool reset()
Clear free parameters, but retain values for multi-step calirations.
CalibrationOffsetParser()
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
bool loadOffsetYAML(const std::string &filename)
Load all the current offsets from a YAML.
bool update(const double *const free_params)
Update the offsets based on free_params from ceres-solver.