Skip to content

Commit

Permalink
Merge pull request #147 from clearpathrobotics/fix-bt-cutoff-rate
Browse files Browse the repository at this point in the history
Fix bluetooth cutoff publications
  • Loading branch information
tonybaltovski authored Jan 17, 2025
2 parents c3cdb5f + b74208a commit 8eb8fb2
Showing 1 changed file with 7 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@

import rclpy
from rclpy.node import Node
from rclpy.qos import qos_profile_default
from rcl_interfaces.srv import GetParameters
from std_msgs.msg import Bool, Int32

Expand All @@ -52,8 +53,8 @@ def __init__(self):
self.quality_cutoff = self.get_parameter('quality_cutoff').value

# Create our publishers
self.stop_pub = self.create_publisher(Bool, 'bt_quality_stop', 10)
self.quality_pub = self.create_publisher(Int32, 'quality', 10)
self.stop_pub = self.create_publisher(Bool, 'bt_quality_stop', qos_profile_default)
self.quality_pub = self.create_publisher(Int32, 'quality', qos_profile_default)

# Get the 'dev' parameter from the joy_node to determine what device we're using
self.get_logger().info('Waiting for joy_node parameter service...')
Expand All @@ -72,11 +73,13 @@ def __init__(self):

self.mac_addr = self.get_mac()

# run the timer at 5Hz
# originally this was 10Hz, but that resulted in missed deadlines
if self.mac_addr is not None:
self.quality_timer = self.create_timer(0.1, self.check_quality)
self.quality_timer = self.create_timer(0.2, self.check_quality)
else:
self.get_logger().info(f'Assuming {self.joy_device} is wired; quality check will be bypassed') # noqa: E501
self.quality_timer = self.create_timer(0.1, self.fake_quality)
self.quality_timer = self.create_timer(0.2, self.fake_quality)

def get_mac(self):
if self.joy_device is None:
Expand Down

0 comments on commit 8eb8fb2

Please sign in to comment.