1 #ifndef OBJECTTURNAROUNDDETECTOR_H 2 #define OBJECTTURNAROUNDDETECTOR_H 5 #include "../TorqueFilter/IIRFilter.h" 6 #include <boost/shared_ptr.hpp> 9 #include "hrpsys/util/Hrpsys.h" 28 detector_total_wrench
dtw;
33 count(0), detect_count_thre(5), start_count_thre(5), pmode(
MODE_IDLE), dtw(
TOTAL_FORCE), is_dwr_changed(false)
35 double default_cutoff_freq = 1;
42 ref_dwrench = _ref_diff_wrench/_max_time;
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;
53 for (
size_t i = 0;
i < fmv.size();
i++) {
56 return axis.dot(tmpv);
58 double calcTotalMoment (
const std::vector<hrp::Vector3>& fmv,
const std::vector<hrp::Vector3>& hposv)
61 for (
size_t i = 0;
i < fmv.size();
i++) {
64 return axis.dot(tmpv);
66 bool checkDetection (
const std::vector<hrp::Vector3>& fmv,
const std::vector<hrp::Vector3>& hposv)
82 wrench_filter->reset(wrench_value);
83 dwrench_filter->reset(0);
84 is_dwr_changed =
false;
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);
92 if (tmp_dwr > ref_dwrench*start_ratio_thre) {
94 if (count > start_count_thre) {
97 std::cerr <<
"[" << print_str <<
"] Object Turnaround Detection Started. (" << start_count_thre*dt <<
"[s] after the first start detection)" << std::endl;
104 if (tmp_dwr < ref_dwrench*detect_ratio_thre) {
106 if (count > detect_count_thre) {
108 std::cerr <<
"[" << print_str <<
"] Object Turnaround Detected (time = " << current_time <<
"[s], " << detect_count_thre*dt <<
"[s] after the first detection)" << std::endl;
123 if (pmode !=
MODE_MAX_TIME) std::cerr <<
"[" << print_str <<
"] Object Turnaround Detection max time reached." << std::endl;
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)
152 is_dwr_changed =
true;
169 #endif // OBJECTTURNAROUNDDETECTOR_H void setDetectTimeThre(const double a)
void setStartRatioThre(const double a)
double getStartRatioThre() const
double getStartTimeThre() const
double getFilteredWrench() const
double getWrenchCutoffFreq() const
process_mode getMode() const
double calcTotalMoment(const std::vector< hrp::Vector3 > &fmv, const std::vector< hrp::Vector3 > &hposv)
detector_total_wrench dtw
ObjectTurnaroundDetector(const double _dt)
hrp::Vector3 getAxis() const
void setDetectorTotalWrench(const detector_total_wrench _dtw)
double getDetectTimeThre() const
bool checkDetection(const std::vector< hrp::Vector3 > &fmv, const std::vector< hrp::Vector3 > &hposv)
void setStartTimeThre(const double a)
double getDwrenchCutoffFreq() const
detector_total_wrench getDetectorTotalWrench() const
hrp::Vector3 moment_center
void setDetectRatioThre(const double a)
double getRawWrench() const
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
~ObjectTurnaroundDetector()
void setDwrenchCutoffFreq(const double a)
void setAxis(const hrp::Vector3 &a)
boost::shared_ptr< FirstOrderLowPassFilter< double > > dwrench_filter
double getDetectRatioThre() const
hrp::Vector3 getMomentCenter() const
void setMomentCenter(const hrp::Vector3 &a)
void startDetection(const double _ref_diff_wrench, const double _max_time)
double getFilteredDwrench() const
bool checkDetection(const double wrench_value)
void setPrintStr(const std::string &str)