Skip to content

Commit b8774c3

Browse files
authored
Merge pull request #185 from CWRUbotix/photosphere-streaming
Photosphere streaming
2 parents f377e7c + 82554d7 commit b8774c3

File tree

8 files changed

+129
-63
lines changed

8 files changed

+129
-63
lines changed

src/photosphere/display/index.html

Lines changed: 13 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -6,23 +6,32 @@
66
<link rel="stylesheet" href="/index.min.css" />
77

88
<style>
9+
html, body {
10+
padding: 0;
11+
margin: 0;
12+
}
13+
914
img {
10-
height: 0.9em;
15+
height: 0.7em;
1116
}
1217

1318
h1 {
1419
font-size: 4em;
1520
text-align: center;
21+
font-family: "Ubuntu Sans", sans-serif;
22+
margin-top: 0.5em;
23+
margin-bottom: 0.5em;
1624
/* color: #4178C1; */
1725
}
26+
1827
div {
19-
margin:auto;
28+
margin: auto;
2029
}
2130
</style>
2231
</head>
2332
<body>
24-
<h1><img src="logo.png"/>CWRUbotix Photosphere</h1>
25-
<div id="viewer" style="width: 500px; height: 500px;"></div>
33+
<h1><img src="logo.png"/> CWRUbotix Photosphere</h1>
34+
<div id="viewer" style="width: 1000px; height: 700px;"></div>
2635

2736
<script type="importmap">
2837
{
Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
#!/usr/bin/env bash
2+
3+
SCRIPT_DIR=$( cd -- "$( dirname -- "${BASH_SOURCE[0]}" )" &> /dev/null && pwd )
4+
5+
echo "Running server from $SCRIPT_DIR..."
6+
7+
python3 -m http.server -d $SCRIPT_DIR

src/photosphere/take_images.sh

Lines changed: 0 additions & 2 deletions
This file was deleted.

src/rov_msgs/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,7 @@ rosidl_generate_interfaces(${PROJECT_NAME}
4545
"srv/MissionTimerSet.srv"
4646
"srv/CameraManage.srv"
4747
"srv/VehicleArming.srv"
48+
"srv/TakePhotosphere.srv"
4849
DEPENDENCIES std_msgs
4950
)
5051

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
#No information is needed in the request
1+
# No information is needed in the request
22
---
3-
#Whether the photosphere was generated correctly
3+
# Whether the photosphere was generated correctly
44
bool generated
Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
uint8 CAM0 = 0
2+
uint8 CAM1 = 1
3+
uint8 BOTH = 2
4+
5+
uint8 cam
6+
---
7+
bool success
8+
uint8 cam

src/surface/gui/gui/widgets/tabs/photosphere_tab.py

Lines changed: 47 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -1,19 +1,18 @@
11
from PyQt6.QtCore import Qt, pyqtSignal, pyqtSlot
2-
from PyQt6.QtWidgets import QHBoxLayout, QLabel, QVBoxLayout, QWidget
3-
from std_srvs.srv import Trigger
2+
from PyQt6.QtWidgets import QGridLayout, QHBoxLayout, QLabel, QVBoxLayout, QWidget
43

54
from gui.gui_node import GUINode
65
from gui.styles.custom_styles import ButtonIndicator, WidgetState
76
from gui.widgets.logger import Logger
87
from gui.widgets.video_widget import CameraDescription, CameraType, VideoWidget
9-
from rov_msgs.srv import GeneratePhotosphere
8+
from rov_msgs.srv import GeneratePhotosphere, TakePhotosphere
109

1110
FISHEYE1_TOPIC = 'photosphere/image_1'
1211
FISHEYE2_TOPIC = 'photosphere/image_2'
1312

1413

1514
class PhotosphereTab(QWidget):
16-
take_photos_response_signal = pyqtSignal(Trigger.Response)
15+
take_photos_response_signal = pyqtSignal(TakePhotosphere.Response)
1716
generate_response_signal = pyqtSignal(GeneratePhotosphere.Response)
1817

1918
def __init__(self) -> None:
@@ -29,7 +28,7 @@ def __init__(self) -> None:
2928
)
3029

3130
self.take_photos_client = GUINode().create_client_multithreaded(
32-
Trigger, 'photosphere/take_photos'
31+
TakePhotosphere, 'photosphere/take_photos'
3332
)
3433
self.generate_photosphere_client = GUINode().create_client_multithreaded(
3534
GeneratePhotosphere, 'photosphere/generate_photosphere'
@@ -47,22 +46,36 @@ def __init__(self) -> None:
4746
alignment=Qt.AlignmentFlag.AlignTop | Qt.AlignmentFlag.AlignLeft,
4847
)
4948

50-
button_pane = QHBoxLayout()
49+
button_pane = QGridLayout()
5150

5251
self.take_photos_button = ButtonIndicator('Take Photos')
53-
self.take_photos_button.setMinimumHeight(60)
54-
self.take_photos_button.setMinimumWidth(150)
55-
self.take_photos_button.clicked.connect(self.take_photos_clicked)
52+
self.take_photos_button.clicked.connect(
53+
lambda: self.take_photo_clicked(TakePhotosphere.Request.BOTH)
54+
)
55+
56+
self.take_cam0_button = ButtonIndicator('Take 0')
57+
self.take_cam1_button = ButtonIndicator('Take 1')
58+
self.take_cam0_button.clicked.connect(
59+
lambda: self.take_photo_clicked(cam=TakePhotosphere.Request.CAM0)
60+
)
61+
self.take_cam1_button.clicked.connect(
62+
lambda: self.take_photo_clicked(cam=TakePhotosphere.Request.CAM1)
63+
)
64+
65+
self.photo_buttons: dict[int, tuple[ButtonIndicator, ...]] = {
66+
TakePhotosphere.Request.CAM0: (self.take_cam0_button,),
67+
TakePhotosphere.Request.CAM1: (self.take_cam1_button,),
68+
TakePhotosphere.Request.BOTH: (self.take_cam0_button, self.take_cam1_button),
69+
}
5670

5771
self.generate_button = ButtonIndicator('Generate Photosphere')
58-
self.generate_button.setMinimumHeight(60)
59-
self.generate_button.setMinimumWidth(150)
6072
self.generate_button.set_state(WidgetState.INACTIVE)
6173
self.generate_button.clicked.connect(self.generate_clicked)
6274

63-
button_pane.addWidget(self.take_photos_button)
64-
button_pane.addWidget(self.generate_button)
65-
button_pane.addStretch()
75+
button_pane.addWidget(self.take_photos_button, 0, 0, 1, 2)
76+
button_pane.addWidget(self.take_cam0_button, 1, 0)
77+
button_pane.addWidget(self.take_cam1_button, 1, 1)
78+
button_pane.addWidget(self.generate_button, 2, 0, 1, 2)
6679

6780
root_layout = QVBoxLayout()
6881
root_layout.addLayout(video_pane)
@@ -78,10 +91,13 @@ def __init__(self) -> None:
7891
root_layout.addWidget(Logger())
7992
self.setLayout(root_layout)
8093

81-
def take_photos_clicked(self) -> None:
82-
self.take_photos_button.set_state(WidgetState.INACTIVE)
94+
def take_photo_clicked(self, cam: int) -> None:
95+
for button in self.photo_buttons[cam]:
96+
button.set_state(WidgetState.INACTIVE)
8397
GUINode().send_request_multithreaded(
84-
self.take_photos_client, Trigger.Request(), self.take_photos_response_signal
98+
self.take_photos_client,
99+
TakePhotosphere.Request(cam=cam),
100+
self.take_photos_response_signal,
85101
)
86102

87103
def generate_clicked(self) -> None:
@@ -100,11 +116,19 @@ def generate_response_handler(self, res: GeneratePhotosphere.Response) -> None:
100116
self.photosphere_status_label.setText('Photosphere generated')
101117
self.generate_button.set_state(WidgetState.ON)
102118

103-
@pyqtSlot(Trigger.Response)
104-
def take_photos_response_handler(self, res: Trigger.Response) -> None:
105-
if res and res.success:
106-
self.take_photos_button.set_state(WidgetState.ON)
107-
if self.generate_button.current_state == WidgetState.INACTIVE:
119+
@pyqtSlot(TakePhotosphere.Response)
120+
def take_photos_response_handler(self, res: TakePhotosphere.Response) -> None:
121+
if not res:
122+
for button in self.photo_buttons[TakePhotosphere.Request.BOTH]:
123+
button.set_state(WidgetState.OFF)
124+
elif res.success:
125+
for button in self.photo_buttons[res.cam]:
126+
button.set_state(WidgetState.ON)
127+
if self.generate_button.current_state == WidgetState.INACTIVE and all(
128+
button.current_state == WidgetState.ON
129+
for button in self.photo_buttons[TakePhotosphere.Request.BOTH]
130+
):
108131
self.generate_button.set_state(WidgetState.NONE)
109132
else:
110-
self.take_photos_button.set_state(WidgetState.OFF)
133+
for button in self.photo_buttons[res.cam]:
134+
button.set_state(WidgetState.OFF)

src/surface/photosphere/photosphere/photosphere_driver_node.py

Lines changed: 51 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -8,16 +8,35 @@
88
from rclpy.node import Node
99
from rclpy.qos import qos_profile_system_default
1010
from sensor_msgs.msg import Image
11-
from std_srvs.srv import Trigger
11+
12+
from rov_msgs.srv import TakePhotosphere
1213

1314
HOST = '192.168.2.5'
1415
USER = 'rov'
16+
# Ruff complains about plaintext passwords
1517
PASSWORD = 'rov12345' # noqa: S105
1618
CONNECT_TIMEOUT = 8 # Seconds to log in
1719

18-
TAKE_PICS_CMD = 'bash /home/rov/rov-25/src/photosphere/take_images.sh'
19-
LOCAL_PATH = 'src/surface/photosphere/images' # relative the rov-25 repo
20+
# TAKE_PICS_CMD = 'bash /home/rov/rov-25/src/photosphere/take_images.sh'
21+
TAKE_PICS_TEMPLATE = (
22+
'fswebcam -d /dev/video{video_num} -r 3840x3032 --skip 10 --scale 3840x3032 '
23+
'--no-banner /home/rov/rov-25/src/photosphere/images/cam{cam_num}.jpg'
24+
)
25+
TAKE_PICS_CMDS = {
26+
TakePhotosphere.Request.CAM0: TAKE_PICS_TEMPLATE.format(video_num=0, cam_num=0),
27+
TakePhotosphere.Request.CAM1: TAKE_PICS_TEMPLATE.format(video_num=2, cam_num=1),
28+
TakePhotosphere.Request.BOTH: TAKE_PICS_TEMPLATE.format(video_num=0, cam_num=0)
29+
+ '\n'
30+
+ TAKE_PICS_TEMPLATE.format(video_num=2, cam_num=1),
31+
}
32+
33+
PIC_FILE_NAMES = {
34+
TakePhotosphere.Request.CAM0: ('cam0.jpg',),
35+
TakePhotosphere.Request.CAM1: ('cam1.jpg',),
36+
TakePhotosphere.Request.BOTH: ('cam0.jpg', 'cam1.jpg'),
37+
}
2038

39+
LOCAL_PATH = 'src/surface/photosphere/images' # relative the rov-25 repo
2140
REMOTE_PATH = '/home/rov/rov-25/src/photosphere/images'
2241

2342

@@ -28,12 +47,13 @@ def __init__(self) -> None:
2847
self.cv_bridge = CvBridge()
2948

3049
self.arming_service = self.create_service(
31-
Trigger, 'take_photos', callback=self.take_photos_callback
50+
TakePhotosphere, 'take_photos', callback=self.take_photos_callback
3251
)
3352

34-
self.image_publisher_1 = self.create_publisher(Image, 'image_1', qos_profile_system_default)
35-
36-
self.image_publisher_2 = self.create_publisher(Image, 'image_2', qos_profile_system_default)
53+
self.image_publishers = {
54+
'cam0.jpg': self.create_publisher(Image, 'image_1', qos_profile_system_default),
55+
'cam1.jpg': self.create_publisher(Image, 'image_2', qos_profile_system_default),
56+
}
3757

3858
self.local_images_path = (
3959
Path(get_package_share_directory('photosphere').split('rov-25')[0])
@@ -44,63 +64,62 @@ def __init__(self) -> None:
4464
self.get_logger().info('Ready to download photosphere images')
4565

4666
def take_photos_callback(
47-
self, _: Trigger.Request, response: Trigger.Response
48-
) -> Trigger.Response:
67+
self, request: TakePhotosphere.Request, response: TakePhotosphere.Response
68+
) -> TakePhotosphere.Response:
4969
"""Connect to the photosphere over ssh and take an image from each camera.
5070
5171
Parameters
5272
----------
53-
request : Trigger.Request
54-
The ROS service request; Trigger has no request fields
55-
response : Trigger.Response
56-
The ROS service response (success and message)
73+
request : TakePhotosphere.Request
74+
The ROS service request (which camera(s))
75+
response : TakePhotosphere.Response
76+
The ROS service response (success)
5777
5878
Returns
5979
-------
60-
Trigger.Response
80+
TakePhotosphere.Response
6181
The filled ROS service response
6282
"""
6383
ssh_client = paramiko.SSHClient()
84+
85+
# Ruff complains about AutoAddPolicy being insecure
6486
ssh_client.set_missing_host_key_policy(paramiko.AutoAddPolicy()) # noqa: S507
6587

6688
try:
6789
ssh_client.connect(HOST, username=USER, password=PASSWORD, timeout=CONNECT_TIMEOUT)
6890
except (TimeoutError, paramiko.ssh_exception.NoValidConnectionsError):
6991
self.get_logger().error('Failed to connect to photosphere sensor')
70-
response = Trigger.Response()
92+
response = TakePhotosphere.Response()
7193
response.success = False
94+
response.cam = request.cam
7295
return response
7396

7497
self.get_logger().info('Connected to Calamari')
7598

76-
_, ssh_stdout, _ = ssh_client.exec_command(TAKE_PICS_CMD)
99+
_, ssh_stdout, _ = ssh_client.exec_command(TAKE_PICS_CMDS[request.cam])
77100
ssh_stdout.channel.set_combine_stderr(True)
78101

79102
for line in ssh_stdout:
80103
self.get_logger().info(line.strip())
81104

82105
ftp_client = ssh_client.open_sftp()
83-
ftp_client.get(
84-
str(Path(REMOTE_PATH) / 'cam0.jpg'), str(Path(self.local_images_path) / 'cam0.jpg')
85-
)
86-
ftp_client.get(
87-
str(Path(REMOTE_PATH) / 'cam1.jpg'), str(Path(self.local_images_path) / 'cam1.jpg')
88-
)
89106

90-
self.get_logger().info('Images downloaded from Calamari')
107+
for filename in PIC_FILE_NAMES[request.cam]:
108+
ftp_client.get(
109+
str(Path(REMOTE_PATH) / filename), str(Path(self.local_images_path) / filename)
110+
)
91111

92-
img_1 = cv2.imread(str(Path(self.local_images_path) / 'cam0.jpg'))
93-
img_1 = cv2.rotate(img_1, cv2.ROTATE_180)
94-
img_msg_1 = self.cv_bridge.cv2_to_imgmsg(img_1)
95-
self.image_publisher_1.publish(img_msg_1)
112+
self.get_logger().info('Images downloaded from Calamari')
96113

97-
img_2 = cv2.imread(str(Path(self.local_images_path) / 'cam1.jpg'))
98-
img_2 = cv2.rotate(img_2, cv2.ROTATE_180)
99-
img_msg_2 = self.cv_bridge.cv2_to_imgmsg(img_2)
100-
self.image_publisher_2.publish(img_msg_2)
114+
for filename in PIC_FILE_NAMES[request.cam]:
115+
img = cv2.imread(str(Path(self.local_images_path) / filename))
116+
img = cv2.rotate(img, cv2.ROTATE_180)
117+
img_msg = self.cv_bridge.cv2_to_imgmsg(img)
118+
self.image_publishers[filename].publish(img_msg)
101119

102-
response = Trigger.Response()
120+
response = TakePhotosphere.Response()
103121
response.success = True
122+
response.cam = request.cam
104123

105124
return response
106125

0 commit comments

Comments
 (0)