Skip to content

Commit

Permalink
Modified ROS node for DAGU differential drive
Browse files Browse the repository at this point in the history
  • Loading branch information
Dmitry Yershov committed Dec 10, 2015
1 parent 782ba1b commit f3c6445
Showing 1 changed file with 5 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -11,29 +11,29 @@
#!/usr/bin/env python

import rospy
import DCMotorInterface
import DAGU_Differential_Drive
from std_msgs.msg import Float64

class motorInterfaceNode():

def __init__(self):

# Initialize DC_motor controller
self.DCMI = DCMotorInterface.DCMotorInterface();
self.dagu = DAGU_Differential_Drive.DAGU_Differential_Drive();
self.speedTimestamp = 0;

rospy.Subscriber("/speed", Float64, self.speedCallback)

def speedCallback(self, data):
#self.speedTimestamp = rospy.Time.now()

self.DCMI.setSpeed(data.data)
self.dagu.setSpeed(data.data)
#rospy.loginfo(rospy.get_caller_id() + "I heard %s", data.data)


if __name__ == '__main__':

# Init ROS network
rospy.init_node('motorsController')
rospy.init_node('DAGU Differential Drive')
node = motorInterfaceNode()
rospy.spin()
rospy.spin()

0 comments on commit f3c6445

Please sign in to comment.