OMIPUtils.cpp
Go to the documentation of this file.
00001 #include <lgsm/Lgsm>
00002 
00003 #include "omip_common/OMIPUtils.h"
00004 
00005 #include <math.h>
00006 
00007 #include <tr1/random>
00008 
00009 #include <iostream>
00010 #include <fstream>
00011 
00012 using namespace omip;
00013 
00014 void omip::EigenAffine2TranslationAndEulerAngles(const Eigen::Affine3d& t,
00015                                                  double& x, double& y, double& z,
00016                                                  double& roll, double& pitch,
00017                                                  double& yaw)
00018 {
00019     x = t(0, 3);
00020     y = t(1, 3);
00021     z = t(2, 3);
00022     roll = atan2(t(2, 1), t(2, 2));
00023     pitch = asin(-t(2, 0));
00024     yaw = atan2(t(1, 0), t(0, 0));
00025 }
00026 
00027 void omip::TranslationAndEulerAngles2EigenAffine(
00028         const double& x, const double& y, const double& z, const double& roll, const double& pitch, const double& yaw,
00029         Eigen::Transform<double, 3, Eigen::Affine> &t)
00030 {
00031     double A = cos(yaw), B = sin(yaw), C = cos(pitch), D = sin(pitch), E = cos(roll), F = sin(roll), DE = D * E, DF = D * F;
00032 
00033     t(0, 0) = A * C;
00034     t(0, 1) = A * DF - B * E;
00035     t(0, 2) = B * F + A * DE;
00036     t(0, 3) = x;
00037     t(1, 0) = B * C;
00038     t(1, 1) = A * E + B * DF;
00039     t(1, 2) = B * DE - A * F;
00040     t(1, 3) = y;
00041     t(2, 0) = -D;
00042     t(2, 1) = C * F;
00043     t(2, 2) = C * E;
00044     t(2, 3) = z;
00045     t(3, 0) = 0;
00046     t(3, 1) = 0;
00047     t(3, 2) = 0;
00048     t(3, 3) = 1;
00049 }
00050 
00051 double omip::sampleNormal(double mean, double std_dev)
00052 {
00053     using namespace boost;
00054     static std::tr1::mt19937 rng(static_cast<unsigned>(std::time(0)));
00055 
00056     std::tr1::normal_distribution<double> norm_dist(mean, std_dev);
00057 
00058     std::tr1::variate_generator<std::tr1::mt19937&, std::tr1::normal_distribution<double> > normal_sampler(
00059                 rng, norm_dist);
00060 
00061     return (normal_sampler());
00062 }
00063 
00064 std::ostream& omip::operator <<(std::ostream& os,
00065                                 std::vector<Feature::Id> vector_ids)
00066 {
00067     for (size_t idx = 0; idx < vector_ids.size(); idx++)
00068     {
00069         os << vector_ids.at(idx) << " ";
00070     }
00071     return (os);
00072 }
00073 
00074 std::ostream& omip::operator <<(std::ostream& os, Feature::Location location)
00075 {
00076     os << "(" << boost::tuples::get<0>(location) << ","
00077        << boost::tuples::get<1>(location) << ","
00078        << boost::tuples::get<2>(location) << ")";
00079 
00080     return (os);
00081 }
00082 
00083 std::ostream& omip::operator <<(std::ostream& os, Eigen::Twistd twistd)
00084 {
00085     os << "(" << twistd.vx() << ","
00086        << twistd.vy() << ","
00087        << twistd.vz() << ","
00088        << twistd.rx() << ","
00089        << twistd.ry() << ","
00090        << twistd.rz() << ")";
00091 
00092     return (os);
00093 }
00094 
00095 double omip::L2Distance(const Feature::Location &first, const Feature::Location &second)
00096 {
00097     double error_value = sqrt( pow(boost::tuples::get<0>(first) - boost::tuples::get<0>(second), 2)
00098                                + pow(boost::tuples::get<1>(first) - boost::tuples::get<1>(second), 2)
00099                                + pow(boost::tuples::get<2>(first) - boost::tuples::get<2>(second), 2));
00100     return error_value;
00101 }
00102 
00103 void omip::TransformMatrix2Twist(const Eigen::Matrix4d& transformation_matrix, Eigen::Twistd &twist)
00104 {
00105     //std::cout << "Error! Do not use TransformMatrix2Twist. It uses the log to convert from lie group to lie algebra and log is dicontinuous. Use TransformMatrix2TwistUnwrapped instead!" << std::endl;
00106     //getchar();
00107     Eigen::Displacementd displ_from_transf(transformation_matrix);
00108     twist = displ_from_transf.log(1e-12);
00109 }
00110 
00111 void omip::TransformMatrix2TwistUnwrapped(const Eigen::Matrix4d& transformation_matrix, Eigen::Twistd &twist, const Eigen::Twistd &twist_previous)
00112 {
00113     Eigen::Displacementd displ_from_transf(transformation_matrix);
00114     twist = displ_from_transf.log(1e-12);
00115 }
00116 
00117 void omip::Twist2TransformMatrix(const Eigen::Twistd& transformation_twist, Eigen::Matrix4d &matrix)
00118 {
00119     Eigen::Displacementd displ_from_twist = transformation_twist.exp(1e-12);
00120     matrix = displ_from_twist.toHomogeneousMatrix();
00121 }
00122 
00123 void omip::TransformLocation(const Feature::Location& origin, const Eigen::Matrix4d& transformation, Feature::Location& new_location)
00124 {
00125     Eigen::Affine3d motion_matrix(transformation);
00126     Eigen::Vector3d origin_vector = Eigen::Vector3d(
00127                 boost::tuples::get<0>(origin), boost::tuples::get<1>(origin),
00128                 boost::tuples::get<2>(origin));
00129     Eigen::Vector3d destination_vector = motion_matrix * origin_vector;
00130     boost::tuples::get<0>(new_location) = destination_vector[0];
00131     boost::tuples::get<1>(new_location)= destination_vector[1];
00132     boost::tuples::get<2>(new_location) = destination_vector[2];
00133 }
00134 
00135 void omip::TransformLocation(const Feature::Location& origin, const Eigen::Twistd& twist, Feature::Location& new_location, int feat_id)
00136 {
00137     Eigen::Matrix4d eigen_transform;
00138     omip::Twist2TransformMatrix(twist, eigen_transform);
00139 
00140     omip::TransformLocation(origin, eigen_transform, new_location);
00141 
00142     //  std::ofstream feat_innovation;
00143     //  std::ostringstream name_file;
00144     //  name_file << "/home/roberto/Desktop/twists_and_Ts.txt";
00145     //  feat_innovation.open (name_file.str().c_str(), std::ios::app);
00146 
00147     //  feat_innovation << feat_id  << std::endl;
00148     //  feat_innovation << boost::tuples::get<0>(origin) << " " << boost::tuples::get<1>(origin) << " " << boost::tuples::get<2>(origin) << " "  << std::endl;
00149     //  Eigen::Twistd copy = twist;
00150     //  Eigen::Vector3d angular_part = Eigen::Vector3d(copy.rx(),copy.ry(),copy.rz() );
00151     //  feat_innovation << (angular_part.norm() - 2*M_PI)  << std::endl;
00152     //  feat_innovation << boost::tuples::get<0>(new_location) << " " << boost::tuples::get<1>(new_location) << " " << boost::tuples::get<2>(new_location) << " "  << std::endl;
00153     //  feat_innovation << twist << std::endl;
00154     //  feat_innovation << eigen_transform << std::endl<< std::endl;
00155     //  feat_innovation.close();
00156 }
00157 
00158 void omip::TransformLocation(const Feature::Location& origin, const geometry_msgs::Twist& twist, Feature::Location& new_location)
00159 {
00160     Eigen::Twistd eigen_twist;
00161     GeometryMsgsTwist2EigenTwist(twist, eigen_twist);
00162     omip::TransformLocation(origin, eigen_twist, new_location);
00163 }
00164 
00165 void omip::LocationOfFeature2ColumnVector(const Feature::Location &lof, MatrixWrapper::ColumnVector &col_vec)
00166 {
00167     col_vec(1) = boost::tuples::get<0>(lof);
00168     col_vec(2) = boost::tuples::get<1>(lof);
00169     col_vec(3) = boost::tuples::get<2>(lof);
00170 }
00171 
00172 void omip::LocationOfFeature2ColumnVectorHomogeneous(const Feature::Location& lof, MatrixWrapper::ColumnVector& col_vec)
00173 {
00174     col_vec(1) = boost::tuples::get<0>(lof);
00175     col_vec(2) = boost::tuples::get<1>(lof);
00176     col_vec(3) = boost::tuples::get<2>(lof);
00177     col_vec(4) = 1;
00178 }
00179 
00180 void omip::LocationOfFeature2EigenVectorHomogeneous(const Feature::Location& lof, Eigen::Vector4d& eig_vec)
00181 {
00182     eig_vec(0) = boost::tuples::get<0>(lof);
00183     eig_vec(1) = boost::tuples::get<1>(lof);
00184     eig_vec(2) = boost::tuples::get<2>(lof);
00185     eig_vec(3) = 1;
00186 }
00187 
00188 Feature::Location omip::operator-(const Feature::Location& location1,
00189                                   const Feature::Location& location2)
00190 {
00191     return Feature::Location(
00192                 boost::tuples::get<0>(location1) - boost::tuples::get<0>(location2),
00193                 boost::tuples::get<1>(location1) - boost::tuples::get<1>(location2),
00194                 boost::tuples::get<2>(location1) - boost::tuples::get<2>(location2));
00195 }
00196 
00197 Feature::Location omip::operator+(const Feature::Location& location1,
00198                                   const Feature::Location& location2)
00199 {
00200     return Feature::Location(
00201                 boost::tuples::get<0>(location1) + boost::tuples::get<0>(location2),
00202                 boost::tuples::get<1>(location1) + boost::tuples::get<1>(location2),
00203                 boost::tuples::get<2>(location1) + boost::tuples::get<2>(location2));
00204 }
00205 
00206 void omip::GeometryMsgsTwist2EigenTwist(const geometry_msgs::Twist& gm_twist, Eigen::Twistd &eigen_twist)
00207 {
00208     eigen_twist = Eigen::Twistd(gm_twist.angular.x, gm_twist.angular.y, gm_twist.angular.z,
00209                                 gm_twist.linear.x, gm_twist.linear.y, gm_twist.linear.z);
00210 }
00211 
00212 void omip::EigenTwist2GeometryMsgsTwist(Eigen::Twistd& eigen_twist, geometry_msgs::Twist &gm_twist)
00213 {
00214     gm_twist.linear.x = eigen_twist.getLinearVelocity().x();
00215     gm_twist.linear.y = eigen_twist.getLinearVelocity().y();
00216     gm_twist.linear.z = eigen_twist.getLinearVelocity().z();
00217     gm_twist.angular.x = eigen_twist.getAngularVelocity().x();
00218     gm_twist.angular.y = eigen_twist.getAngularVelocity().y();
00219     gm_twist.angular.z = eigen_twist.getAngularVelocity().z();
00220 }
00221 
00222 bool omip::isFinite(const Eigen::Matrix4d& transformation)
00223 {
00224     bool ret_val = true;
00225     for (int col = 0; col < transformation.cols(); ++col)
00226     {
00227         for (int row = 0; row < transformation.rows(); ++row)
00228         {
00229             if (isnan(transformation(row, col)))
00230             {
00231                 ret_val = false;
00232                 break;
00233             }
00234         }
00235     }
00236     return ret_val;
00237 }
00238 
00239 void omip::Location2PointPCL(const Feature::Location &point_location,pcl::PointXYZ& point_pcl)
00240 {
00241     point_pcl.x = boost::tuples::get<0>(point_location);
00242     point_pcl.y = boost::tuples::get<1>(point_location);
00243     point_pcl.z = boost::tuples::get<2>(point_location);
00244 }
00245 
00246 void omip::LocationAndId2FeaturePCL(const Feature::Location &feature_location, const Feature::Id &feature_id, omip::FeaturePCL &feature_pcl)
00247 {
00248     feature_pcl.x = boost::tuples::get<0>(feature_location);
00249     feature_pcl.y = boost::tuples::get<1>(feature_location);
00250     feature_pcl.z = boost::tuples::get<2>(feature_location);
00251     feature_pcl.label = feature_id;
00252 }
00253 
00254 void omip::LocationAndId2FeaturePCLwc(const Feature::Location &feature_location, const Feature::Id &feature_id, omip::FeaturePCLwc &feature_pcl)
00255 {
00256     feature_pcl.x = boost::tuples::get<0>(feature_location);
00257     feature_pcl.y = boost::tuples::get<1>(feature_location);
00258     feature_pcl.z = boost::tuples::get<2>(feature_location);
00259     feature_pcl.label = feature_id;
00260 }
00261 
00262 void omip::ROSTwist2EigenTwist(const geometry_msgs::Twist& ros_twist, Eigen::Twistd& eigen_twist)
00263 {
00264     geometry_msgs::Vector3 linear = ros_twist.linear;
00265     geometry_msgs::Vector3 angular = ros_twist.angular;
00266     eigen_twist = Eigen::Twistd(angular.x, angular.y, angular.z,
00267                                 linear.x, linear.y, linear.z);
00268 }
00269 
00270 //Normalize to [-180,180):
00271 inline double constrainAngle(double x){
00272     x = fmod(x + M_PI,2*M_PI);
00273     if (x < 0)
00274         x += 2*M_PI;
00275     return x - M_PI;
00276 }
00277 // convert to [-360,360]
00278 inline double angleConv(double angle){
00279     return fmod(constrainAngle(angle),2*M_PI);
00280 }
00281 inline double angleDiff(double a,double b){
00282     double dif = fmod(b - a + M_PI,2*M_PI);
00283     if (dif < 0)
00284         dif += 2*M_PI;
00285     return dif - M_PI;
00286 }
00287 inline double unwrap(double previousAngle,double newAngle){
00288     return previousAngle - angleDiff(newAngle,angleConv(previousAngle));
00289 }
00290 
00291 Eigen::Twistd omip::unwrapTwist(Eigen::Twistd& current_twist, Eigen::Displacementd& current_displacement, Eigen::Twistd& previous_twist, bool& changed)
00292 {
00293     Eigen::Vector3d current_angular_component = Eigen::Vector3d(current_twist.rx(), current_twist.ry(), current_twist.rz());
00294     double current_rotation_angle = current_angular_component.norm();
00295     Eigen::Vector3d current_angular_direction = current_angular_component / current_rotation_angle;
00296     Eigen::Vector3d previous_angular_component = Eigen::Vector3d(previous_twist.rx(), previous_twist.ry(), previous_twist.rz());
00297     double previous_rotation_angle = previous_angular_component.norm();
00298     Eigen::Vector3d previous_angular_direction = previous_angular_component / previous_rotation_angle;
00299 
00300     // The difference should be around 2PI (a little bit less)
00301     if(Eigen::Vector3d(current_twist.rx()-previous_twist.rx(), current_twist.ry()-previous_twist.ry(), current_twist.rz()-previous_twist.rz()).norm() > M_PI
00302             || current_angular_direction.dot(previous_angular_direction) < -0.8)
00303     {
00304 
00305         Eigen::Vector3d new_angular_component;
00306 
00307         Eigen::Twistd unwrapped_twist;
00308         // Two cases:
00309         // 1) Jump from PI to -PI or vice versa
00310         // 1) Jump from 2*PI to 0 or from -2*PI to zero
00311         if(previous_rotation_angle + 0.3 < 2*M_PI)
00312         {
00313             // If previous and current are looking in opposite directions -> scalar product will be close to -1
00314             if(current_angular_direction.dot(previous_angular_direction) < 0)
00315             {
00316                 new_angular_component= M_PI*previous_angular_direction -(M_PI - current_rotation_angle)*current_angular_direction;
00317             }// If both are looking in the same direction -> scalar product is close to +1
00318             else{
00319                 new_angular_component= M_PI*previous_angular_direction +(M_PI - current_rotation_angle)*current_angular_direction;
00320             }
00321         }else{
00322             ROS_ERROR_STREAM("Numeric instability in the logarithm of a homogeneous transformation!");
00323             // If previous and current are looking in opposite directions -> scalar product will be close to -1
00324             if(current_angular_direction.dot(previous_angular_direction) < 0)
00325             {
00326                 new_angular_component= std::min(2*M_PI, previous_rotation_angle)*previous_angular_direction +current_rotation_angle*current_angular_direction;
00327             }// If both are looking in the same direction -> scalar product is close to +1
00328             else{
00329                 new_angular_component= std::min(2*M_PI, previous_rotation_angle)*previous_angular_direction +current_rotation_angle*current_angular_direction;
00330             }
00331         }
00332 
00333         double n2 = new_angular_component.squaredNorm();  // ||wtilde||^2
00334         double n = sqrt(n2);
00335         double sn = sin(n);
00336         double val = (double(2.0) * sn - n * (double(1.0) + cos(n))) / (double(2.0) *n2 * sn);
00337 
00338         Eigen::Vector3d RE3Element = Eigen::Vector3d(current_displacement.getR3Element()(0),current_displacement.getR3Element()(1),current_displacement.getR3Element()(2) );
00339         Eigen::Vector3d lin = -0.5*new_angular_component.cross(RE3Element);
00340         lin += (double(1.0) - val * n2 ) * RE3Element;
00341         lin += val * new_angular_component.dot(RE3Element) * new_angular_component;
00342 
00343         unwrapped_twist = Eigen::Twistd(new_angular_component.x(), new_angular_component.y(), new_angular_component.z(), lin.x(), lin.y(), lin.z());
00344 
00345         if(std::fabs(val) > 10)
00346         {
00347             ROS_ERROR_STREAM("Numeric instability in the logarithm of a homogeneous transformation. Val: " << val);
00348         }
00349 
00350         changed = true;
00351         return unwrapped_twist;
00352     }else{
00353         changed = false;
00354         return current_twist;
00355     }
00356 }
00357 
00358 Eigen::Twistd omip::invertTwist(Eigen::Twistd& current_twist, Eigen::Twistd& previous_twist, bool& inverted)
00359 {
00360     Eigen::Vector3d current_angular_component = Eigen::Vector3d(current_twist.rx(), current_twist.ry(), current_twist.rz());
00361     double current_rotation_angle = current_angular_component.norm();
00362     Eigen::Vector3d current_angular_direction = current_angular_component / current_rotation_angle;
00363     Eigen::Vector3d previous_angular_component = Eigen::Vector3d(previous_twist.rx(), previous_twist.ry(), previous_twist.rz());
00364     double previous_rotation_angle = previous_angular_component.norm();
00365     Eigen::Vector3d previous_angular_direction = previous_angular_component / previous_rotation_angle;
00366     // The difference should be around 2PI (a little bit less)
00367     if(Eigen::Vector3d(current_twist.rx()-previous_twist.rx(), current_twist.ry()-previous_twist.ry(), current_twist.rz()-previous_twist.rz()).norm() > M_PI
00368             || current_angular_direction.dot(previous_angular_direction) < -0.8)
00369     {
00370         inverted = true;
00371         return -current_twist;
00372     }else{
00373         inverted = false;
00374         return current_twist;
00375     }
00376 }
00377 
00378 void omip::invert3x3Matrix(const MatrixWrapper::Matrix& to_inv, MatrixWrapper::Matrix& inverse)
00379 {
00380     double determinant =    +to_inv(1,1)*(to_inv(2,2)*to_inv(3,3)-to_inv(3,2)*to_inv(2,3))
00381             -to_inv(1,2)*(to_inv(2,1)*to_inv(3,3)-to_inv(2,3)*to_inv(3,1))
00382             +to_inv(1,3)*(to_inv(2,1)*to_inv(3,2)-to_inv(2,2)*to_inv(3,1));
00383     double invdet = 1.0/determinant;
00384     inverse(1,1) =  (to_inv(2,2)*to_inv(3,3)-to_inv(3,2)*to_inv(2,3))*invdet;
00385     inverse(2,1) = -(to_inv(1,2)*to_inv(3,3)-to_inv(1,3)*to_inv(3,2))*invdet;
00386     inverse(3,1) =  (to_inv(1,2)*to_inv(2,3)-to_inv(1,3)*to_inv(2,2))*invdet;
00387     inverse(1,2) = -(to_inv(2,1)*to_inv(3,3)-to_inv(2,3)*to_inv(3,1))*invdet;
00388     inverse(2,2) =  (to_inv(1,1)*to_inv(3,3)-to_inv(1,3)*to_inv(3,1))*invdet;
00389     inverse(3,2) = -(to_inv(1,1)*to_inv(2,3)-to_inv(2,1)*to_inv(1,3))*invdet;
00390     inverse(1,3) =  (to_inv(2,1)*to_inv(3,2)-to_inv(3,1)*to_inv(2,2))*invdet;
00391     inverse(2,3) = -(to_inv(1,1)*to_inv(3,2)-to_inv(3,1)*to_inv(1,2))*invdet;
00392     inverse(3,3) =  (to_inv(1,1)*to_inv(2,2)-to_inv(2,1)*to_inv(1,2))*invdet;
00393 }
00394 
00395 void omip::invert3x3MatrixEigen(const Eigen::Map<Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> >& to_inv,
00396                                 Eigen::Map<Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> >& inverse)
00397 {
00398     double determinant =    +to_inv(0,0)*(to_inv(1,1)*to_inv(2,2)-to_inv(2,1)*to_inv(1,2))
00399             -to_inv(0,1)*(to_inv(1,0)*to_inv(2,2)-to_inv(1,2)*to_inv(2,0))
00400             +to_inv(0,2)*(to_inv(1,0)*to_inv(2,1)-to_inv(1,1)*to_inv(2,0));
00401     double invdet = 1.0/determinant;
00402     inverse(0,0) =  (to_inv(1,1)*to_inv(2,2)-to_inv(2,1)*to_inv(1,2))*invdet;
00403     inverse(1,0) = -(to_inv(0,1)*to_inv(2,2)-to_inv(0,2)*to_inv(2,1))*invdet;
00404     inverse(2,0) =  (to_inv(0,1)*to_inv(1,2)-to_inv(0,2)*to_inv(1,1))*invdet;
00405     inverse(0,1) = -(to_inv(1,0)*to_inv(2,2)-to_inv(1,2)*to_inv(2,0))*invdet;
00406     inverse(1,1) =  (to_inv(0,0)*to_inv(2,2)-to_inv(0,2)*to_inv(2,0))*invdet;
00407     inverse(2,1) = -(to_inv(0,0)*to_inv(1,2)-to_inv(1,0)*to_inv(0,2))*invdet;
00408     inverse(0,2) =  (to_inv(1,0)*to_inv(2,1)-to_inv(2,0)*to_inv(1,1))*invdet;
00409     inverse(1,2) = -(to_inv(0,0)*to_inv(2,1)-to_inv(2,0)*to_inv(0,1))*invdet;
00410     inverse(2,2) =  (to_inv(0,0)*to_inv(1,1)-to_inv(1,0)*to_inv(0,1))*invdet;
00411 }
00412 
00413 void omip::invert3x3MatrixEigen2(const Eigen::Matrix3d& to_inv,
00414                                  Eigen::Matrix3d& inverse)
00415 {
00416     double determinant =    +to_inv(0,0)*(to_inv(1,1)*to_inv(2,2)-to_inv(2,1)*to_inv(1,2))
00417             -to_inv(0,1)*(to_inv(1,0)*to_inv(2,2)-to_inv(1,2)*to_inv(2,0))
00418             +to_inv(0,2)*(to_inv(1,0)*to_inv(2,1)-to_inv(1,1)*to_inv(2,0));
00419     double invdet = 1.0/determinant;
00420     inverse(0,0) =  (to_inv(1,1)*to_inv(2,2)-to_inv(2,1)*to_inv(1,2))*invdet;
00421     inverse(1,0) = -(to_inv(0,1)*to_inv(2,2)-to_inv(0,2)*to_inv(2,1))*invdet;
00422     inverse(2,0) =  (to_inv(0,1)*to_inv(1,2)-to_inv(0,2)*to_inv(1,1))*invdet;
00423     inverse(0,1) = -(to_inv(1,0)*to_inv(2,2)-to_inv(1,2)*to_inv(2,0))*invdet;
00424     inverse(1,1) =  (to_inv(0,0)*to_inv(2,2)-to_inv(0,2)*to_inv(2,0))*invdet;
00425     inverse(2,1) = -(to_inv(0,0)*to_inv(1,2)-to_inv(1,0)*to_inv(0,2))*invdet;
00426     inverse(0,2) =  (to_inv(1,0)*to_inv(2,1)-to_inv(2,0)*to_inv(1,1))*invdet;
00427     inverse(1,2) = -(to_inv(0,0)*to_inv(2,1)-to_inv(2,0)*to_inv(0,1))*invdet;
00428     inverse(2,2) =  (to_inv(0,0)*to_inv(1,1)-to_inv(1,0)*to_inv(0,1))*invdet;
00429 }
00430 
00431 void omip::computeAdjoint(const Eigen::Twistd &pose_ec, Eigen::Matrix<double, 6, 6> &adjoint_out)
00432 {
00433     omip::computeAdjoint(pose_ec.exp(1e-12), adjoint_out);
00434 }
00435 
00436 void omip::adjointXcovXadjointT(const Eigen::Twistd& pose_ec, const Eigen::Matrix<double, 6, 6>& cov, Eigen::Matrix<double, 6, 6>& transformed_cov_out)
00437 {
00438     Eigen::Matrix<double, 6, 6> adjoint;
00439     omip::computeAdjoint(pose_ec, adjoint);
00440 
00441     transformed_cov_out = adjoint*cov*adjoint.transpose();
00442 }
00443 
00444 //LGSM adjoint:
00445 // (   R    0 )
00446 // ((t x R) R )
00447 //Desired adjoint:
00448 // ( R (t x R))
00449 // ( 0    R   )
00450 void omip::computeAdjoint(Eigen::Displacementd pose_disp, Eigen::Matrix<double, 6, 6> &adjoint_out)
00451 {
00452     Eigen::Matrix<double, 6, 6> adjoint_rot_trans = pose_disp.adjoint();
00453 
00454     adjoint_out = adjoint_rot_trans;
00455     adjoint_out.block<3,3>(0,3) = adjoint_rot_trans.block<3,3>(3,0);
00456     adjoint_out.block<3,3>(3,0) = adjoint_rot_trans.block<3,3>(0,3);
00457 }
00458 
00459 void omip::adjointXcovXadjointT(const Eigen::Displacementd& pose_disp,
00460                                 const Eigen::Matrix<double, 6, 6>& cov,
00461                                 Eigen::Matrix<double, 6, 6>& transformed_cov_out)
00462 {
00463     Eigen::Matrix<double, 6, 6> adjoint;
00464     omip::computeAdjoint(pose_disp, adjoint);
00465 
00466     transformed_cov_out = adjoint*cov*adjoint.transpose();
00467 }
00468 
00469 void omip::adjointXinvAdjointXcovXinvAdjointTXadjointT(const Eigen::Displacementd& pose_disp1,
00470                                                        const Eigen::Displacementd& pose_disp2,
00471                                                        const Eigen::Matrix<double, 6, 6>& cov,
00472                                                        Eigen::Matrix<double, 6, 6>& transformed_cov_out)
00473 {
00474     //T_rrbf_srbf.adjoint()*T_rrbf_srbf_t0.inverse().adjoint()*_srb_initial_pose_cov_in_rrbf*T_rrbf_srbf_t0.inverse().adjoint().transpose()*T_rrbf_srbf.adjoint().transpose()
00475     Eigen::Matrix<double, 6, 6> adjoint1;
00476     omip::computeAdjoint(pose_disp1, adjoint1);
00477 
00478     Eigen::Matrix<double, 6, 6> adjoint2;
00479     omip::computeAdjoint(pose_disp2.inverse(), adjoint2);
00480 
00481     transformed_cov_out = adjoint1*adjoint2*cov*adjoint2.transpose()*adjoint1.transpose();
00482 }


omip_common
Author(s): Roberto Martín-Martín
autogenerated on Sat Jun 8 2019 18:26:37