00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00037 00038 #ifndef _PR2_TRANSMISSION_CHECK_TRANSMISSION_CHECK_ 00039 #define _PR2_TRANSMISSION_CHECK_TRANSMISSION_CHECK_ 00040 00041 #include <vector> 00042 #include <float.h> 00043 00044 #include <boost/shared_ptr.hpp> 00045 #include <boost/math/special_functions/fpclassify.hpp> 00046 #include <boost/accumulators/accumulators.hpp> 00047 #include <boost/accumulators/statistics/max.hpp> 00048 #include <boost/accumulators/statistics/min.hpp> 00049 #include <diagnostic_updater/DiagnosticStatusWrapper.h> 00050 #include <urdf/joint.h> 00051 00052 #include <ros/ros.h> 00053 #include <pr2_mechanism_msgs/MechanismStatistics.h> 00054 #include <pr2_mechanism_msgs/JointStatistics.h> 00055 #include <pr2_mechanism_msgs/ActuatorStatistics.h> 00056 00057 00058 namespace pr2_transmission_check 00059 { 00060 00065 class TransmissionListener 00066 { 00067 private: 00068 std::string joint_name_; 00069 std::string actuator_name_; 00070 float deadband_; 00071 float up_ref_; 00072 float down_ref_; 00073 bool has_wrap_, has_up_, has_down_; 00074 bool status_, last_trans_status_; 00075 float max_; 00076 float min_; 00077 int error_cnt_; 00078 00079 int num_errors_; 00080 int num_hits_; 00081 int num_errors_since_reset_; 00082 int rx_cnt_; 00083 00084 bool last_cal_reading_; 00085 float last_rising_, last_falling_; 00086 float last_bad_reading_; 00087 float last_position_; 00088 bool is_calibrated_; 00089 00090 bool has_updated_; 00091 00092 // Min and max observed joint positions 00093 boost::accumulators::accumulator_set<float, 00094 boost::accumulators::features<boost::accumulators::tag::max, 00095 boost::accumulators::tag::min> > position_obs_; 00096 00097 // Check to make sure we're in min/max 00098 bool checkBounds(const pr2_mechanism_msgs::JointStatistics *js) const; 00099 00100 // Check to make sure we have correct flag setting 00101 bool checkFlag(const pr2_mechanism_msgs::JointStatistics *js, 00102 const pr2_mechanism_msgs::ActuatorStatistics *as) const; 00103 00104 public: 00105 TransmissionListener(); 00106 00107 ~TransmissionListener() {} 00108 00110 bool initUrdf(const boost::shared_ptr<urdf::Joint> jnt, const std::string &actuator_name); 00111 00112 bool update(const pr2_mechanism_msgs::MechanismStatistics::ConstPtr& mechMsg); 00113 00114 bool checkOK() const { return status_; } 00115 00116 void reset() { status_ = true; last_trans_status_ = true; num_errors_since_reset_ = 0; } 00117 00118 boost::shared_ptr<diagnostic_updater::DiagnosticStatusWrapper> toDiagStat() const; 00119 }; 00120 00121 00122 00123 } 00124 00125 #endif //