Skip to content

Commit

Permalink
WIP #15: Added skeleton for function to load config file
Browse files Browse the repository at this point in the history
Also capitalized some stuff
  • Loading branch information
Jacob Gloudemans committed Feb 16, 2019
1 parent 9918560 commit ba1e238
Showing 1 changed file with 22 additions and 8 deletions.
30 changes: 22 additions & 8 deletions update_node/scripts/update_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,10 @@

# imports
import rospy
from std_msgs.msg import UInt8
from geometry_msgs.msg import Twist
from geometry_msgs.msg import Pose
from std_msgs.msg import Float64, Float32
from std_msgs.msg import *
from geometry_msgs.msg import *
from nav_msgs.msg import *
from sensor_msgs.msg import *

class UpdatePublisher:

Expand All @@ -19,10 +19,10 @@ def __init__ (self, topic_name):
latest_var = 0

#Initialize Publisher
self.publisher = rospy.publisher('updates/' + topic_name, Float64, queue_size=0)
self.publisher = rospy.Publisher('updates/' + topic_name, Float64, queue_size=0)

#Initialize Subscriber
self.subscriber = rospy.subscriber(topic_name, Float64, self.update_message)
self.subscriber = rospy.Subscriber(topic_name, Float64, self.update_message)

def update_message(self, data):

Expand All @@ -36,6 +36,14 @@ def publish_message(self, latest_var):
#Publish the variable
self.publisher.publish(latest_var)

@staticmethod
def load_config_file(file_name):

updaters = []

# Create a list of UpdatePublishers

return updaters

if __name__ == "__main__":

Expand All @@ -45,12 +53,18 @@ def publish_message(self, latest_var):
#create UpdatePublisher object
updater = UpdatePublisher()

# TODO: Read a file containing a bunch of [topic name, message type] pairs, create an UpdatePublisher for each
# updaters = load_config_file(filename)

#read values from server
update_rate = rospy.get_param("update_rate")

#Log initialization message
rospy.loginfo("Update node initialized...")

rate = rospy.rate(update_rate)
rate = rospy.Rate(update_rate)
while not rospy.is_shutdown():
rospy.sleep()

# Send an update from each UpdatePublisher

rate.sleep()

0 comments on commit ba1e238

Please sign in to comment.