ObjectTurnaroundDetector.h
Go to the documentation of this file.
1 #ifndef OBJECTTURNAROUNDDETECTOR_H
2 #define OBJECTTURNAROUNDDETECTOR_H
3 
4 #include "RatsMatrix.h"
5 #include "../TorqueFilter/IIRFilter.h"
6 #include <boost/shared_ptr.hpp>
7 #include <iostream>
8 #include <cmath>
9 #include "hrpsys/util/Hrpsys.h"
10 
12 {
13  public:
16  private:
20  double prev_wrench, dt;
22  size_t count;
23  // detect_count_thre*dt and start_ratio_thre*dt are threshould for time.
24  // detect_count_thre*dt : Threshould for time [s] after the first object turnaround detection (Wait detect_time_thre [s] after first object turnaround detection).
25  // start_count_thre*dt : Threshould for time [s] after the first starting detection (Wait start_time_thre [s] after first start detection).
27  process_mode pmode;
28  detector_total_wrench dtw;
29  std::string print_str;
31  public:
32  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),
33  count(0), detect_count_thre(5), start_count_thre(5), pmode(MODE_IDLE), dtw(TOTAL_FORCE), is_dwr_changed(false)
34  {
35  double default_cutoff_freq = 1; // [Hz]
36  wrench_filter = boost::shared_ptr<FirstOrderLowPassFilter<double> >(new FirstOrderLowPassFilter<double>(default_cutoff_freq, _dt, 0));
37  dwrench_filter = boost::shared_ptr<FirstOrderLowPassFilter<double> >(new FirstOrderLowPassFilter<double>(default_cutoff_freq, _dt, 0));
38  };
40  void startDetection (const double _ref_diff_wrench, const double _max_time)
41  {
42  ref_dwrench = _ref_diff_wrench/_max_time;
43  max_time = _max_time;
44  current_time = 0;
45  count = 0;
46  std::cerr << "[" << print_str << "] Start Object Turnaround Detection (ref_dwrench = " << ref_dwrench
47  << ", detect_thre = " << detect_ratio_thre * ref_dwrench << ", start_thre = " << start_ratio_thre * ref_dwrench << "), max_time = " << max_time << "[s]" << std::endl;
48  pmode = MODE_IDLE;
49  };
50  double calcTotalForce (const std::vector<hrp::Vector3>& fmv)
51  {
52  hrp::Vector3 tmpv = hrp::Vector3::Zero();
53  for (size_t i = 0; i < fmv.size(); i++) {
54  tmpv += fmv[i];
55  }
56  return axis.dot(tmpv);
57  };
58  double calcTotalMoment (const std::vector<hrp::Vector3>& fmv, const std::vector<hrp::Vector3>& hposv)
59  {
60  hrp::Vector3 tmpv = hrp::Vector3::Zero();
61  for (size_t i = 0; i < fmv.size(); i++) {
62  tmpv += (hposv[i]-moment_center).cross(fmv[i]);
63  }
64  return axis.dot(tmpv);
65  };
66  bool checkDetection (const std::vector<hrp::Vector3>& fmv, const std::vector<hrp::Vector3>& hposv)
67  {
68  switch(dtw) {
69  case TOTAL_FORCE:
71  break;
72  case TOTAL_MOMENT:
73  checkDetection(calcTotalMoment(fmv, hposv));
74  break;
75  default:
76  break;
77  };
78  };
79  bool checkDetection (const double wrench_value)
80  {
81  if (is_dwr_changed) {
82  wrench_filter->reset(wrench_value);
83  dwrench_filter->reset(0);
84  is_dwr_changed = false;
85  }
86  current_wrench = wrench_value;
87  double tmp_wr = wrench_filter->passFilter(wrench_value);
88  double tmp_dwr = dwrench_filter->passFilter((tmp_wr-prev_wrench)/dt);
89  prev_wrench = tmp_wr;
90  switch (pmode) {
91  case MODE_IDLE:
92  if (tmp_dwr > ref_dwrench*start_ratio_thre) {
93  count++;
94  if (count > start_count_thre) {
95  pmode = MODE_STARTED;
96  count = 0;
97  std::cerr << "[" << print_str << "] Object Turnaround Detection Started. (" << start_count_thre*dt << "[s] after the first start detection)" << std::endl;
98  }
99  } else {
100  /* count--; */
101  }
102  break;
103  case MODE_STARTED:
104  if (tmp_dwr < ref_dwrench*detect_ratio_thre) {
105  count++;
106  if (count > detect_count_thre) {
107  pmode = MODE_DETECTED;
108  std::cerr << "[" << print_str << "] Object Turnaround Detected (time = " << current_time << "[s], " << detect_count_thre*dt << "[s] after the first detection)" << std::endl;
109  }
110  } else {
111  /* count--; */
112  }
113  //std::cerr << "[" << print_str << "] " << tmp_wr << " " << tmp_dwr << " " << count << std::endl;
114  break;
115  case MODE_DETECTED:
116  break;
117  case MODE_MAX_TIME:
118  break;
119  default:
120  break;
121  }
122  if (max_time <= current_time && (pmode != MODE_DETECTED)) {
123  if (pmode != MODE_MAX_TIME) std::cerr << "[" << print_str << "] Object Turnaround Detection max time reached." << std::endl;
124  pmode = MODE_MAX_TIME;
125  }
126  current_time += dt;
127  return isDetected();
128  };
129  bool isDetected () const { return (pmode == MODE_DETECTED); };
130  process_mode getMode () const { return pmode; };
131  void printParams () const
132  {
133  std::cerr << "[" << print_str << "] ObjectTurnaroundDetector params (" << (dtw==TOTAL_FORCE?"TOTAL_FORCE":"TOTAL_MOMENT") << ")" << std::endl;
134  std::cerr << "[" << print_str << "] wrench_cutoff_freq = " << wrench_filter->getCutOffFreq() << "[Hz], dwrench_cutoff_freq = " << dwrench_filter->getCutOffFreq() << "[Hz]" << std::endl;
135  std::cerr << "[" << print_str << "] detect_ratio_thre = " << detect_ratio_thre << ", start_ratio_thre = " << start_ratio_thre
136  << ", start_time_thre = " << start_count_thre*dt << "[s], detect_time_thre = " << detect_count_thre*dt << "[s]" << std::endl;
137  std::cerr << "[" << print_str << "] axis = [" << axis(0) << ", " << axis(1) << ", " << axis(2)
138  << "], moment_center = " << moment_center(0) << ", " << moment_center(1) << ", " << moment_center(2) << "][m]" << std::endl;
139  };
140  void setPrintStr (const std::string& str) { print_str = str; };
141  void setWrenchCutoffFreq (const double a) { wrench_filter->setCutOffFreq(a); };
142  void setDwrenchCutoffFreq (const double a) { dwrench_filter->setCutOffFreq(a); };
143  void setDetectRatioThre (const double a) { detect_ratio_thre = a; };
144  void setStartRatioThre (const double a) { start_ratio_thre = a; };
145  void setDetectTimeThre (const double a) { detect_count_thre = round(a/dt); };
146  void setStartTimeThre (const double a) { start_count_thre = round(a/dt); };
147  void setAxis (const hrp::Vector3& a) { axis = a; };
148  void setMomentCenter (const hrp::Vector3& a) { moment_center = a; };
149  void setDetectorTotalWrench (const detector_total_wrench _dtw)
150  {
151  if (_dtw != dtw) {
152  is_dwr_changed = true;
153  }
154  dtw = _dtw;
155  };
156  double getWrenchCutoffFreq () const { return wrench_filter->getCutOffFreq(); };
157  double getDwrenchCutoffFreq () const { return dwrench_filter->getCutOffFreq(); };
158  double getDetectRatioThre () const { return detect_ratio_thre; };
159  double getStartRatioThre () const { return start_ratio_thre; };
160  double getDetectTimeThre () const { return detect_count_thre*dt; };
161  double getStartTimeThre () const { return start_count_thre*dt; };
162  hrp::Vector3 getAxis () const { return axis; };
164  detector_total_wrench getDetectorTotalWrench () const { return dtw; };
165  double getFilteredWrench () const { return wrench_filter->getCurrentValue(); };
166  double getFilteredDwrench () const { return dwrench_filter->getCurrentValue(); };
167  double getRawWrench () const { return current_wrench; };
168 };
169 #endif // OBJECTTURNAROUNDDETECTOR_H
void setDetectTimeThre(const double a)
void setStartRatioThre(const double a)
double calcTotalMoment(const std::vector< hrp::Vector3 > &fmv, const std::vector< hrp::Vector3 > &hposv)
ObjectTurnaroundDetector(const double _dt)
png_uint_32 i
void setDetectorTotalWrench(const detector_total_wrench _dtw)
Eigen::Vector3d Vector3
bool checkDetection(const std::vector< hrp::Vector3 > &fmv, const std::vector< hrp::Vector3 > &hposv)
void setStartTimeThre(const double a)
OpenHRP::vector3 Vector3
detector_total_wrench getDetectorTotalWrench() const
void setDetectRatioThre(const double a)
void setWrenchCutoffFreq(const double a)
Vector3 cross(const Vector3 &v1, const Vector3 &v2)
double calcTotalForce(const std::vector< hrp::Vector3 > &fmv)
boost::shared_ptr< FirstOrderLowPassFilter< double > > wrench_filter
void setDwrenchCutoffFreq(const double a)
void setAxis(const hrp::Vector3 &a)
boost::shared_ptr< FirstOrderLowPassFilter< double > > dwrench_filter
hrp::Vector3 getMomentCenter() const
void setMomentCenter(const hrp::Vector3 &a)
void startDetection(const double _ref_diff_wrench, const double _max_time)
bool checkDetection(const double wrench_value)
void setPrintStr(const std::string &str)


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Thu May 6 2021 02:41:50