RiCParam.py
Go to the documentation of this file.
00001 __author__ = 'tom1231'
00002 import rospy
00003 
00004 
00005 class RiCParam:
00006     def getServoNum(self):
00007         return int(rospy.get_param('servoNum', '0'))
00008 
00009     def getServoName(self, servoNum):
00010         return rospy.get_param('servo%d/name' % servoNum, '')
00011 
00012     def getServoPublishHz(self, servoNum):
00013         return int(rospy.get_param('servo%d/publishHz' % servoNum, '0'))
00014 
00015     def getServoPort(self, servoNum):
00016         return int(rospy.get_param('servo%d/port' % servoNum, '0'))
00017 
00018     def getServoMin(self, servoNum):
00019         return float(rospy.get_param('servo%d/min' % servoNum, '0'))
00020 
00021     def getServoMax(self, servoNum):
00022         return float(rospy.get_param('servo%d/max' % servoNum, '0'))
00023 
00024     def getServoInitMove(self, servoNum):
00025         return float(rospy.get_param('servo%d/initMove' % servoNum, '0'))
00026 
00027     def getServoAParameter(self, servoNum):
00028         return float(rospy.get_param('servo%d/a' % servoNum, '0'))
00029 
00030     def getServoBParameter(self, servoNum):
00031         return float(rospy.get_param('servo%d/b' % servoNum, '0'))
00032 
00033     def getServoData(self, servoNum):
00034         data = dict()
00035         data['devId'] = servoNum
00036         data['name'] = self.getServoName(servoNum)
00037         data['pubHz'] = self.getServoPublishHz(servoNum)
00038         data['port'] = self.getServoPort(servoNum)
00039         data['min'] = self.getServoMin(servoNum)
00040         data['max'] = self.getServoMax(servoNum)
00041         data['initMove'] = self.getServoInitMove(servoNum)
00042         data['a'] = self.getServoAParameter(servoNum)
00043         data['b'] = self.getServoBParameter(servoNum)
00044         return data
00045 
00046     def getCloseLoopMotorSize(self):
00047         return int(rospy.get_param('closeLoopNum', '0'))
00048 
00049     def getCloseLoopMotorName(self, motorNum):
00050         return rospy.get_param('closeLoop%d/name' % motorNum, '')
00051 
00052     def getCloseLoopMotorPubHz(self, motorNum):
00053         return int(rospy.get_param('closeLoop%d/publishHz' % motorNum, '0'))
00054 
00055     def getCloseLoopMotorLPFAlpha(self, motorNum):
00056         return float(rospy.get_param('closeLoop%d/LPFAlpha' % motorNum, '0'))
00057 
00058     def getCloseLoopMotorLPFHz(self, motorNum):
00059         return int(rospy.get_param('closeLoop%d/LPFHz' % motorNum, '0'))
00060 
00061     def getCloseLoopMotorDriverAddress(self, motorNum):
00062         return int(rospy.get_param('closeLoop%d/driverAddress' % motorNum, '0'))
00063 
00064     def getCloseLoopMotorChannel(self, motorNum):
00065         return int(rospy.get_param('closeLoop%d/channel' % motorNum, '0'))
00066 
00067     def getCloseLoopMotorEncoderPort(self, motorNum):
00068         return int(rospy.get_param('closeLoop%d/port' % motorNum, '0'))
00069 
00070     def getCloseLoopMotorPIDHz(self, motorNum):
00071         return int(rospy.get_param('closeLoop%d/PIDHz' % motorNum, '0'))
00072 
00073     def getCloseLoopMotorKp(self, motorNum):
00074         return float(rospy.get_param('closeLoop%d/kP' % motorNum, '0'))
00075 
00076     def getCloseLoopMotorKi(self, motorNum):
00077         return float(rospy.get_param('closeLoop%d/kI' % motorNum, '0'))
00078 
00079     def getCloseLoopMotorKd(self, motorNum):
00080         return float(rospy.get_param('closeLoop%d/kD' % motorNum, '0'))
00081 
00082     def getCloseLoopMotorMaxSpeed(self, motorNum):
00083         return float(rospy.get_param('closeLoop%d/maxSpeed' % motorNum, '0'))
00084 
00085     def getCloseLoopMotorCpr(self, motorNum):
00086         return int(rospy.get_param('closeLoop%d/cpr' % motorNum, '0'))
00087 
00088     def getCloseLoopMotorTimeout(self, motorNum):
00089         return int(rospy.get_param('closeLoop%d/timeout' % motorNum, '0'))
00090 
00091     def getCloseLoopMotorType(self, motorNum):
00092         return int(rospy.get_param('closeLoop%d/motorType' % motorNum, '0'))
00093 
00094     def getCloseLoopMotorDirection(self, motorNum):
00095         return int(rospy.get_param('closeLoop%d/direction' % motorNum, '0'))
00096 
00097     def getCloseLoopMotorDirectionEncoder(self, motorNum):
00098         return int(rospy.get_param('closeLoop%d/directionE' % motorNum, '0'))
00099 
00100     def getCloseLoopMotorIntegralLimit(self, motorNum):
00101         return float(rospy.get_param('closeLoop%d/limit' % motorNum, '0'))
00102 
00103     def getCloseLoopMotorEncoderType(self, motorNum):
00104         return int(rospy.get_param('closeLoop%d/encoderType' % motorNum, '0'))
00105 
00106     def getCloseLoopMotorPort2(self, motorNum):
00107         return int(rospy.get_param('closeLoop%d/port2' % motorNum, '0'))
00108 
00109     def isInitCloseDiff(self):
00110         return int(rospy.get_param('DIFF_INIT', '0')) == 1
00111 
00112     def isInitOpenDiff(self):
00113         return int(rospy.get_param('DIFF_INIT_OP', '0')) == 1
00114 
00115     def getCloseDiffPubHz(self):
00116         return int(rospy.get_param('Diff/publishHz', '0'))
00117 
00118     def getCloseDiffName(self):
00119         return rospy.get_param('Diff/name', '')
00120 
00121     def getCloseDiffRWheel(self):
00122         return float(rospy.get_param('Diff/rWheel', '0'))
00123 
00124     def getCloseDiffWidth(self):
00125         return float(rospy.get_param('Diff/width', '0'))
00126 
00127     def getCloseDiffBaseLink(self):
00128         return rospy.get_param('Diff/baseLink', '')
00129 
00130     def getCloseDiffOdom(self):
00131         return rospy.get_param('Diff/odom', '')
00132 
00133     def getCloseDiffSlip(self):
00134         return float(rospy.get_param('Diff/slip', '0'))
00135 
00136     def getCloseDiffMotorL(self):
00137         return int(rospy.get_param('Diff/motorL', '0'))
00138 
00139     def getCloseDiffMotorR(self):
00140         return int(rospy.get_param('Diff/motorR', '0'))
00141 
00142     def getCloseDiffMaxAng(self):
00143         return float(rospy.get_param('Diff/maxAng', '0'))
00144 
00145     def getCloseDiffMaxLin(self):
00146         return float(rospy.get_param('Diff/maxLin', '0'))
00147 
00148     def getURFNum(self):
00149         return int(rospy.get_param('URFNum', '0'))
00150 
00151     def getURFPubHz(self, urfNum):
00152         return int(rospy.get_param('URF%d/publishHz' % urfNum, '0'))
00153 
00154     def getURFName(self, urfNum):
00155         return rospy.get_param('URF%d/name' % urfNum, '')
00156 
00157     def getURFFrameId(self, urfNum):
00158         return rospy.get_param('URF%d/frameId' % urfNum, '')
00159 
00160     def getURFType(self, urfNum):
00161         return int(rospy.get_param('URF%d/type' % urfNum, '0'))
00162 
00163     def getURFPort(self, urfNum):
00164         return int(rospy.get_param('URF%d/port' % urfNum, '0'))
00165 
00166     def getSwitchSize(self):
00167         return int(rospy.get_param('switchNum', '0'))
00168 
00169     def getSwitchName(self, switchId):
00170         return rospy.get_param('switch%d/name' % switchId, '')
00171 
00172     def getSwitchPort(self, switchId):
00173         return int(rospy.get_param('switch%d/port' % switchId, '0'))
00174 
00175     def getSwitchPubHz(self, switchId):
00176         return int(rospy.get_param('switch%d/publishHz' % switchId, '0'))
00177 
00178     def isImuInit(self):
00179         return int(rospy.get_param('IMU_INIT', '0')) == 1
00180 
00181     def getIMUPubHz(self):
00182         return int(rospy.get_param('IMU/publishHz', '0'))
00183 
00184     def getIMUName(self):
00185         return rospy.get_param('IMU/name', '')
00186 
00187     def getIMUFrameId(self):
00188         return rospy.get_param('IMU/frameId', '')
00189 
00190     def getIMUCamp(self):
00191         return float(rospy.get_param('IMU/camp', '0.0'))
00192 
00193     def getIMUFusionHz(self):
00194         return int(rospy.get_param('IMU/fusionHz', '0'))
00195 
00196     def getIMUOrientation(self):
00197         return float(rospy.get_param('IMU/orientation', '0.0'))
00198 
00199     def isIMUFuseGyro(self):
00200         return int(rospy.get_param('IMU/fuseGyro', '0')) == 1
00201 
00202     def getRelaysSize(self):
00203         return int(rospy.get_param('relayNum', '0'))
00204 
00205     def getRelayName(self, relayNum):
00206         return rospy.get_param('relay%d/name' % relayNum, '')
00207 
00208     def getRelayPort(self, relayNum):
00209         return int(rospy.get_param('relay%d/port' % relayNum, '0'))
00210 
00211     def isGpsInit(self):
00212         return int(rospy.get_param('GPS_INIT', '0')) == 1
00213 
00214     def getGpsPubHz(self):
00215         return int(rospy.get_param('GPS/publishHz', '0'))
00216 
00217     def getGpsName(self):
00218         return rospy.get_param('GPS/name', '')
00219 
00220     def getGpsFrameId(self):
00221         return rospy.get_param('GPS/frameId', '')
00222 
00223     def getGpsBaudrate(self):
00224         return int(rospy.get_param('GPS/baudrate', '0'))
00225 
00226     def isXbeeEnable(self):
00227         return int(rospy.get_param('Xbee_INIT', '0'))
00228 
00229     def isPPMInit(self):
00230         return int(rospy.get_param('PPM_INIT', '0')) == 1
00231 
00232     def getPPMPubHz(self):
00233         return int(rospy.get_param('PPM/publishHz', '0'))
00234 
00235     def getPPMName(self):
00236         return rospy.get_param('PPM/name', '')
00237 
00238     def getOpenLoopNum(self):
00239         return int(rospy.get_param('openLoopNum', '0'))
00240 
00241     def getOpenLoopName(self, motorNum):
00242         return rospy.get_param('openLoop%d/name' % motorNum, '')
00243 
00244     def getOpenLoopAddress(self, motorNum):
00245         return int(rospy.get_param('openLoop%d/address' % motorNum, '0'))
00246 
00247     def getOpenLoopChannel(self, motorNum):
00248         return int(rospy.get_param('openLoop%d/channel' % motorNum, '0'))
00249 
00250     def getOpenLoopTimeout(self, motorNum):
00251         return int(rospy.get_param('openLoop%d/timeout' % motorNum, '0'))
00252 
00253     def getOpenLoopMax(self, motorNum):
00254         return int(rospy.get_param('openLoop%d/max' % motorNum, '0'))
00255 
00256     def getOpenLoopDirection(self, motorNum):
00257         return int(rospy.get_param('openLoop%d/direction' % motorNum, '0'))
00258 
00259     def isBatteryInit(self):
00260         return int(rospy.get_param('BAT_INIT', '0')) == 1
00261 
00262     def getBatteryName(self):
00263         return rospy.get_param('Battery/name', '')
00264 
00265     def getBatteryPubHz(self):
00266         return int(rospy.get_param('Battery/pubHz', '0'))
00267 
00268     def getBatteryVoltageDividerRatio(self):
00269         return float(rospy.get_param('Battery/voltageDividerRatio', '0.0'))
00270 
00271     def isCloseDiffFourInit(self):
00272         return int(rospy.get_param('DIFF_CLOSE_FOUR', '0')) == 1
00273 
00274     def getCloseDiffMotorFL(self):
00275         return int(rospy.get_param('Diff/motorFL', 0))
00276 
00277     def getCloseDiffMotorFR(self):
00278         return int(rospy.get_param('Diff/motorFR', 0))
00279 
00280     def getCloseDiffMotorBL(self):
00281         return int(rospy.get_param('Diff/motorBL', 0))
00282 
00283     def getCloseDiffMotorBR(self):
00284         return int(rospy.get_param('Diff/motorBR', 0))
00285 
00286     def getConPort(self):
00287         return rospy.get_param('CON_PORT', 'RiCBoard')
00288 
00289     def getFileName(self):
00290         return rospy.get_param('FILE_NAME', '')
00291 
00292     def getEmergencyPin(self, index):
00293         return int(rospy.get_param('emergency_switch{0}/pin'.format(str(index)), 27))
00294 
00295     def getEmergencyState(self, index):
00296         return int(rospy.get_param('emergency_switch{0}/state'.format(str(index)), 1))
00297 
00298     def getEmergencyName(self, index):
00299         return rospy.get_param('emergency_switch{0}/name'.format(str(index)), 'None')
00300 
00301     def EmergencyCount(self):
00302         return int(rospy.get_param('emergencySwitchNum', 0))
00303 
00304     def getBatteryMin(self):
00305         return float(rospy.get_param('Battery/min', '0.0'))
00306 
00307     def getBatteryMax(self):
00308         return float(rospy.get_param('Battery/max', '0.0'))


ric_board
Author(s): RoboTiCan
autogenerated on Fri Oct 27 2017 03:02:31