Skip to content

Commit

Permalink
use ros.Rate instead of ros.Timer
Browse files Browse the repository at this point in the history
  • Loading branch information
talhabw committed Dec 22, 2024
1 parent 0859e3f commit c9bcb96
Showing 1 changed file with 6 additions and 4 deletions.
10 changes: 6 additions & 4 deletions auv_control/auv_control/scripts/reference_pose_publisher.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,6 @@ def __init__(self):
self.update_rate = rospy.get_param("~update_rate", 10)
self.command_timeout = rospy.get_param("~command_timeout", 0.1)

rospy.Timer(rospy.Duration(1.0 / self.update_rate), self.control_loop)

def target_depth_handler(self, req: SetDepthRequest) -> SetDepthResponse:
self.target_depth = req.target_depth
return SetDepthResponse(
Expand Down Expand Up @@ -63,7 +61,7 @@ def cmd_vel_callback(self, msg):
self.target_heading += msg.angular.z * dt
self.last_cmd_time = rospy.Time.now()

def control_loop(self, event):
def control_loop(self):
# Create and publish the cmd_pose message
cmd_pose = Pose()

Expand All @@ -78,7 +76,11 @@ def control_loop(self, event):
self.cmd_pose_pub.publish(cmd_pose)

def run(self):
rospy.spin()
rate = rospy.Rate(self.update_rate)

while not rospy.is_shutdown():
self.control_loop()
rate.sleep()


if __name__ == "__main__":
Expand Down

0 comments on commit c9bcb96

Please sign in to comment.