Skip to content

Commit

Permalink
updated launch_camera to search for device names
Browse files Browse the repository at this point in the history
  • Loading branch information
KiraYang3 committed Feb 6, 2025
1 parent 8df47f0 commit 0664045
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 3 deletions.
14 changes: 13 additions & 1 deletion videos/src/get_ip.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
# Import necessary libraries
import rclpy
import ipaddress
import subprocess
from rclpy.node import Node
from std_msgs.msg import String

Expand Down Expand Up @@ -32,7 +33,18 @@ def get_ip(self, msg):
self.get_logger().info(f'Invalid IP received from topic: "{msg.data}"')

def launch_camera(self, ip):
pass
# Run command: v4l2-ctl --list-devices
list_devices = subprocess.Popen(["v4l2-ctl", "--list-devices"], stdout=subprocess.PIPE, text=True)

# Search for explorer HD cameras and launch the third device name
counter = 0
camera_name = ""
for line in list_devices.stdout:
if counter == 3:
camera_name = line
if "explorerHD" in line:
counter = 0
counter += 1

def publish_stop(self):
msg = "STOP"
Expand Down
2 changes: 0 additions & 2 deletions videos/src/videos_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,10 +9,8 @@ class Camera(Node):
def __init__(self):
super().__init__("cameras")
self.declare_parameter("dev_name", "device=/dev/video2")
self.declare_parameter("port_num", "5600")

dev_name = self.get_parameter("dev_name").get_parameter_value().string_value
port = self.get_parameter("port_num").get_parameter_value().string_value

while True:
subprocess.run(
Expand Down

0 comments on commit 0664045

Please sign in to comment.