Skip to content

Commit

Permalink
add tcp_nodelay for python nodes too
Browse files Browse the repository at this point in the history
  • Loading branch information
senceryazici committed Dec 28, 2024
1 parent 719d419 commit 82756c7
Show file tree
Hide file tree
Showing 6 changed files with 13 additions and 9 deletions.
4 changes: 3 additions & 1 deletion auv_common_lib/python/auv_common_lib/control/enable_state.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,9 @@ def __init__(self, timeout_duration):
self.enable = False
self.timeout_duration = rospy.Duration(timeout_duration)
self.last_enable_time = rospy.Time.now()
rospy.Subscriber("enable", std_msgs.msg.Bool, self._enable_callback)
rospy.Subscriber(
"enable", std_msgs.msg.Bool, self._enable_callback, tcp_nodelay=True
)

def _enable_callback(self, msg):
self.enable = msg.data
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,9 @@ def __init__(self, source_frame: str):
self.transformer = auv_common_lib.transform.transformer.Transformer()
self.source_frame = source_frame

rospy.Subscriber("imu/data", sensor_msgs.msg.Imu, self.imu_data_callback)
rospy.Subscriber(
"imu/data", sensor_msgs.msg.Imu, self.imu_data_callback, tcp_nodelay=True
)

def imu_data_callback(self, data: sensor_msgs.msg.Imu):
angular_rate_raw = np.array(
Expand Down
4 changes: 2 additions & 2 deletions auv_control/auv_control/scripts/depth_controller_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,14 +14,14 @@ def __init__(self):

# Initialize subscribers
self.odometry_sub = rospy.Subscriber(
"/taluy/odometry", Odometry, self.odometry_callback
"/taluy/odometry", Odometry, self.odometry_callback, tcp_nodelay=True
)
self.set_depth_service = rospy.Service(
"/taluy/set_depth", SetDepth, self.target_depth_handler
)

# Initialize publisher
self.cmd_pose_pub = rospy.Publisher("/taluy/cmd_pose", Pose, queue_size=10)
self.cmd_pose_pub = rospy.Publisher("/taluy/cmd_pose", Pose, queue_size=1)

# Initialize internal state
self.target_depth = 0.0
Expand Down
6 changes: 3 additions & 3 deletions auv_navigation/auv_localization/scripts/dvl_odometry_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,13 +30,13 @@ def __init__(self):

# Subscribers and Publishers
self.dvl_velocity_subscriber = message_filters.Subscriber(
"sensors/dvl/velocity_raw", Twist
"sensors/dvl/velocity_raw", Twist, tcp_no_delay=True
)
self.is_valid_subscriber = message_filters.Subscriber(
"sensors/dvl/is_valid", Bool
"sensors/dvl/is_valid", Bool, tcp_no_delay=True
)
self.cmd_vel_subscriber = rospy.Subscriber(
"cmd_vel", Twist, self.cmd_vel_callback
"cmd_vel", Twist, self.cmd_vel_callback, tcp_nodelay=True
)

self.sync = message_filters.ApproximateTimeSynchronizer(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ def __init__(self):
)
# Subscribers and Publishers
self.imu_subscriber = rospy.Subscriber(
"sensors/imu/data", Imu, self.imu_callback
"sensors/imu/data", Imu, self.imu_callback, tcp_nodelay=True
)
self.odom_publisher = rospy.Publisher(
"localization/odom_imu", Odometry, queue_size=10
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ def __init__(self):
rospy.loginfo(
f"{pressure_odometry_colored} : depth covariance: {self.depth_calibration_covariance}"
)
self.depth_subscriber = rospy.Subscriber("depth", Float32, self.depth_callback)
self.depth_subscriber = rospy.Subscriber("depth", Float32, self.depth_callback, tcp_nodelay=True)

def depth_callback(self, depth_msg):
# Fill the odometry message with depth data as the z component of the linear position
Expand Down

0 comments on commit 82756c7

Please sign in to comment.