00001 00029 #ifndef _SR_CALIBRATION_HPP_ 00030 #define _SR_CALIBRATION_HPP_ 00031 00032 #include <iostream> 00033 #include <vector> 00034 00035 namespace joint_calibration 00036 { 00041 struct Point 00042 { 00043 double raw_value; 00044 double calibrated_value; 00045 }; 00046 00057 static bool sort_growing_raw_operator(const Point& p1, const Point& p2) 00058 { 00059 return p1.raw_value < p2.raw_value; 00060 } 00061 } 00062 00063 namespace shadow_robot 00064 { 00069 class JointCalibration 00070 { 00071 public: 00072 JointCalibration(std::vector<joint_calibration::Point> calibration_table); 00073 00081 double compute(double raw_reading); 00082 00086 friend std::ostream& operator<<(std::ostream& out, const JointCalibration& calib ) 00087 { 00088 out << " calibration = {"; 00089 out << "size: " << calib.calibration_table_size_; 00090 for( unsigned int i=0; i< calib.calibration_table_.size(); ++i) 00091 { 00092 out << " [raw: " << calib.calibration_table_[i].raw_value; 00093 out << ", cal: " << calib.calibration_table_[i].calibrated_value<<"]"; 00094 } 00095 out << " }"; 00096 return out; 00097 }; 00098 00099 private: 00104 std::vector<joint_calibration::Point> calibration_table_; 00108 unsigned int calibration_table_size_; 00109 }; 00110 } 00111 00112 /* For the emacs weenies in the crowd. 00113 Local Variables: 00114 c-basic-offset: 2 00115 End: 00116 */ 00117 00118 #endif 00119