DataLogger.cpp
Go to the documentation of this file.
00001 // -*- C++ -*-
00010 #include "hrpsys/util/Hrpsys.h"
00011 #include "hrpsys/idl/pointcloud.hh"
00012 #include "hrpsys/idl/RobotHardwareService.hh"
00013 #include "DataLogger.h"
00014 
00015 
00016 typedef coil::Guard<coil::Mutex> Guard;
00017 
00018 // Module specification
00019 // <rtc-template block="module_spec">
00020 static const char* nullcomponent_spec[] =
00021   {
00022     "implementation_id", "DataLogger",
00023     "type_name",         "DataLogger",
00024     "description",       "data logger component",
00025     "version",           HRPSYS_PACKAGE_VERSION,
00026     "vendor",            "AIST",
00027     "category",          "example",
00028     "activity_type",     "DataFlowComponent",
00029     "max_instance",      "10",
00030     "language",          "C++",
00031     "lang_type",         "compile",
00032     // Configuration variables
00033     "conf.default.log_precision", "0",
00034     ""
00035   };
00036 // </rtc-template>
00037 
00038 #define LOG_SET_PRECISION(strm)                                         \
00039     int prc;                                                            \
00040     if (precision != 0) {                                               \
00041         prc = os.precision();                                           \
00042         os << std::scientific << std::setprecision(precision);          \
00043     }                                                                   \
00044 
00045 #define LOG_UNSET_PRECISION(strm)                                       \
00046     if (precision != 0)                                                 \
00047         os << std::fixed << std::setprecision(prc);                     \
00048 
00049 void printData(std::ostream& os, const RTC::Acceleration3D& data, unsigned int precision = 0)
00050 {
00051     LOG_SET_PRECISION(os);
00052     os << data.ax << " " << data.ay << " " << data.az << " ";
00053     LOG_UNSET_PRECISION(os);
00054 }
00055 
00056 void printData(std::ostream& os, const RTC::Velocity2D& data, unsigned int precision = 0)
00057 {
00058     LOG_SET_PRECISION(os);
00059     os << data.vx << " " << data.vy << " " << data.va << " ";
00060     LOG_UNSET_PRECISION(os);
00061 }
00062 
00063 void printData(std::ostream& os, const RTC::Pose3D& data, unsigned int precision = 0)
00064 {
00065     LOG_SET_PRECISION(os);
00066     os << data.position.x << " " << data.position.y << " " 
00067        << data.position.z << " " << data.orientation.r << " "
00068        << data.orientation.p << " " << data.orientation.y << " ";
00069     LOG_UNSET_PRECISION(os);
00070 }
00071 
00072 void printData(std::ostream& os, const RTC::AngularVelocity3D& data, unsigned int precision = 0)
00073 {
00074     LOG_SET_PRECISION(os);
00075     os << data.avx << " " << data.avy << " " << data.avz << " ";
00076     LOG_UNSET_PRECISION(os);
00077 }
00078 
00079 void printData(std::ostream& os, const RTC::Point3D& data, unsigned int precision = 0)
00080 {
00081     LOG_SET_PRECISION(os);
00082     os << data.x << " " << data.y << " " << data.z << " ";
00083     LOG_UNSET_PRECISION(os);
00084 }
00085 
00086 void printData(std::ostream& os, const RTC::Vector3D& data, unsigned int precision = 0)
00087 {
00088     LOG_SET_PRECISION(os);
00089     os << data.x << " " << data.y << " " << data.z << " ";
00090     LOG_UNSET_PRECISION(os);
00091 }
00092 
00093 void printData(std::ostream& os, const RTC::Orientation3D& data, unsigned int precision = 0)
00094 {
00095     LOG_SET_PRECISION(os);
00096     os << data.r << " " << data.p << " " << data.y << " ";
00097     LOG_UNSET_PRECISION(os);
00098 }
00099 
00100 void printData(std::ostream& os, const PointCloudTypes::PointCloud& data, unsigned int precision = 0)
00101 {
00102   uint npoint = data.data.length()/data.point_step;
00103   os << data.width << " " << data.height << " " << data.type << " " << npoint;
00104   float *ptr = (float *)data.data.get_buffer();
00105   std::string type(data.type);
00106   if (type != "xyz" && type != "xyzrgb"){
00107     std::cerr << "point cloud type(" << type << ") is not supported" 
00108               << std::endl;
00109     return;
00110   } 
00111   for (uint i=0; i<npoint ;i++){
00112     os << " " << *ptr++ << " " << *ptr++ << " " << *ptr++;
00113     if (type == "xyzrgb"){
00114       unsigned char *rgb = (unsigned char *)ptr;
00115       os << " " << (int)rgb[0] << " " << (int)rgb[1] << " " << (int)rgb[2];
00116       ptr++;
00117     }
00118   }
00119 } 
00120 
00121 template<class T>
00122 std::ostream& operator<<(std::ostream& os, const _CORBA_Unbounded_Sequence<T > & data)
00123 {
00124   for (unsigned int j=0; j<data.length(); j++){
00125     os << data[j] << " ";
00126   }
00127   return os;
00128 }
00129 
00130 std::ostream& operator<<(std::ostream& os, const OpenHRP::RobotHardwareService::DblSequence6 & data)
00131 {
00132   for (unsigned int j=0; j<data.length(); j++){
00133     os << data[j] << " ";
00134   }
00135   return os;
00136 }
00137 
00138 std::ostream& operator<<(std::ostream& os, const OpenHRP::RobotHardwareService::DblSequence3 & data)
00139 {
00140   for (unsigned int j=0; j<data.length(); j++){
00141     os << data[j] << " ";
00142   }
00143   return os;
00144 }
00145 
00146 std::ostream& operator<<(std::ostream& os, const OpenHRP::RobotHardwareService::BatteryState & data)
00147 {
00148   os << data.voltage << " " << data.current << " " << data.soc << " ";
00149   return os;
00150 }
00151 
00152 template <class T>
00153 void printData(std::ostream& os, const T& data, unsigned int precision = 0)
00154 {
00155     LOG_SET_PRECISION(os);
00156     for (unsigned int j=0; j<data.length(); j++){
00157         os << data[j] << " ";
00158     }
00159     LOG_UNSET_PRECISION(os);
00160 }
00161 
00162 void printData(std::ostream& os, double data, unsigned int precision = 0)
00163 {
00164     LOG_SET_PRECISION(os);
00165     os << data << " ";
00166     LOG_UNSET_PRECISION(os);
00167 }
00168 
00169 void printData(std::ostream& os, const OpenHRP::RobotHardwareService::RobotState2& data, unsigned int precision = 0)
00170 {
00171   printData(os, data.angle, precision);
00172   printData(os, data.command, precision);
00173   printData(os, data.torque, precision);
00174   printData(os, data.servoState, precision);
00175   printData(os, data.force, precision);
00176   printData(os, data.rateGyro, precision);
00177   printData(os, data.accel, precision);
00178   printData(os, data.batteries, precision);
00179   printData(os, data.voltage, precision);
00180   printData(os, data.current, precision);
00181   printData(os, data.temperature, precision);
00182 }
00183 
00184 template <class T>
00185 class LoggerPort : public LoggerPortBase
00186 {
00187 public:
00188     LoggerPort(const char *name) : m_port(name, m_data) {}
00189     const char *name(){
00190         return m_port.name();
00191     }
00192     virtual void dumpLog(std::ostream& os, unsigned int precision = 0){
00193         os.setf(std::ios::fixed, std::ios::floatfield);
00194         for (unsigned int i=0; i<m_log.size(); i++){
00195             printLog(os, m_log[i], precision);
00196         }
00197     }
00198     void printLog(std::ostream& os, T &data, unsigned int precision = 0){
00199         os << std::setprecision(6) << (data.tm.sec + data.tm.nsec/1e9) << " ";
00200         // data
00201         printData(os, data.data, precision);
00202         os << std::endl;
00203     }
00204     InPort<T>& port(){
00205             return m_port;
00206     }
00207     void log(){
00208         if (m_port.isNew()){
00209             m_port.read();
00210             m_log.push_back(m_data);
00211             while (m_log.size() > m_maxLength){
00212                 m_log.pop_front();
00213             }
00214         }
00215     }
00216     void clear(){
00217         m_log.clear();
00218     }
00219 protected:
00220     InPort<T> m_port;
00221     T m_data;
00222     std::deque<T> m_log;
00223 };
00224 
00225 class LoggerPortForPointCloud : public LoggerPort<PointCloudTypes::PointCloud>
00226 {
00227 public:
00228     LoggerPortForPointCloud(const char *name) : LoggerPort<PointCloudTypes::PointCloud>(name) {}
00229     void dumpLog(std::ostream& os, unsigned int precision = 0){
00230         os.setf(std::ios::fixed, std::ios::floatfield);
00231         for (unsigned int i=0; i<m_log.size(); i++){
00232             // time
00233             os << std::setprecision(6) << (m_log[i].tm.sec + m_log[i].tm.nsec/1e9) << " ";
00234             // data
00235             printData(os, m_log[i], precision);
00236             os << std::endl;
00237         }
00238     }
00239 };
00240 
00241 DataLogger::DataLogger(RTC::Manager* manager)
00242   : RTC::DataFlowComponentBase(manager),
00243     // <rtc-template block="initializer">
00244     m_emergencySignalIn("emergencySignal", m_emergencySignal),
00245     m_DataLoggerServicePort("DataLoggerService"),
00246     // </rtc-template>
00247     m_suspendFlag(false),
00248     m_log_precision(0),
00249         dummy(0)
00250 {
00251   m_service0.setLogger(this);
00252 }
00253 
00254 DataLogger::~DataLogger()
00255 {
00256 }
00257 
00258 
00259 
00260 RTC::ReturnCode_t DataLogger::onInitialize()
00261 {
00262   std::cerr << "[" << m_profile.instance_name << "] onInitialize()" << std::endl;
00263   bindParameter("log_precision", m_log_precision, "0");
00264 
00265   // Registration: InPort/OutPort/Service
00266   // <rtc-template block="registration">
00267   // Set InPort buffers
00268   addInPort("emergencySignal", m_emergencySignalIn);
00269 
00270   // Set OutPort buffer
00271   
00272   // Set service provider to Ports
00273   m_DataLoggerServicePort.registerProvider("service0", "DataLoggerService", m_service0);
00274   
00275   // Set service consumers to Ports
00276   
00277   // Set CORBA Service Ports
00278   addPort(m_DataLoggerServicePort);
00279   
00280   // </rtc-template>
00281   // <rtc-template block="bind_config">
00282   // Bind variables and configuration variable
00283   
00284   // </rtc-template>
00285 
00286   return RTC::RTC_OK;
00287 }
00288 
00289 
00290 
00291 /*
00292 RTC::ReturnCode_t DataLogger::onFinalize()
00293 {
00294   return RTC::RTC_OK;
00295 }
00296 */
00297 
00298 /*
00299 RTC::ReturnCode_t DataLogger::onStartup(RTC::UniqueId ec_id)
00300 {
00301   return RTC::RTC_OK;
00302 }
00303 */
00304 
00305 /*
00306 RTC::ReturnCode_t DataLogger::onShutdown(RTC::UniqueId ec_id)
00307 {
00308   return RTC::RTC_OK;
00309 }
00310 */
00311 
00312 RTC::ReturnCode_t DataLogger::onActivated(RTC::UniqueId ec_id)
00313 {
00314   return RTC::RTC_OK;
00315 }
00316 
00317 RTC::ReturnCode_t DataLogger::onDeactivated(RTC::UniqueId ec_id)
00318 {
00319   return RTC::RTC_OK;
00320 }
00321 
00322 RTC::ReturnCode_t DataLogger::onExecute(RTC::UniqueId ec_id)
00323 {
00324   if (ec_id == 0){
00325     if (m_emergencySignalIn.isNew()){
00326         m_emergencySignalIn.read();
00327         time_t sec = time(NULL);
00328         struct tm *tm_ = localtime(&sec);
00329         char date[20];
00330         strftime(date,20, "%Y-%m-%d", tm_);
00331         char basename[30];
00332         sprintf(basename, "emglog-%s-%02d%02d",
00333                 date, tm_->tm_hour, tm_->tm_min);
00334         std::cout << "received emergency signal. saving log files("
00335                   << basename << ")" << std::endl;
00336         save(basename);
00337         while (m_emergencySignalIn.isNew()){
00338             m_emergencySignalIn.read();
00339         }
00340     }
00341   }else{
00342     Guard guard(m_suspendFlagMutex);
00343     
00344     if (m_suspendFlag) return RTC::RTC_OK;
00345     
00346     for (unsigned int i=0; i<m_ports.size(); i++){
00347       m_ports[i]->log();
00348     }
00349   }
00350   return RTC::RTC_OK;
00351 }
00352 
00353 /*
00354 RTC::ReturnCode_t DataLogger::onAborting(RTC::UniqueId ec_id)
00355 {
00356   return RTC::RTC_OK;
00357 }
00358 */
00359 
00360 /*
00361 RTC::ReturnCode_t DataLogger::onError(RTC::UniqueId ec_id)
00362 {
00363   return RTC::RTC_OK;
00364 }
00365 */
00366 
00367 /*
00368 RTC::ReturnCode_t DataLogger::onReset(RTC::UniqueId ec_id)
00369 {
00370   return RTC::RTC_OK;
00371 }
00372 */
00373 
00374 /*
00375 RTC::ReturnCode_t DataLogger::onStateUpdate(RTC::UniqueId ec_id)
00376 {
00377   return RTC::RTC_OK;
00378 }
00379 */
00380 
00381 /*
00382 RTC::ReturnCode_t DataLogger::onRateChanged(RTC::UniqueId ec_id)
00383 {
00384   return RTC::RTC_OK;
00385 }
00386 */
00387 
00388 bool DataLogger::add(const char *i_type, const char *i_name)
00389 {
00390   suspendLogging();
00391   for (unsigned int i=0; i<m_ports.size(); i++){
00392       if (strcmp(m_ports[i]->name(),i_name) == 0){
00393           std::cerr << "Logger port named \"" << i_name << "\" already exists"
00394                     << std::endl;
00395           resumeLogging();
00396           return false;
00397       }
00398   }  
00399 
00400   LoggerPortBase *new_port=NULL;
00401   if (strcmp(i_type, "TimedDoubleSeq")==0){
00402       LoggerPort<TimedDoubleSeq> *lp = new LoggerPort<TimedDoubleSeq>(i_name);
00403       new_port = lp;
00404       if (!addInPort(i_name, lp->port())) {
00405           resumeLogging();
00406           return false;
00407       }
00408   }else if (strcmp(i_type, "TimedLongSeq")==0){
00409       LoggerPort<TimedLongSeq> *lp = new LoggerPort<TimedLongSeq>(i_name);
00410       new_port = lp;
00411       if (!addInPort(i_name, lp->port())) {
00412           resumeLogging();
00413           return false;
00414       }
00415   }else if (strcmp(i_type, "TimedBooleanSeq")==0){
00416       LoggerPort<TimedBooleanSeq> *lp = new LoggerPort<TimedBooleanSeq>(i_name);
00417       new_port = lp;
00418       if (!addInPort(i_name, lp->port())) {
00419           resumeLogging();
00420           return false;
00421       }
00422   }else if (strcmp(i_type, "TimedLongSeqSeq")==0){
00423       LoggerPort<OpenHRP::TimedLongSeqSeq> *lp = new LoggerPort<OpenHRP::TimedLongSeqSeq>(i_name);
00424       new_port = lp;
00425       if (!addInPort(i_name, lp->port())) {
00426           resumeLogging();
00427           return false;
00428       }
00429   }else if (strcmp(i_type, "TimedPoint3D")==0){
00430       LoggerPort<TimedPoint3D> *lp = new LoggerPort<TimedPoint3D>(i_name);
00431       new_port = lp;
00432       if (!addInPort(i_name, lp->port())) {
00433           resumeLogging();
00434           return false;
00435       }
00436   }else if (strcmp(i_type, "TimedVector3D")==0){
00437       LoggerPort<TimedVector3D> *lp = new LoggerPort<TimedVector3D>(i_name);
00438       new_port = lp;
00439       if (!addInPort(i_name, lp->port())) {
00440           resumeLogging();
00441           return false;
00442       }
00443   }else if (strcmp(i_type, "TimedOrientation3D")==0){
00444       LoggerPort<TimedOrientation3D> *lp = new LoggerPort<TimedOrientation3D>(i_name);
00445       new_port = lp;
00446       if (!addInPort(i_name, lp->port())) {
00447           resumeLogging();
00448           return false;
00449       }
00450   }else if (strcmp(i_type, "TimedAcceleration3D")==0){
00451       LoggerPort<TimedAcceleration3D> *lp = new LoggerPort<TimedAcceleration3D>(i_name);
00452       new_port = lp;
00453       if (!addInPort(i_name, lp->port())) {
00454           resumeLogging();
00455           return false;
00456       }
00457   }else if (strcmp(i_type, "TimedAngularVelocity3D")==0){
00458       LoggerPort<TimedAngularVelocity3D> *lp = new LoggerPort<TimedAngularVelocity3D>(i_name);
00459       new_port = lp;
00460       if (!addInPort(i_name, lp->port())) {
00461           resumeLogging();
00462           return false;
00463       }
00464   }else if (strcmp(i_type, "TimedVelocity2D")==0){
00465       LoggerPort<TimedVelocity2D> *lp = new LoggerPort<TimedVelocity2D>(i_name);
00466       new_port = lp;
00467       if (!addInPort(i_name, lp->port())) {
00468           resumeLogging();
00469           return false;
00470       }
00471   }else if (strcmp(i_type, "TimedPose3D")==0){
00472       LoggerPort<TimedPose3D> *lp = new LoggerPort<TimedPose3D>(i_name);
00473       new_port = lp;
00474       if (!addInPort(i_name, lp->port())) {
00475           resumeLogging();
00476           return false;
00477       }
00478   }else if (strcmp(i_type, "PointCloud")==0){
00479     LoggerPort<PointCloudTypes::PointCloud> *lp = new LoggerPortForPointCloud(i_name);
00480       new_port = lp;
00481       if (!addInPort(i_name, lp->port())) {
00482           resumeLogging();
00483           return false;
00484       }
00485   }else if (strcmp(i_type, "TimedRobotState2")==0){
00486     LoggerPort<OpenHRP::RobotHardwareService::TimedRobotState2> *lp = new LoggerPort<OpenHRP::RobotHardwareService::TimedRobotState2>(i_name);
00487     new_port = lp;
00488     if (!addInPort(i_name, lp->port())) {
00489         resumeLogging();
00490         return false;
00491     }
00492   }else{
00493       std::cout << "DataLogger: unsupported data type(" << i_type << ")"
00494                 << std::endl;
00495       resumeLogging();
00496       return false;
00497   }
00498   m_ports.push_back(new_port);
00499   resumeLogging();
00500   return true;
00501 }
00502 
00503 bool DataLogger::save(const char *i_basename)
00504 {
00505   suspendLogging();
00506   bool ret = true;
00507   for (unsigned int i=0; i<m_ports.size(); i++){
00508     std::string fname = i_basename;
00509     fname.append(".");
00510     fname.append(m_ports[i]->name());
00511     std::ofstream ofs(fname.c_str());
00512     if (ofs.is_open()){
00513       m_ports[i]->dumpLog(ofs, m_log_precision);
00514     }else{
00515       std::cerr << "[" << m_profile.instance_name << "] failed to open(" << fname << ")" << std::endl;
00516       ret = false;
00517     }
00518   }
00519   if (ret) std::cerr << "[" << m_profile.instance_name << "] Save log to " << i_basename << ".*" << std::endl;
00520   resumeLogging();
00521   return ret;
00522 }
00523 
00524 bool DataLogger::clear()
00525 {
00526   suspendLogging();
00527   for (unsigned int i=0; i<m_ports.size(); i++){
00528     m_ports[i]->clear();
00529   }
00530   std::cerr << "[" << m_profile.instance_name << "] Log cleared" << std::endl;
00531   resumeLogging();
00532   return true;
00533 }
00534 
00535 void DataLogger::suspendLogging()
00536 {
00537   Guard guard(m_suspendFlagMutex);
00538   m_suspendFlag = true;
00539 }
00540 
00541 void DataLogger::resumeLogging()
00542 {
00543   Guard guard(m_suspendFlagMutex);
00544   m_suspendFlag = false;
00545 }
00546 
00547 void DataLogger::maxLength(unsigned int len)
00548 {
00549   suspendLogging();
00550   for (unsigned int i=0; i<m_ports.size(); i++){
00551     m_ports[i]->maxLength(len);
00552   }
00553   std::cerr << "[" << m_profile.instance_name << "] Log max length is set to " << len << std::endl;
00554   resumeLogging();
00555 }
00556 
00557 extern "C"
00558 {
00559 
00560   void DataLoggerInit(RTC::Manager* manager)
00561   {
00562     RTC::Properties profile(nullcomponent_spec);
00563     manager->registerFactory(profile,
00564                              RTC::Create<DataLogger>,
00565                              RTC::Delete<DataLogger>);
00566   }
00567 
00568 };
00569 
00570 


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Wed May 15 2019 05:02:17