Go to the documentation of this file.00001 #ifndef OBJECTTURNAROUNDDETECTOR_H
00002 #define OBJECTTURNAROUNDDETECTOR_H
00003
00004 #include "RatsMatrix.h"
00005 #include "../TorqueFilter/IIRFilter.h"
00006 #include <boost/shared_ptr.hpp>
00007 #include <iostream>
00008 #include <cmath>
00009 #include "hrpsys/util/Hrpsys.h"
00010
00011 class ObjectTurnaroundDetector
00012 {
00013 public:
00014 typedef enum {MODE_IDLE, MODE_STARTED, MODE_DETECTED, MODE_MAX_TIME} process_mode;
00015 typedef enum {TOTAL_FORCE, TOTAL_MOMENT} detector_total_wrench;
00016 private:
00017 boost::shared_ptr<FirstOrderLowPassFilter<double> > wrench_filter;
00018 boost::shared_ptr<FirstOrderLowPassFilter<double> > dwrench_filter;
00019 hrp::Vector3 axis, moment_center;
00020 double prev_wrench, dt;
00021 double detect_ratio_thre, start_ratio_thre, ref_dwrench, max_time, current_time, current_wrench;
00022 size_t count;
00023
00024
00025
00026 size_t detect_count_thre, start_count_thre;
00027 process_mode pmode;
00028 detector_total_wrench dtw;
00029 std::string print_str;
00030 bool is_dwr_changed;
00031 public:
00032 ObjectTurnaroundDetector (const double _dt) : axis(-1*hrp::Vector3::UnitZ()), moment_center(hrp::Vector3::Zero()), prev_wrench(0.0), dt(_dt), detect_ratio_thre(0.01), start_ratio_thre(0.5),
00033 count(0), detect_count_thre(5), start_count_thre(5), pmode(MODE_IDLE), dtw(TOTAL_FORCE), is_dwr_changed(false)
00034 {
00035 double default_cutoff_freq = 1;
00036 wrench_filter = boost::shared_ptr<FirstOrderLowPassFilter<double> >(new FirstOrderLowPassFilter<double>(default_cutoff_freq, _dt, 0));
00037 dwrench_filter = boost::shared_ptr<FirstOrderLowPassFilter<double> >(new FirstOrderLowPassFilter<double>(default_cutoff_freq, _dt, 0));
00038 };
00039 ~ObjectTurnaroundDetector () {};
00040 void startDetection (const double _ref_diff_wrench, const double _max_time)
00041 {
00042 ref_dwrench = _ref_diff_wrench/_max_time;
00043 max_time = _max_time;
00044 current_time = 0;
00045 count = 0;
00046 std::cerr << "[" << print_str << "] Start Object Turnaround Detection (ref_dwrench = " << ref_dwrench
00047 << ", detect_thre = " << detect_ratio_thre * ref_dwrench << ", start_thre = " << start_ratio_thre * ref_dwrench << "), max_time = " << max_time << "[s]" << std::endl;
00048 pmode = MODE_IDLE;
00049 };
00050 double calcTotalForce (const std::vector<hrp::Vector3>& fmv)
00051 {
00052 hrp::Vector3 tmpv = hrp::Vector3::Zero();
00053 for (size_t i = 0; i < fmv.size(); i++) {
00054 tmpv += fmv[i];
00055 }
00056 return axis.dot(tmpv);
00057 };
00058 double calcTotalMoment (const std::vector<hrp::Vector3>& fmv, const std::vector<hrp::Vector3>& hposv)
00059 {
00060 hrp::Vector3 tmpv = hrp::Vector3::Zero();
00061 for (size_t i = 0; i < fmv.size(); i++) {
00062 tmpv += (hposv[i]-moment_center).cross(fmv[i]);
00063 }
00064 return axis.dot(tmpv);
00065 };
00066 bool checkDetection (const std::vector<hrp::Vector3>& fmv, const std::vector<hrp::Vector3>& hposv)
00067 {
00068 switch(dtw) {
00069 case TOTAL_FORCE:
00070 checkDetection(calcTotalForce(fmv));
00071 break;
00072 case TOTAL_MOMENT:
00073 checkDetection(calcTotalMoment(fmv, hposv));
00074 break;
00075 default:
00076 break;
00077 };
00078 };
00079 bool checkDetection (const double wrench_value)
00080 {
00081 if (is_dwr_changed) {
00082 wrench_filter->reset(wrench_value);
00083 dwrench_filter->reset(0);
00084 is_dwr_changed = false;
00085 }
00086 current_wrench = wrench_value;
00087 double tmp_wr = wrench_filter->passFilter(wrench_value);
00088 double tmp_dwr = dwrench_filter->passFilter((tmp_wr-prev_wrench)/dt);
00089 prev_wrench = tmp_wr;
00090 switch (pmode) {
00091 case MODE_IDLE:
00092 if (tmp_dwr > ref_dwrench*start_ratio_thre) {
00093 count++;
00094 if (count > start_count_thre) {
00095 pmode = MODE_STARTED;
00096 count = 0;
00097 std::cerr << "[" << print_str << "] Object Turnaround Detection Started. (" << start_count_thre*dt << "[s] after the first start detection)" << std::endl;
00098 }
00099 } else {
00100
00101 }
00102 break;
00103 case MODE_STARTED:
00104 if (tmp_dwr < ref_dwrench*detect_ratio_thre) {
00105 count++;
00106 if (count > detect_count_thre) {
00107 pmode = MODE_DETECTED;
00108 std::cerr << "[" << print_str << "] Object Turnaround Detected (time = " << current_time << "[s], " << detect_count_thre*dt << "[s] after the first detection)" << std::endl;
00109 }
00110 } else {
00111
00112 }
00113
00114 break;
00115 case MODE_DETECTED:
00116 break;
00117 case MODE_MAX_TIME:
00118 break;
00119 default:
00120 break;
00121 }
00122 if (max_time <= current_time && (pmode != MODE_DETECTED)) {
00123 if (pmode != MODE_MAX_TIME) std::cerr << "[" << print_str << "] Object Turnaround Detection max time reached." << std::endl;
00124 pmode = MODE_MAX_TIME;
00125 }
00126 current_time += dt;
00127 return isDetected();
00128 };
00129 bool isDetected () const { return (pmode == MODE_DETECTED); };
00130 process_mode getMode () const { return pmode; };
00131 void printParams () const
00132 {
00133 std::cerr << "[" << print_str << "] ObjectTurnaroundDetector params (" << (dtw==TOTAL_FORCE?"TOTAL_FORCE":"TOTAL_MOMENT") << ")" << std::endl;
00134 std::cerr << "[" << print_str << "] wrench_cutoff_freq = " << wrench_filter->getCutOffFreq() << "[Hz], dwrench_cutoff_freq = " << dwrench_filter->getCutOffFreq() << "[Hz]" << std::endl;
00135 std::cerr << "[" << print_str << "] detect_ratio_thre = " << detect_ratio_thre << ", start_ratio_thre = " << start_ratio_thre
00136 << ", start_time_thre = " << start_count_thre*dt << "[s], detect_time_thre = " << detect_count_thre*dt << "[s]" << std::endl;
00137 std::cerr << "[" << print_str << "] axis = [" << axis(0) << ", " << axis(1) << ", " << axis(2)
00138 << "], moment_center = " << moment_center(0) << ", " << moment_center(1) << ", " << moment_center(2) << "][m]" << std::endl;
00139 };
00140 void setPrintStr (const std::string& str) { print_str = str; };
00141 void setWrenchCutoffFreq (const double a) { wrench_filter->setCutOffFreq(a); };
00142 void setDwrenchCutoffFreq (const double a) { dwrench_filter->setCutOffFreq(a); };
00143 void setDetectRatioThre (const double a) { detect_ratio_thre = a; };
00144 void setStartRatioThre (const double a) { start_ratio_thre = a; };
00145 void setDetectTimeThre (const double a) { detect_count_thre = round(a/dt); };
00146 void setStartTimeThre (const double a) { start_count_thre = round(a/dt); };
00147 void setAxis (const hrp::Vector3& a) { axis = a; };
00148 void setMomentCenter (const hrp::Vector3& a) { moment_center = a; };
00149 void setDetectorTotalWrench (const detector_total_wrench _dtw)
00150 {
00151 if (_dtw != dtw) {
00152 is_dwr_changed = true;
00153 }
00154 dtw = _dtw;
00155 };
00156 double getWrenchCutoffFreq () const { return wrench_filter->getCutOffFreq(); };
00157 double getDwrenchCutoffFreq () const { return dwrench_filter->getCutOffFreq(); };
00158 double getDetectRatioThre () const { return detect_ratio_thre; };
00159 double getStartRatioThre () const { return start_ratio_thre; };
00160 double getDetectTimeThre () const { return detect_count_thre*dt; };
00161 double getStartTimeThre () const { return start_count_thre*dt; };
00162 hrp::Vector3 getAxis () const { return axis; };
00163 hrp::Vector3 getMomentCenter () const { return moment_center; };
00164 detector_total_wrench getDetectorTotalWrench () const { return dtw; };
00165 double getFilteredWrench () const { return wrench_filter->getCurrentValue(); };
00166 double getFilteredDwrench () const { return dwrench_filter->getCurrentValue(); };
00167 double getRawWrench () const { return current_wrench; };
00168 };
00169 #endif // OBJECTTURNAROUNDDETECTOR_H