105 string inputFilename;
106 string outputfilename;
108 string odomTestFilename;
109 string dumpGraphFilename;
112 commandLineArguments.
param(
"i", maxIterations, 10,
"perform n iterations");
113 commandLineArguments.
param(
"v", verbose,
false,
"verbose output of the optimization process");
114 commandLineArguments.
param(
"o", outputfilename,
"",
"output final version of the graph");
115 commandLineArguments.
param(
"test", odomTestFilename,
"",
"apply odometry calibration to some test data");
116 commandLineArguments.
param(
"dump", dumpGraphFilename,
"",
"write the graph to the disk");
117 commandLineArguments.
param(
"fixLaser", fixLaser,
false,
"keep the laser offset fixed during optimization");
118 commandLineArguments.
paramLeftOver(
"gm2dl-input", inputFilename,
"",
"gm2dl file which will be processed");
119 commandLineArguments.
paramLeftOver(
"raw-log", rawFilename,
"",
"raw log file containing the odometry");
121 commandLineArguments.
parseArgs(argc, argv);
130 int numLaserOdom = Gm2dlIO::readRobotLaser(rawFilename, odometryQueue);
131 if (numLaserOdom == 0) {
132 cerr <<
"No raw information read" << endl;
135 cerr <<
"Read " << numLaserOdom <<
" laser readings from file" << endl;
137 Eigen::Vector3d odomCalib(1., 1., 1.);
138 SE2 initialLaserPose;
140 int numRobotLaser = Gm2dlIO::readRobotLaser(inputFilename, robotLaserQueue);
141 if (numRobotLaser == 0) {
142 cerr <<
"No robot laser read" << endl;
147 cerr << PVAR(initialLaserPose.
toVector().transpose()) << endl;
151 vector<MotionInformation, Eigen::aligned_allocator<MotionInformation> > motions;
153 std::map<double, RobotData*>::const_iterator it = robotLaserQueue.
buffer().begin();
154 std::map<double, RobotData*>::const_iterator prevIt = it++;
155 for (; it != robotLaserQueue.
buffer().end(); ++it) {
166 motions.push_back(mi);
172 laserOffset->
setId(Gm2dlIO::ID_LASERPOSE);
176 odomParamsVertex->
setId(Gm2dlIO::ID_ODOMCALIB);
177 odomParamsVertex->
setEstimate(Eigen::Vector3d(1., 1., 1.));
179 for (
size_t i = 0; i < motions.size(); ++i) {
180 const SE2& odomMotion = motions[i].odomMotion;
181 const SE2& laserMotion = motions[i].laserMotion;
182 const double& timeInterval = motions[i].timeInterval;
187 meas.laserMotion = laserMotion;
190 calibEdge->
setVertex(1, odomParamsVertex);
193 if (! optimizer.
addEdge(calibEdge)) {
194 cerr <<
"Error adding calib edge" << endl;
200 cerr <<
"Fix position of the laser offset" << endl;
204 cerr <<
"\nPerforming full non-linear estimation" << endl;
208 cerr <<
"Calibrated laser offset (x, y, theta):" << laserOffset->
estimate().
toVector().transpose() << endl;
209 odomCalib = odomParamsVertex->
estimate();
210 cerr <<
"Odometry parameters (scaling factors (v_l, v_r, b)): " << odomParamsVertex->
estimate().transpose() << endl;
216 Eigen::MatrixXd A(motions.size(), 2);
217 Eigen::VectorXd x(motions.size());
218 for (
size_t i = 0; i < motions.size(); ++i) {
219 const SE2& odomMotion = motions[i].odomMotion;
220 const SE2& laserMotion = motions[i].laserMotion;
221 const double& timeInterval = motions[i].timeInterval;
224 A(i, 0) = velMeas.vl() * timeInterval;
225 A(i, 1) = velMeas.vr() * timeInterval;
226 x(i) = laserMotion.
rotation().angle();
235 laserOffset->
setId(Gm2dlIO::ID_LASERPOSE);
239 odomParamsVertex->
setId(Gm2dlIO::ID_ODOMCALIB);
242 for (
size_t i = 0; i < motions.size(); ++i) {
243 const SE2& odomMotion = motions[i].odomMotion;
244 const SE2& laserMotion = motions[i].laserMotion;
245 const double& timeInterval = motions[i].timeInterval;
250 meas.laserMotion = laserMotion;
253 calibEdge->
setVertex(1, odomParamsVertex);
256 if (! optimizer.
addEdge(calibEdge)) {
257 cerr <<
"Error adding calib edge" << endl;
263 cerr <<
"Fix position of the laser offset" << endl;
267 cerr <<
"\nPerforming partial non-linear estimation" << endl;
271 cerr <<
"Calibrated laser offset (x, y, theta):" << laserOffset->
estimate().
toVector().transpose() << endl;
274 odomCalib(2) = odomParamsVertex->
estimate();
275 cerr <<
"Odometry parameters (scaling factors (v_l, v_r, b)): " << odomCalib.transpose() << endl;
279 Eigen::Vector3d closedFormOdom;
280 ClosedFormCalibration::calibrate(motions, closedFormLaser, closedFormOdom);
281 cerr <<
"\nObtaining closed form solution" << endl;
282 cerr <<
"Calibrated laser offset (x, y, theta):" << closedFormLaser.
toVector().transpose() << endl;
283 cerr <<
"Odometry parameters (scaling factors (v_l, v_r, b)): " << closedFormOdom.transpose() << endl;
286 if (dumpGraphFilename.size() > 0) {
287 cerr <<
"Writing " << dumpGraphFilename <<
" ... ";
288 optimizer.
save(dumpGraphFilename.c_str());
289 cerr <<
"done." << endl;
293 if (odomTestFilename.size() > 0) {
296 int numTestOdom = Gm2dlIO::readRobotLaser(odomTestFilename, testRobotLaserQueue);
297 if (numTestOdom == 0) {
298 cerr <<
"Unable to read test data" << endl;
301 ofstream rawStream(
"odometry_raw.txt");
302 ofstream calibratedStream(
"odometry_calibrated.txt");
306 for (DataQueue::Buffer::const_iterator it = testRobotLaserQueue.
buffer().begin(); it != testRobotLaserQueue.
buffer().end(); ++it) {
315 VelocityMeasurement velocityMeasurement = OdomConvert::convertToVelocity(motionMeasurement);
319 calibratedVelocityMeasurment.
setVl(odomCalib(0) * calibratedVelocityMeasurment.
vl());
320 calibratedVelocityMeasurment.
setVr(odomCalib(1) * calibratedVelocityMeasurment.
vr());
321 MotionMeasurement mm = OdomConvert::convertToMotion(calibratedVelocityMeasurment, odomCalib(2));
326 SE2 calOdomPose = prevCalibratedPose * remappedOdom;
332 prevCalibratedPose = calOdomPose;
const SE2 & odomPose() const
const Vector3D & measurement() const
const Buffer & buffer() const
Command line parsing of argc and argv.
Vector3D toVector() const
convert to a 3D vector (x, y, theta)
laser measurement obtained by a robot
int optimize(int iterations, bool online=false)
calibrate odometry and laser based on a set of measurements
virtual void setMeasurement(const Measurement &m)
void computeActiveErrors()
2D pose Vertex, (x,y,theta)
static Eigen::Vector2d linearSolution
void setVertex(size_t i, Vertex *v)
VelocityMeasurement velocityMeasurement
virtual void setId(int id)
sets the id of the node in the graph be sure that the graph keeps consistent after changing the id ...
bool parseArgs(int argc, char **argv, bool exitOnError=true)
virtual bool save(std::ostream &os, int level=0) const
save the graph to a stream. Again uses the Factory system.
const Eigen::Rotation2Dd & rotation() const
rotational component
void setVerbose(bool verbose)
velocity measurement of a differential robot
void fromVector(const Vector3D &v)
assign from a 3D vector (x, y, theta)
void paramLeftOver(const std::string &name, std::string &p, const std::string &defValue, const std::string &desc, bool optional=false)
EIGEN_STRONG_INLINE void setInformation(const InformationType &information)
A 2D odometry measurement expressed as a transformation.
void param(const std::string &name, bool &p, bool defValue, const std::string &desc)
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
a simple queue to store data and retrieve based on a timestamp
void allocateSolverForSclam(SparseOptimizer &optimizer, bool levenberg)
const EstimateType & estimate() const
return the current estimate of the vertex
SE2 inverse() const
invert :-)
void setFixed(bool fixed)
true => this node should be considered fixed during the optimization
virtual bool initializeOptimization(HyperGraph::EdgeSet &eset)
RobotData * findClosestData(double timestamp) const
const Vector2D & translation() const
translational component
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)