From 0be932c1d2dc25a3e50550a5f47a3a8143ec70e4 Mon Sep 17 00:00:00 2001 From: Fabien Grzeskowiak <fabien.grzeskowiak@inria.fr> Date: Mon, 8 Jul 2019 17:50:23 +0200 Subject: [PATCH] add clock controller --- crowdbotsim/scripts/clock_publisher.py | 41 ++++++++++++++++++++++++++ crowdbotsim/scripts/joy_to_twist.py | 2 +- 2 files changed, 42 insertions(+), 1 deletion(-) create mode 100755 crowdbotsim/scripts/clock_publisher.py diff --git a/crowdbotsim/scripts/clock_publisher.py b/crowdbotsim/scripts/clock_publisher.py new file mode 100755 index 0000000..c0b8ec7 --- /dev/null +++ b/crowdbotsim/scripts/clock_publisher.py @@ -0,0 +1,41 @@ +#!/usr/bin/env python +import rospy +import sys +import math +from time import sleep +from rosgraph_msgs.msg import Clock + +myargv = rospy.myargv(argv=sys.argv) +script, sleep_time, delta_time = myargv + +sleep_time = float(sleep_time) +delta_time = float(delta_time) + +def publish_clock(): + # initialize node + rospy.init_node('clock_controller', anonymous = False) + + ### Set up clock publisher + clock_pub = rospy.Publisher('clock', Clock, queue_size = 1) + clock_pub2 = rospy.Publisher('myclock', Clock, queue_size = 1) + + msg = Clock() + msg.clock = rospy.Time() + + current_time = 0 + + while not rospy.is_shutdown(): + ### Publish clock + secs = int(current_time) + nsecs = 1e9 * (current_time - secs) + msg.clock = rospy.Time(secs,nsecs) + clock_pub.publish(msg) + clock_pub2.publish(msg) + current_time += delta_time + sleep(sleep_time) + +if __name__ == '__main__': + publish_clock() + + + diff --git a/crowdbotsim/scripts/joy_to_twist.py b/crowdbotsim/scripts/joy_to_twist.py index a2aba1d..52f7f83 100755 --- a/crowdbotsim/scripts/joy_to_twist.py +++ b/crowdbotsim/scripts/joy_to_twist.py @@ -12,7 +12,7 @@ rospy.init_node('joy_to_twist', anonymous = True) #### Setup joy_to_twist Publisher -joy_to_twist_pub = rospy.Publisher(topic, Twist, queue_size = 5) +joy_to_twist_pub = rospy.Publisher(topic, Twist, queue_size = 1) msg = Twist() -- GitLab