Skip to content

Commit

Permalink
black
Browse files Browse the repository at this point in the history
  • Loading branch information
JonasFrey96 committed Feb 20, 2024
1 parent 1f4f110 commit afe5a48
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -8,13 +8,13 @@
from message_filters import ApproximateTimeSynchronizer, Subscriber
from PIL import Image as PILImage


class ImageSaver:
def __init__(self):
rospy.init_node('image_saver', anonymous=True)
rospy.init_node("image_saver", anonymous=True)
self.bridge = CvBridge()
self.count = 0


self.dir_path = "/Data/open_source_dataset"
# Create directories to store images
# Subscriber for the images with approximate time synchronization
Expand All @@ -28,7 +28,7 @@ def callback(self, trav_msg, raw_msg):
trav_cv2 = self.bridge.imgmsg_to_cv2(trav_msg, desired_encoding="passthrough")
raw_cv2 = self.bridge.imgmsg_to_cv2(raw_msg, desired_encoding="passthrough")

# Convert images to RGBA format
# Convert images to RGBA format
trav_rgba = cv2.cvtColor(trav_cv2, cv2.COLOR_RGB2BGR)
raw_rgba = cv2.cvtColor(raw_cv2, cv2.COLOR_BGR2BGRA)

Expand All @@ -46,9 +46,10 @@ def callback(self, trav_msg, raw_msg):
except Exception as e:
rospy.logerr(f"Error processing images: {e}")

if __name__ == '__main__':

if __name__ == "__main__":
try:
ImageSaver()
rospy.spin()
except rospy.ROSInterruptException:
pass
pass
Original file line number Diff line number Diff line change
Expand Up @@ -127,8 +127,7 @@ def setup_ros(self, setup_fully=True):
self._log_data[f"nr_model_updates"] = -1

self._last_image_ts = {}



for cam in self._ros_params.camera_topics:
self._last_image_ts[cam] = rospy.get_time()
if self._ros_params.verbose:
Expand Down Expand Up @@ -279,7 +278,7 @@ def image_callback(self, image_msg: Image, cam: str): # info_msg: CameraInfo
image_msg (sensor_msgs/Image): Incoming image
info_msg (sensor_msgs/CameraInfo): Camera info message associated to the image
cam (str): Camera name
"""
"""
# Check the rate
ts = image_msg.header.stamp.to_sec()
if abs(ts - self._last_image_ts[cam]) < 1.0 / self._ros_params.image_callback_rate:
Expand Down

0 comments on commit afe5a48

Please sign in to comment.