Skip to content

Commit

Permalink
Add scheduler weight as param
Browse files Browse the repository at this point in the history
  • Loading branch information
mmattamala committed Feb 3, 2024
1 parent 9e3c01e commit 5814cd0
Show file tree
Hide file tree
Showing 11 changed files with 21 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -5,18 +5,21 @@ camera_topics:
use_for_training: true
publish_confidence: true
publish_input_image: true
scheduler_weight: 1
left:
image_topic: "/alphasense_driver_ros/cam3/debayered"
info_topic: "/alphasense_driver_ros/cam3/camera_info"
use_for_training: false
publish_confidence: true
publish_input_image: true
scheduler_weight: 1
right:
image_topic: "/alphasense_driver_ros/cam5/debayered"
info_topic: "/alphasense_driver_ros/cam5/camera_info"
use_for_training: false
publish_confidence: true
publish_input_image: true
scheduler_weight: 1

# Provides 1080 (height) x 1920 (width) images
network_input_image_height: 224 # 448
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,18 +5,21 @@ camera_topics:
use_for_training: true
publish_confidence: true
publish_input_image: true
scheduler_weight: 1
left:
image_topic: "/alphasense_driver_ros/cam3/color_rect/image/compressed"
info_topic: "/alphasense_driver_ros/cam3/color_rect/camera_info"
use_for_training: false
publish_confidence: true
publish_input_image: true
scheduler_weight: 1
right:
image_topic: "/alphasense_driver_ros/cam5/color_rect/image/compressed"
info_topic: "/alphasense_driver_ros/cam5/color_rect/camera_info"
use_for_training: false
publish_confidence: true
publish_input_image: true
scheduler_weight: 1

# Provides 1080 (height) x 1920 (width) images
network_input_image_height: 224 # 448
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ camera_topics:
use_for_training: true
publish_confidence: true
publish_input_image: true
scheduler_weight: 1

# Provides 1080 (height) x 1920 (width) images
network_input_image_height: 224 # 448
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,18 +5,21 @@ camera_topics:
use_for_training: true
publish_confidence: true
publish_input_image: true
scheduler_weight: 1
left:
image_topic: "/alphasense_driver_ros/cam3/color_rect_resize/image"
info_topic: "/alphasense_driver_ros/cam3/color_rect_resize/camera_info"
use_for_training: false
publish_confidence: true
publish_input_image: true
scheduler_weight: 1
right:
image_topic: "/alphasense_driver_ros/cam5/color_rect_resize/image"
info_topic: "/alphasense_driver_ros/cam5/color_rect_resize/camera_info"
use_for_training: false
publish_confidence: true
publish_input_image: true
scheduler_weight: 1

# Provides 1080 (height) x 1920 (width) images
network_input_image_height: 224 # 448
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ camera_topics:
use_for_training: true
publish_confidence: true
publish_input_image: true
scheduler_weight: 1

# Provides 480 (height) x 848 (width) images
network_input_image_height: 448 # 448
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ camera_topics:
use_for_training: true
publish_confidence: true
publish_input_image: true
scheduler_weight: 1

# Provides 480 (height) x 848 (width) images
network_input_image_height: 224 # 448
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ camera_topics:
use_for_training: true
publish_confidence: true
publish_input_image: true
scheduler_weight: 1

# Provides 1080 (height) x 1920 (width) images
network_input_image_height: 448 # 448
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ camera_topics:
use_for_training: true
publish_confidence: true
publish_input_image: true
scheduler_weight: 1

# Provides 1080 (height) x 1920 (width) images
network_input_image_height: 224 # 448
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ camera_topics:
use_for_training: true
publish_confidence: true
publish_input_image: true
scheduler_weight: 1

# Provides 1080 (height) x 1920 (width) images
network_input_image_height: 224 # 448
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<launch>
<!-- Arguments -->
<arg name="camera" default="alphasense_compressed_front"/> <!-- alphasense, wide_angle_front, realsense_front, realsense_rear -->
<arg name="camera" default="alphasense_compressed"/> <!-- alphasense, wide_angle_front, realsense_front, realsense_rear -->
<arg name="stack" default="anybotics"/> <!-- rsl or anybotics $(eval arg('camera') == 'wide_angle_front_resize') $(eval arg('camera') == 'alphasense_resize') -->
<arg name="params_file" default="$(find wild_visual_navigation_ros)/config/wild_visual_navigation/default.yaml"/>
<arg name="overlay_images" default="True"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ def setup_ros(self, setup_fully=True):
# Image callback

self._camera_handler = {}
self._scheduler = Scheduler()
self._camera_scheduler = Scheduler()

if self._ros_params.verbose:
# DEBUG Logging
Expand All @@ -132,7 +132,8 @@ def setup_ros(self, setup_fully=True):
self._ros_params.camera_topics[cam]["name"] = cam

# Add to scheduler
self._scheduler.add_process(cam, 1)
rospy.logwarn(self._ros_params.camera_topics)
self._camera_scheduler.add_process(cam, self._ros_params.camera_topics[cam]["scheduler_weight"])

# Camera info
rospy.loginfo(f"[{self._node_name}] Waiting for camera info topic...")
Expand Down Expand Up @@ -276,7 +277,7 @@ def image_callback(self, image_msg: Image, cam: str): # info_msg: CameraInfo
return

# Check the scheduler
if self._scheduler.get() != cam:
if self._camera_scheduler.get() != cam:
return
else:
if self._ros_params.verbose:
Expand Down Expand Up @@ -415,7 +416,7 @@ def image_callback(self, image_msg: Image, cam: str): # info_msg: CameraInfo
raise Exception("Error in image callback")

# Step scheduler
self._scheduler.step()
self._camera_scheduler.step()

def load_model(self, stamp):
"""Method to load the new model weights to perform inference on the incoming images
Expand Down

0 comments on commit 5814cd0

Please sign in to comment.