00001
00002
00003
00004
00005
00006
00007
00008 #include "structs.h"
00009 #include "hogman_wrapper.h"
00010 #include "boost/tuple/tuple.hpp"
00011
00012 using namespace std;
00013 using namespace articulation_models;
00014 using namespace geometry_msgs;
00015 using namespace articulation_msgs;
00016 using namespace std_msgs;
00017 using namespace sensor_msgs;
00018 using namespace articulation_structure;
00019 using namespace Eigen;
00020
00021 USING_PART_OF_NAMESPACE_EIGEN
00022
00023 KinematicParams::KinematicParams() {
00024 sigma_position = 0.005;
00025 sigma_orientation = 0.001;
00026 eval_every = 1;
00027 eval_every_power = 1.0;
00028 supress_similar = false;
00029 reuse_model = true;
00030 restricted_graphs = "";
00031 restrict_graphs = false;
00032 reduce_dofs = false;
00033 search_all_models = false;
00034 full_eval="tree";
00035 }
00036
00037 void KinematicParams::LoadParams(ros::NodeHandle &nh_local,bool show) {
00038 string filter_models("rigid rotational prismatic");
00039 nh_local.getParam("filter_models", filter_models);
00040 nh_local.getParam("sigma_position", sigma_position);
00041 nh_local.getParam("sigma_orientation", sigma_orientation);
00042 nh_local.getParam("sigmax_position", sigmax_position);
00043 nh_local.getParam("sigmax_orientation", sigmax_orientation);
00044 nh_local.getParam("full_eval", full_eval);
00045 nh_local.getParam("eval_every", eval_every);
00046 nh_local.getParam("eval_every_power", eval_every_power);
00047 nh_local.getParam("restricted_graphs", restricted_graphs);
00048 restricted_graphs = " "+restricted_graphs+" ";
00049 nh_local.getParam("restrict_graphs", restrict_graphs);
00050
00051 nh_local.getParam("reuse_model", reuse_model);
00052 nh_local.getParam("supress_similar", supress_similar);
00053 nh_local.getParam("reduce_dofs", reduce_dofs);
00054 nh_local.getParam("search_all_models", search_all_models);
00055
00056 factory.setFilter(filter_models);
00057
00058 }
00059
00060 void KinematicData::addPose(PoseStamped pose1, PoseStamped pose2, size_t id1, size_t id2,KinematicParams ¶ms) {
00061 TrackMsgPtr& track = trajectories[id1][id2];
00062 if (!track) {
00063 track = boost::make_shared<TrackMsg>();
00064 ChannelFloat32 ch;
00065 ch.name = "stamp";
00066 track->channels.push_back(ch);
00067 }
00068
00069 btTransform transf1 = poseToTransform(pose1.pose);
00070 btTransform transf2 = poseToTransform(pose2.pose);
00071 btTransform diff = transf1.inverseTimes(transf2);
00072
00073 for(size_t i=0;i<trajectories[id1][id2]->pose.size();i++) {
00074 btTransform diff_to_known;
00075 Pose p;
00076 p = trajectories[id1][id2]->pose[i];
00077 btTransform t;
00078 t = poseToTransform( p );
00079 diff_to_known = t.inverseTimes( diff );
00080 double diff_position = diff_to_known.getOrigin().length();
00081 double diff_orientation = fabs(diff_to_known.getRotation().getAngle());
00082 if(params.supress_similar && diff_position < params.sigma_position/2 && diff_orientation < params.sigma_orientation/2) {
00083
00084 return;
00085 }
00086 }
00087
00088 poseIndex[id1][id2][ pose1.header.stamp.toSec() ] = track->pose.size();
00089
00090 track->pose.push_back(transformToPose( diff));
00091 track->channels[0].values.push_back( pose1.header.stamp.toSec() );
00092 track->header = pose1.header;
00093
00094
00095 }
00096
00097 void KinematicData::updateModel(size_t id1, size_t id2,KinematicParams ¶ms) {
00098 TrackMsgPtr& track = trajectories[id1][id2];
00099 GenericModelPtr& model = models[id1][id2];
00100
00101 articulation_msgs::ModelMsg model_track;
00102 model_track.track = *track;
00103 model_track.header = track->header;
00104 setParamIfNotDefined(model_track.params, "sigma_position",
00105 params.sigma_position, ParamMsg::PRIOR);
00106 setParamIfNotDefined(model_track.params, "sigma_orientation",
00107 params.sigma_orientation, ParamMsg::PRIOR);
00108
00109 GenericModelVector models_new = params.factory.createModels(model_track);
00110 map<double,GenericModelPtr> models_sorted;
00111 models_all[id1][id2].clear();
00112 for (size_t i = 0; i < models_new.size(); i++) {
00113 if (!models_new[i]->fitModel()) continue;
00114 if (!models_new[i]->fitMinMaxConfigurations()) continue;
00115 if (!models_new[i]->evaluateModel()) continue;
00116 if(isnan( models_new[i]->getBIC() )) continue;
00117
00118 if(params.reuse_model && model && model->getModelName()==models_new[i]->getModelName()) {
00119 model->setTrack(*track);
00120 model->optimizeParameters();
00121 model->evaluateModel();
00122 if(!isnan( model->getBIC() ) &&
00123 (models_new[i]->getBIC() > model->getBIC())) {
00124 models_new[i] = model;
00125 }
00126 }
00127
00128 models_sorted[models_new[i]->getBIC()] = models_new[i];
00129 models_all[id1][id2].push_back( models_new[i] );
00130 }
00131
00132 if(models_sorted.size()==0) {
00133 ROS_INFO_STREAM("no models!! model["<<id1<<","<<id2<<"]: poses="<<track->pose.size());
00134 model.reset();
00135 return;
00136 }
00137 map<double,GenericModelPtr>::iterator it = models_sorted.begin();
00138 model = it->second;
00139
00140
00141
00142
00143
00144
00145
00146
00147
00148
00149
00150
00151 }
00152
00153 std::vector<double> KinematicData::intersectionOfStamps() {
00154
00155 std::vector<double> intersection;
00156
00157 size_t num_markers = markerStamped.size();
00158 for(map<double, map<int, PoseStampedIdMsgConstPtr> >::iterator it = stampedMarker.begin();
00159 it != stampedMarker.end();
00160 it++) {
00161 if(it->second.size() == num_markers) {
00162 intersection.push_back( it->first );
00163 }
00164
00165
00166
00167
00168
00169
00170 }
00171
00172
00173 return(intersection);
00174 }
00175
00176 PoseMap KinematicData::getObservation(double timestamp) {
00177 PoseMap observedMarkers;
00178 for(std::map<int, articulation_structure::PoseStampedIdMsgConstPtr>::iterator it = stampedMarker[timestamp].begin();
00179 it != stampedMarker[timestamp].end();it++) {
00180 observedMarkers[it->first] = it->second->pose.pose;
00181 }
00182 return observedMarkers;
00183 }
00184
00185 KinematicGraph::KinematicGraph() {
00186 BIC = DBL_MAX;
00187 DOF = -1;
00188 avg_pos_err = -1;
00189 avg_orient_err = -1;
00190 loglh = DBL_MAX;
00191 }
00192
00193 KinematicGraph::KinematicGraph(const KinematicGraph &other):
00194 KinematicGraphType( other ), BIC(other.BIC),DOF(other.DOF),avg_pos_err(other.avg_pos_err),avg_orient_err(other.avg_orient_err),loglh(other.loglh)
00195 {
00196 }
00197
00198 KinematicGraph::KinematicGraph(const KinematicGraph &other,bool deepcopy):
00199 KinematicGraphType( other ), BIC(other.BIC),DOF(other.DOF),avg_pos_err(other.avg_pos_err),avg_orient_err(other.avg_orient_err),loglh(other.loglh)
00200 {
00201 if(deepcopy) {
00202 CopyFrom(other);
00203 }
00204 }
00205
00206 void KinematicGraph::CopyFrom(const KinematicGraph &other) {
00207 *this = other;
00208 static MultiModelFactory factory;
00209 for(KinematicGraph::iterator it=begin();it!=end();it++) {
00210 it->second = factory.restoreModel(it->second->getModel());
00211 }
00212 }
00213
00214
00215 size_t KinematicGraph::getNumberOfParameters() {
00216 size_t k = 0;
00217 for(KinematicGraph::iterator it=begin(); it != end();it++) {
00218 k += (size_t) it->second->complexity;
00219 }
00220 return k;
00221 }
00222
00223
00224
00225 int KinematicGraph::getNominalDOFs() {
00226 int DOFs = 0;
00227 for(KinematicGraph::iterator it=begin(); it != end();it++) {
00228 DOFs += it->second->getDOFs();
00229 }
00230 return(DOFs);
00231 }
00232
00233 PoseMap KinematicGraph::getPrediction(double timestamp, PoseMap &observedMarkers, PoseMap &predictedMarkersEmpty, KinematicParams ¶ms,KinematicData &data) {
00234 return hogman_solver(*this, data.poseIndex, observedMarkers, predictedMarkersEmpty, params.sigma_position,params.sigma_orientation, timestamp);
00235 }
00236
00237 string KinematicGraph::getTreeName(bool show_name,bool show_samples,bool show_dof) {
00238 stringstream s;
00239 if(show_dof) {
00240 s << DOF<<"-DOF ";
00241 }
00242 for(KinematicGraph::iterator it=begin(); it != end();it++) {
00243 if(it != begin()) s<<",";
00244 s << "(";
00245 if(show_name) {
00246 s <<it->second->getModelName().substr(0,2)<<":";
00247 }
00248 s <<it->first.first<<","<<it->first.second;
00249 if(show_samples)
00250 s << "/"<<it->second->getSamples();
00251 s<<")";
00252 }
00253 return s.str();
00254 }
00255
00256 void KinematicGraph::evaluateSingleStamp(double timestamp,
00257 double &avgPositionError,
00258 double &avgOrientationError,
00259 double &loglikelihood,KinematicParams ¶ms,KinematicData &data) {
00260
00261 if (size()==0) return;
00262
00263 PoseMap observationMarkers = data.getObservation(timestamp);
00264 PoseMap predictedMarkers = getPrediction(timestamp,observationMarkers,observationMarkers,params,data);
00265
00266
00267 for(PoseMap::iterator i=predictedMarkers.begin();i!=predictedMarkers.end();i++) {
00268 PoseStampedIdMsg p = *data.stampedMarker[timestamp][i->first];
00269 p.pose.pose = i->second;
00270 PoseStampedIdMsgConstPtr pptr = boost::make_shared<PoseStampedIdMsg>(p);
00271 data.stampedMarkerProjected[timestamp][i->first] = pptr;
00272 }
00273
00274
00275 double sum_loglh = 0;
00276 double sum_pos2_err = 0;
00277 double sum_orient2_err = 0;
00278
00279 double sigma2_position = SQR(params.sigmax_position);
00280 double sigma2_orientation = SQR(params.sigmax_orientation);
00281
00282 for(PoseMap::iterator it = observationMarkers.begin();
00283 it != observationMarkers.end(); it++ ) {
00284 btTransform p1 = poseToTransform(observationMarkers[it->first]);
00285 btTransform p2 = poseToTransform(predictedMarkers[it->first]);
00286
00287 btTransform diff = p1.inverseTimes(p2);
00288 double err_position2 = diff.getOrigin().length2();
00289 if(isnan(err_position2 )) err_position2 =0;
00290 double err_orientation2 = SQR(diff.getRotation().getAngle());
00291 if(isnan(err_orientation2 )) err_orientation2 =0;
00292
00293 sum_pos2_err += err_position2;
00294 sum_orient2_err += err_orientation2;
00295
00296 double loglikelihood =
00297 - log(2*M_PI * params.sigma_position*params.sigma_orientation)
00298 - 0.5*(
00299 ( err_position2 / (sigma2_position) ) +
00300 ( err_orientation2 / (sigma2_orientation) ) );
00301 sum_loglh += loglikelihood;
00302 }
00303
00304 size_t n = observationMarkers.size();
00305 avgPositionError = sqrt(sum_pos2_err/n);
00306 avgOrientationError = sqrt(sum_orient2_err/n);
00307 loglikelihood = sum_loglh;
00308 }
00309
00310 void KinematicGraph::evaluate(
00311 std::vector<double> stamps,
00312 KinematicParams ¶ms,KinematicData &data) {
00313
00314 static MultiModelFactory factory;
00315 for(KinematicGraph::iterator it=begin();it!=end();it++) {
00316 it->second = factory.restoreModel(it->second->getModel());
00317 }
00318
00319 BIC = DBL_MAX;
00320 avg_pos_err = DBL_MAX;
00321 avg_orient_err = DBL_MAX;
00322 loglh = DBL_MIN;
00323
00324 if (size()==0) return;
00325
00326 if(DOF != getNominalDOFs())
00327 projectConfigurationSpace(DOF,stamps,params,data);
00328
00329
00330
00331 double sum_pos2_err = 0;
00332 double sum_orient2_err = 0;
00333 double sum_loglh = 0;
00334
00335 double pos_err,orient_err;
00336
00337 data.stampedMarkerProjected.clear();
00338 for(size_t i=0;i<stamps.size();i++) {
00339 evaluateSingleStamp(stamps[i],pos_err, orient_err, loglh,params,data );
00340 sum_loglh += loglh;
00341 sum_pos2_err += SQR(pos_err);
00342 sum_orient2_err += SQR(orient_err);
00343 }
00344
00345 avg_pos_err = sqrt(sum_pos2_err/stamps.size());
00346 avg_orient_err = sqrt(orient_err/stamps.size());
00347 loglh = sum_loglh;
00348
00349 k = getNumberOfParameters();
00350 int k_pca = 0;
00351 double loglh_pca;
00352 if(DOF != getNominalDOFs()) {
00353 k_pca = getNominalDOFs() * DOF;
00354 loglh_pca = stamps.size() * (getNominalDOFs() - DOF) * log(stamps.size());
00355 }
00356 BIC = getBIC( loglh + loglh_pca, k + k_pca,stamps.size() );
00357
00358 return;
00359 }
00360
00361 void KinematicGraph::projectConfigurationSpace(int reducedDOFs,std::vector<double> stamps, KinematicParams ¶ms,KinematicData &data) {
00362 if(reducedDOFs == 0) return;
00363 if(stamps.size() == 0) return;
00364
00365 map< GenericModelPtr, int> DOFoffsets;
00366 int DOFs = 0;
00367 for(KinematicGraph::iterator it=begin(); it != end();it++) {
00368 DOFoffsets[it->second] = DOFs;
00369 DOFs += it->second->getDOFs();
00370 }
00371 if(DOFs==0) return;
00372
00373 MatrixXf X_trans(stamps.size(), DOFs);
00374
00375 for(KinematicGraph::iterator it=begin(); it != end();it++) {
00376 GenericModelPtr model = it->second;
00377 int DOFoffset = DOFoffsets[model];
00378
00379 if(model->getDOFs()==0) continue;
00380
00381 for(size_t timestamp_idx = 0;timestamp_idx < stamps.size();timestamp_idx++) {
00382 int idx = data.poseIndex[ it->first.first ][it->first.second][ stamps[timestamp_idx]];
00383
00384 VectorXd c = model->getConfiguration(idx);
00385 for(size_t d=0;d< model->getDOFs();d++) {
00386 X_trans( timestamp_idx,DOFoffset + d ) = c(d);
00387 }
00388 }
00389 }
00390
00391 VectorXf X_mean = VectorXf::Zero(DOFs,1);
00392 for( size_t i=0;i< stamps.size();i++) {
00393 for( int j=0;j< DOFs;j++) {
00394 X_mean(j) += X_trans(i,j);
00395 }
00396 }
00397 X_mean /= stamps.size();
00398
00399
00400
00401 for( int j=0;j< DOFs;j++) {
00402 if(isnan(X_mean(j))) {
00403 cout << X_trans << endl<<endl;
00404 cout << X_mean << endl;
00405 cout <<"reducing DOFs failed, NaN value"<<endl;
00406 return;
00407 }
00408 if(fabs(X_mean(j))>100) {
00409 cout << X_trans << endl<<endl;
00410 cout << X_mean << endl;
00411 cout <<"reducing DOFs failed, large value"<<endl;
00412 return;
00413 }
00414 }
00415
00416 MatrixXf X_center(stamps.size(), DOFs);
00417 for( size_t i=0;i< stamps.size();i++) {
00418 for( int j=0;j< DOFs;j++) {
00419 X_center(i,j) = X_trans(i,j) - X_mean(j);
00420 }
00421 }
00422
00423 if(stamps.size() < (size_t)DOFs) return;
00424 SVD<MatrixXf> svdOfA(X_center);
00425 const Eigen::MatrixXf U = svdOfA.matrixU();
00426 const Eigen::MatrixXf V = svdOfA.matrixV();
00427 const Eigen::VectorXf S = svdOfA.singularValues();
00428
00429
00430 Eigen::MatrixXf V_projection = V.block(0,0,DOFs,reducedDOFs);
00431 MatrixXf X_reduced(stamps.size(),reducedDOFs);
00432
00433 for( size_t i=0;i< stamps.size();i++) {
00434 for( int k=0;k< reducedDOFs;k++) {
00435 X_reduced(i,k) = 0.0;
00436 for( int j=0;j< DOFs;j++) {
00437 X_reduced(i,k) += V(j,k) * X_center(i,j);
00438 }
00439 }
00440 }
00441
00442 MatrixXf X_projected(stamps.size(),DOFs);
00443 for( size_t i=0;i< stamps.size();i++) {
00444 for( int j=0;j< DOFs;j++) {
00445 X_projected(i,j) = X_mean(j);
00446 for( int k=0;k< reducedDOFs;k++) {
00447 X_projected(i,j) += V(j,k) * X_reduced(i,k);
00448 }
00449 }
00450 }
00451
00452 for(KinematicGraph::iterator it=begin(); it != end();it++) {
00453 GenericModelPtr model = it->second;
00454 if(model->getDOFs()==0) continue;
00455 int DOFoffset = DOFoffsets[model];
00456
00457 for(size_t timestamp_idx = 0;timestamp_idx < stamps.size();timestamp_idx++) {
00458 int idx = data.poseIndex[ it->first.first ][it->first.second][ stamps[timestamp_idx]];
00459
00460 VectorXd c(model->getDOFs());
00461 for(size_t d=0;d< model->getDOFs();d++) {
00462 c(d) =X_projected( timestamp_idx,DOFoffset + d );
00463 }
00464
00465 model->setConfiguration(idx,c);
00466 model->model.track.pose_projected[idx] = model->predictPose( c );
00467 }
00468 }
00469 DOF = reducedDOFs;
00470 }
00471
00472 #include "boost/tuple/tuple.hpp"
00473
00474 int KinematicGraph::distanceTo(KinematicGraph &other) {
00475 int distance = 0;
00476 distance +=fabs((getNominalDOFs()-DOF) - (other.getNominalDOFs()-other.DOF));
00477
00478
00479 set< pair<int,int> > my_edges,other_edges,diff_edges;
00480 for(KinematicGraph::iterator it=begin();it!=end();it++) my_edges.insert( pair<int,int>(it->first.first,it->first.second) );
00481 for(KinematicGraph::iterator it = other.begin();it!=other.end();it++) other_edges.insert(pair<int,int>(it->first.first,it->first.second) );
00482 set_symmetric_difference(my_edges.begin(),my_edges.end(),other_edges.begin(),other_edges.end(),insert_iterator<set< pair<int,int> > >(diff_edges,diff_edges.begin()) );
00483 distance += diff_edges.size();
00484
00485
00486 set< pair<pair<int,int>,string> > my_models,other_models,intersec_models,diff_models;
00487 for(KinematicGraph::iterator it=begin();it!=end();it++)
00488 if(diff_edges.find(it->first)==diff_edges.end())
00489 my_models.insert( pair<pair<int,int>,string>(pair<int,int>(it->first.first,it->first.second),it->second->getModelName()) );
00490 for(KinematicGraph::iterator it = other.begin();it!=other.end();it++)
00491 if(diff_edges.find(it->first)==diff_edges.end())
00492 other_models.insert(pair<pair<int,int>,string>(pair<int,int>(it->first.first,it->first.second),it->second->getModelName()) );
00493 set_symmetric_difference(my_models.begin(),my_models.end(),other_models.begin(),other_models.end(),insert_iterator<set< pair<pair<int,int>,string> > >(diff_models,diff_models.begin()) );
00494 distance += diff_models.size()/2;
00495
00496 return distance;
00497 }