00001 #include <sparse_bundle_adjustment/node.h>
00002
00003 using namespace std;
00004 using namespace Eigen;
00005
00006 namespace sba
00007 {
00008 void Node::setTransform()
00009 { transformW2F(w2n,trans,qrot); }
00010
00011
00012
00013
00014 void Node::setDri()
00015 {
00016 setDr(true);
00017 }
00018
00019
00020
00021 Eigen::Matrix3d Node::dRidx, Node::dRidy, Node::dRidz;
00022
00023 void Node::initDr()
00024 {
00025 dRidx << 0.0,0.0,0.0,
00026 0.0,0.0,2.0,
00027 0.0,-2.0,0.0;
00028 dRidy << 0.0,0.0,-2.0,
00029 0.0,0.0,0.0,
00030 2.0,0.0,0.0;
00031 dRidz << 0.0,2.0,0.0,
00032 -2.0,0.0,0.0,
00033 0.0,0.0,0.0;
00034 }
00035
00036
00037 void Node::normRot()
00038 {
00039
00040 if (qrot.w() < 0) qrot.coeffs().head<3>() = -qrot.coeffs().head<3>();
00041 double sn = qrot.coeffs().head<3>().squaredNorm();
00042 if (sn >= 0.9999)
00043 qrot.coeffs().head<3>() *= -1.0/(sqrt(sn)*1.0001);
00044 qrot.w() = sqrt(1.0 - qrot.coeffs().head<3>().squaredNorm());
00045 if (isnan(qrot.x()) || isnan(qrot.y()) || isnan(qrot.z()) || isnan(qrot.w()) )
00046 {
00047 printf("[NormRot] Bad quaternion: %f %f %f %f\n", qrot.x(), qrot.y(), qrot.z(), qrot.w());
00048 exit(1);
00049 }
00050
00051 }
00052
00053
00054
00055
00056 void Node::setDr(bool local)
00057 {
00058
00059 if (local)
00060 {
00061 #if 0
00062 dRdx = w2n.block<3,3>(0,0) * dRidx;
00063 dRdy = w2n.block<3,3>(0,0) * dRidy;
00064 dRdz = w2n.block<3,3>(0,0) * dRidz;
00065 #endif
00066 dRdx = dRidx * w2n.block<3,3>(0,0);
00067 dRdy = dRidy * w2n.block<3,3>(0,0);
00068 dRdz = dRidz * w2n.block<3,3>(0,0);
00069
00070 }
00071 else
00072 {
00073 double x2 = qrot.x() * 2.0;
00074 double y2 = qrot.y() * 2.0;
00075 double z2 = qrot.z() * 2.0;
00076 double w2 = qrot.w() * 2.0;
00077 double xw = qrot.x()/qrot.w();
00078 double yw = qrot.y()/qrot.w();
00079 double zw = qrot.z()/qrot.w();
00080
00081
00082 dRdx(0,0) = 0.0;
00083 dRdx(0,1) = y2-zw*x2;
00084 dRdx(0,2) = z2+yw*x2;
00085
00086 dRdx(1,0) = y2+zw*x2;
00087 dRdx(1,1) = -2.0*x2;
00088 dRdx(1,2) = w2-xw*x2;
00089
00090 dRdx(2,0) = z2-yw*x2;
00091 dRdx(2,1) = -dRdx(1,2);
00092 dRdx(2,2) = dRdx(1,1);
00093
00094
00095 dRdy(0,0) = -2.0*y2;
00096 dRdy(0,1) = x2-zw*y2;
00097 dRdy(0,2) = (-w2)+yw*y2;
00098
00099 dRdy(1,0) = x2+zw*y2;
00100 dRdy(1,1) = 0.0;
00101 dRdy(1,2) = dRdx(2,0);
00102
00103 dRdy(2,0) = -dRdy(0,2);
00104 dRdy(2,1) = dRdx(0,2);
00105 dRdy(2,2) = dRdy(0,0);
00106
00107
00108 dRdz(0,0) = -2.0*z2;
00109 dRdz(0,1) = w2-zw*z2;
00110 dRdz(0,2) = dRdy(1,0);
00111
00112 dRdz(1,0) = -dRdz(0,1);
00113 dRdz(1,1) = dRdz(0,0);
00114 dRdz(1,2) = dRdx(0,1);
00115
00116 dRdz(2,0) = dRdy(0,1);
00117 dRdz(2,1) = dRdx(1,0);
00118 dRdz(2,2) = 0.0;
00119 }
00120 }
00121
00122 void Node::normRotLocal()
00123 {
00124 qrot.normalize();
00125 if (qrot.w() < 0) qrot.coeffs().head<3>() = -qrot.coeffs().head<3>();
00126 if (isnan(qrot.x()) || isnan(qrot.y()) || isnan(qrot.z()) || isnan(qrot.w()) )
00127 {
00128 printf("[NormRot] Bad quaternion in normRotLocal(): %f %f %f %f\n", qrot.x(), qrot.y(), qrot.z(), qrot.w());
00129 exit(1);
00130 }
00131
00132 }
00133
00134 void Node::projectMono(const Point& point, Eigen::Vector3d& proj)
00135 {
00136 Vector2d proj2d;
00137 project2im(proj2d, point);
00138
00139 proj.head<2>() = proj2d;
00140 }
00141
00142 void Node::projectStereo(const Point& point, Eigen::Vector3d& proj)
00143 {
00144 Vector2d proj2d;
00145 Vector3d pc, baseline_vect;
00146 project2im(proj2d, point);
00147
00148
00149 baseline_vect << baseline, 0, 0;
00150 pc = Kcam * (w2n*point - baseline_vect);
00151 proj.head<2>() = proj2d;
00152 proj(2) = pc(0)/pc(2);
00153 }
00154
00155
00156
00157 void transformW2F(Eigen::Matrix<double,3,4> &m,
00158 const Eigen::Matrix<double,4,1> &trans,
00159 const Eigen::Quaternion<double> &qrot)
00160 {
00161 m.block<3,3>(0,0) = qrot.toRotationMatrix().transpose();
00162 m.col(3).setZero();
00163 m.col(3) = -m*trans;
00164 };
00165
00166 void transformF2W(Eigen::Matrix<double,3,4> &m,
00167 const Eigen::Matrix<double,4,1> &trans,
00168 const Eigen::Quaternion<double> &qrot)
00169 {
00170 m.block<3,3>(0,0) = qrot.toRotationMatrix();
00171 m.col(3) = trans.head(3);
00172 };
00173
00174
00175
00176
00177 void transformN2N(Eigen::Matrix<double,4,1> &trans,
00178 Eigen::Quaternion<double> &qr,
00179 Node &nd0, Node &nd1)
00180 {
00181 Matrix<double,3,4> tfm;
00182 Quaterniond q0,q1;
00183 q0 = nd0.qrot;
00184 transformW2F(tfm,nd0.trans,q0);
00185 trans.head(3) = tfm*nd1.trans;
00186 trans(3) = 1.0;
00187 q1 = nd1.qrot;
00188 qr = q0.inverse()*q1;
00189 qr.normalize();
00190 if (qr.w() < 0)
00191 qr.coeffs() = -qr.coeffs();
00192 }
00193
00194
00195 }
00196
00197