RICOpenLoopMotor.py
Go to the documentation of this file.
00001 from threading import Thread
00002 from BAL.Header.Requests.openLoopMotorRequest import OpenLoopMotorRequest
00003 from BAL.Header.Response.ParamBuildResponse import EngineOL
00004 
00005 __author__ = 'tom1231'
00006 from rospy import Subscriber
00007 from std_msgs.msg import Float32
00008 from BAL.Interfaces.Device import Device
00009 
00010 
00011 class OpenLoopMotor(Device):
00012     def __init__(self, motorId,param, output):
00013         Device.__init__(self, param.getOpenLoopName(motorId), output)
00014         self._id = motorId
00015         self._direction = param.getOpenLoopDirection(motorId)
00016         Subscriber('%s/command' % self._name, Float32, self.openLoopCallback)
00017 
00018     def publish(self, data): pass
00019 
00020     def getType(self): return EngineOL
00021 
00022     def openLoopCallback(self, msg):
00023         Thread(target=self.sendMsg, args=(msg,)).start()
00024 
00025     def sendMsg(self, msg):
00026         self._output.write(OpenLoopMotorRequest(self._id, msg.data * self._direction).dataTosend())


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