Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Sw/update velocity #34

Merged
merged 14 commits into from
Nov 18, 2023
70 changes: 70 additions & 0 deletions rb_ws/src/buggy/scripts/2d_sim/velocity_updater.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
#! /usr/bin/env python3
import rospy
from controller_2d import Controller
from geometry_msgs.msg import Pose
from geometry_msgs.msg import Point
import threading
import math

class VelocityUpdater:
RATE = 100
# Bubbles for updating acceleration based on position
# represented as 4-tuples: (x-pos, y-pos, radius, acceleration)
CHECKPOINTS: 'list[tuple[float,float,float,float]]' = [
(589701, 4477160, 20, 0.5)
]

def __init__(self):
self.pose_subscriber = rospy.Subscriber(
"sim_2d/utm", Pose, self.update_position
)

self.buggy_vel = 15.0
self.accel = 0.0

self.position = Point()
self.position.x = 0
self.position.y = 0
self.position.z = 0

self.controller = Controller()

self.lock = threading.Lock()

def update_position(self, new_pose: Pose):
'''Callback function to update internal position variable when new
buggy position is published

Args:
new_pose (Pose): Pose object from topic
'''
with self.lock:
self.position = new_pose.position

def calculate_accel(self):
'''Check if the position of the buggy is in any of the checkpoints set
in self.CHECKPOINTS, and update acceleration of buggy accordingly
'''
for (x,y,r,a) in self.CHECKPOINTS:
dist = math.sqrt((x - self.position.x)**2 + (y - self.position.y)**2)
if dist < r:
self.accel = a
break

def step(self):
'''Update acceleration and velocity of buggy for one timestep'''
self.calculate_accel()

new_velocity = self.buggy_vel + self.accel / self.RATE
self.buggy_vel = new_velocity
self.controller.set_velocity(new_velocity)


if __name__ == "__main__":
rospy.init_node("velocity_updater")
vel = VelocityUpdater()
rate = rospy.Rate(vel.RATE)

while not rospy.is_shutdown():
vel.step()
rate.sleep()