$search
00001 /* 00002 * ART steering self-test 00003 * 00004 * Copyright (C) 2008, 2009 Austin Robot Technology 00005 * 00006 * License: Modified BSD Software License Agreement 00007 * 00008 * $Id: testwheel.cc 1161 2011-03-26 02:10:49Z jack.oquin $ 00009 */ 00010 00011 #include <errno.h> 00012 00013 #include <ros/ros.h> 00014 00015 #include "testwheel.h" 00016 #include "devsteer.h" 00017 #include "dtimer.h" 00018 00020 // public methods 00022 00023 00024 #define CLASS "testwheel" 00025 00026 testwheel::testwheel(const boost::shared_ptr<devsteer> &_dev): 00027 state(Begin), 00028 dev(_dev), 00029 timer(new DriverTimer()) 00030 {} 00031 00032 testwheel::~testwheel() 00033 {} 00034 00035 int testwheel::Configure() 00036 { 00037 // use private node handle to get parameters 00038 ros::NodeHandle mynh("~"); 00039 00040 test_wheel = true; 00041 mynh.getParam("test_wheel", test_wheel); 00042 if (!test_wheel) 00043 return 0; 00044 ROS_INFO("wheel test configured"); 00045 00046 test_angle = 3.0; 00047 mynh.getParam("test_angle", test_angle); 00048 ROS_INFO("wheel test angle is %.1f degrees", test_angle); 00049 00050 timeout = 2.0; 00051 mynh.getParam("test_timeout", timeout); 00052 ROS_INFO("wheel test timeout is %.1f seconds", timeout); 00053 00054 tolerance = 2.0; 00055 mynh.getParam("test_tolerance", tolerance); 00056 ROS_INFO("wheel test tolerance is %.1f degrees", tolerance); 00057 00058 return 0; 00059 } 00060 00061 // Run steering wheel self-test 00062 // 00063 // Called once per cycle until test completed. 00064 // 00065 // returns: 0 if test still running 00066 // < 0 if test failed (negative of errno value), 00067 // > 0 if test completed successfully, 00068 // 00069 int testwheel::Run(float steering_angle) 00070 { 00071 int result = 0; // test still running 00072 00073 switch(state) 00074 { 00075 case Begin: 00076 { 00077 if (test_wheel) // test configured? 00078 { 00079 start_angle = steering_angle; 00080 target_angle = test_angle + steering_angle; 00081 int rc = dev->steering_absolute(target_angle); 00082 if (rc == 0) 00083 { 00084 state = Move; 00085 ROS_INFO("beginning steering self-test"); 00086 timer->Start(timeout); 00087 } 00088 else 00089 { 00090 ROS_ERROR("steering self-test failed (%s)", strerror(rc)); 00091 result = -rc; 00092 } 00093 } 00094 else // nothing to do 00095 { 00096 ROS_INFO("steering self-test: nothing to do, returning"); 00097 result = 1; // success 00098 } 00099 break; 00100 } 00101 case Move: 00102 { 00103 if (timer->Check()) 00104 { 00105 ROS_ERROR("steering self-test move failed (timeout)"); 00106 result = -EBUSY; 00107 } 00108 else if (fabs(steering_angle - target_angle) <= tolerance) 00109 { 00110 // go back to starting position 00111 int rc = dev->steering_absolute(start_angle); 00112 if (rc == 0) 00113 { 00114 state = Back; 00115 ROS_INFO("self-test angle reached, turning back"); 00116 timer->Start(timeout); 00117 } 00118 else 00119 { 00120 ROS_ERROR("steering self-test failed (%s)", strerror(rc)); 00121 result = -rc; 00122 } 00123 } 00124 break; 00125 } 00126 case Back: 00127 { 00128 if (timer->Check()) 00129 { 00130 ROS_ERROR("steering self-test move back failed (timeout)"); 00131 result = -EBUSY; 00132 } 00133 else if (fabs(steering_angle - start_angle) <= tolerance) 00134 { 00135 ROS_INFO("steering self-test successful"); 00136 result = 1; // success 00137 } 00138 break; 00139 } 00140 case Done: 00141 { 00142 result = 1; // nothing left to do 00143 break; 00144 } 00145 default: 00146 // invalid state -- should not happen 00147 ROS_ERROR("steering self-test failed (invalid state)"); 00148 result = -EINVAL; 00149 } 00150 00151 if (result != 0) 00152 state = Done; 00153 00154 return result; 00155 }