commit 76ce88cc4ee796d6578c2a6d2d48ebca9826b0c3 Author: Matas Keras Date: Wed Jul 13 10:11:01 2022 -0400 Added src and launch files diff --git a/launch/oscillation_damp_circle.launch b/launch/oscillation_damp_circle.launch new file mode 100644 index 0000000..41c260c --- /dev/null +++ b/launch/oscillation_damp_circle.launch @@ -0,0 +1,86 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/circle_waypoints.py b/src/circle_waypoints.py new file mode 100755 index 0000000..30b6327 --- /dev/null +++ b/src/circle_waypoints.py @@ -0,0 +1,27 @@ +#!/usr/bin/env python +# license removed for brevity +import rospy +from std_msgs.msg import String +from geometry_msgs.msg import Point +import numpy as np +def circle_points(): + + pub = rospy.Publisher('reference/waypoints',Point, queue_size=10) + rospy.init_node('circle_points', anonymous=True) + rospy.loginfo('init_node') + rate=rospy.Rate(10) + rospy.sleep(48.) + now = rospy.get_rostime().secs + while not rospy.is_shutdown(): + x_pos = np.cos((rospy.get_rostime().secs-now)*np.pi/30)-1 + y_pos = np.sin((rospy.get_rostime().secs-now)*np.pi/30) + z_pos = 5 + to_publish = Point(x=x_pos,y=y_pos,z=z_pos) + pub.publish(to_publish) + rate.sleep + +if __name__ == '__main__': + try: + circle_points() + except rospy.ROSInterruptException: + pass