00001 00029 #include "sr_utilities/calibration.hpp" 00030 #include "sr_utilities/sr_math_utils.hpp" 00031 00032 #include <boost/assert.hpp> 00033 #include <algorithm> 00034 00035 #include <boost/foreach.hpp> 00036 #include <iostream> 00037 00038 namespace shadow_robot 00039 { 00040 JointCalibration::JointCalibration(std::vector<joint_calibration::Point> calibration_table) 00041 { 00042 this->calibration_table_ = calibration_table; 00043 //calibration size - 1 because we use this number to access the last value in the vector 00044 calibration_table_size_ = calibration_table.size() - 1; 00045 00046 //fails if we have only one calibration point as it's not possible 00047 //to interpolate from one point 00048 BOOST_ASSERT(calibration_table_size_ > 0); 00049 00050 /* 00051 * make sure that the given calibration table is ordered by 00052 * growing values of the raw_value 00053 */ 00054 std::sort(this->calibration_table_.begin(), this->calibration_table_.end(), joint_calibration::sort_growing_raw_operator); 00055 } 00056 00057 JointCalibration::~JointCalibration() 00058 {} 00059 00067 double JointCalibration::compute(double raw_reading) 00068 { 00073 joint_calibration::Point low_point, high_point; 00074 00075 //That takes care of computing a reading that's before 00076 // the calibration table as well as a reading that's in the 00077 // first calibration table case. 00078 low_point = calibration_table_[0]; 00079 high_point = calibration_table_[1]; 00080 00081 bool found = false; 00082 00083 //if we have more than 2 points in our calibration table 00084 // or if the raw value isn't before the calibration table 00085 if( (raw_reading > calibration_table_[0].raw_value) ) 00086 { 00087 if( (calibration_table_size_ > 1) ) 00088 { 00089 for(unsigned int index_cal=1; index_cal < calibration_table_size_; ++index_cal) 00090 { 00091 if( (raw_reading >= calibration_table_[index_cal - 1].raw_value) && 00092 (raw_reading < calibration_table_[index_cal].raw_value) ) 00093 { 00094 low_point = calibration_table_[index_cal - 1]; 00095 high_point = calibration_table_[index_cal]; 00096 00097 found = true; 00098 break; 00099 } 00100 } //end for 00101 00102 //the point is outside of the table 00103 if( !found ) 00104 { 00105 low_point = calibration_table_[calibration_table_size_ - 1]; 00106 high_point = calibration_table_[calibration_table_size_]; 00107 } 00108 } // end if 2 values only in the table 00109 } //end if raw_reading before table 00110 00111 return sr_math_utils::linear_interpolate_(raw_reading, low_point.raw_value, 00112 low_point.calibrated_value, 00113 high_point.raw_value, 00114 high_point.calibrated_value); 00115 } 00116 } 00117 00118 /* For the emacs weenies in the crowd. 00119 Local Variables: 00120 c-basic-offset: 2 00121 End: 00122 */ 00123 00124