diff --git a/src/problem/problem.cpp b/src/problem/problem.cpp index b0052f8066b04250051d912727797fdb20569d40..9796de853c787ec17f31ab3384e9ab32e1b9837c 100644 --- a/src/problem/problem.cpp +++ b/src/problem/problem.cpp @@ -199,7 +199,7 @@ ProcessorBasePtr Problem::installProcessor(const std::string& _prc_type, // { SensorBasePtr sen_ptr = getSensor(_corresponding_sensor_name); if (sen_ptr == nullptr) - throw std::runtime_error("Sensor not found. Cannot bind Processor."); + throw std::runtime_error("Cannot bind processor. Reason: Sensor \"" + _corresponding_sensor_name + "\" not found. Check sensor name, in must match in sensor and processor!"); if (_params_filename == "") return installProcessor(_prc_type, _unique_processor_name, sen_ptr, nullptr); else @@ -217,7 +217,7 @@ ProcessorBasePtr Problem::installProcessor(const std::string& _prc_type, // { SensorBasePtr sen_ptr = getSensor(_corresponding_sensor_name); if (sen_ptr == nullptr) - throw std::runtime_error("Sensor not found. Cannot bind Processor."); + throw std::runtime_error("Cannot bind processor. Reason: Sensor \"" + _corresponding_sensor_name + "\" not found. Check sensor name, in must match in sensor and processor!"); ProcessorBasePtr prc_ptr = AutoConfProcessorFactory::get().create(uppercase(_prc_type), _unique_processor_name, _server, sen_ptr); prc_ptr->configure(sen_ptr); prc_ptr->link(sen_ptr); @@ -813,7 +813,7 @@ void Problem::print(int depth, bool constr_by, bool metric, bool state_blocks) // Sensors ======================================================================================= for (auto S : getHardware()->getSensorList()) { - cout << " S" << S->id() << " " << S->getType(); + cout << " S" << S->id() << " " << S->getType() << " \"" << S->getName() << "\""; if (!metric && !state_blocks) cout << (S->isExtrinsicDynamic() ? " [Dyn," : " [Sta,") << (S->isIntrinsicDynamic() ? "Dyn]" : "Sta]"); if (depth < 2) cout << " -- " << S->getProcessorList().size() << "p"; @@ -860,7 +860,7 @@ void Problem::print(int depth, bool constr_by, bool metric, bool state_blocks) { if (p->isMotion()) { - std::cout << " pm" << p->id() << " " << p->getType() << endl; + std::cout << " pm" << p->id() << " " << p->getType() << " \"" << p->getName() << "\"" << endl; ProcessorMotionPtr pm = std::static_pointer_cast<ProcessorMotion>(p); if (pm->getOrigin()) cout << " o: C" << pm->getOrigin()->id() << " - " << (pm->getOrigin()->getFrame()->isKeyOrAux() ? (pm->getOrigin()->getFrame()->isKey() ? " KF" : " AuxF" ) : " F") @@ -873,17 +873,10 @@ void Problem::print(int depth, bool constr_by, bool metric, bool state_blocks) } else { - cout << " pt" << p->id() << " " << p->getType() << endl; + cout << " pt" << p->id() << " " << p->getType() << " \"" << p->getName() << "\"" << endl; ProcessorTrackerPtr pt = std::dynamic_pointer_cast<ProcessorTracker>(p); if (pt) { -// ProcessorTrackerFeatureTrifocalPtr ptt = std::dynamic_pointer_cast<ProcessorTrackerFeatureTrifocal>(pt); -// if (ptt) -// { -// if (ptt->getPrevOrigin()) -// cout << " p: C" << ptt->getPrevOrigin()->id() << " - " << (ptt->getPrevOrigin()->getFrame()->isEstimated() ? (ptt->getPrevOrigin()->getFrame()->isKey() ? " KF" : " AuxF") : " F") -// << ptt->getPrevOrigin()->getFrame()->id() << endl; -// } if (pt->getOrigin()) cout << " o: C" << pt->getOrigin()->id() << " - " << (pt->getOrigin()->getFrame()->isKeyOrAux() ? (pt->getOrigin()->getFrame()->isKey() ? " KF" : " AuxF") : " F") << pt->getOrigin()->getFrame()->id() << endl;