Skip to content

Commit 95d06eb

Browse files
authored
Revamp In-App Video Streaming (#106)
* Remove dependency on web video server * Unsubscribe before unload --------- Co-authored-by: Amal Nanavati <amaln@cs.washington.edu>
1 parent 6b3e050 commit 95d06eb

File tree

14 files changed

+110
-120
lines changed

14 files changed

+110
-120
lines changed

feeding_web_app_ros2_test/feeding_web_app_ros2_test/DummyRealSense.py

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -85,6 +85,9 @@ def __init__(self):
8585
self.camera_info_publisher = self.create_publisher(
8686
CameraInfo, "~/camera_info", 1
8787
)
88+
self.aligned_depth_camera_info_publisher = self.create_publisher(
89+
CameraInfo, "~/aligned_depth/camera_info", 1
90+
)
8891
if self.video is not None:
8992
self.num_frames = 0
9093
self.bridge = CvBridge()
@@ -174,6 +177,7 @@ def publish_frames(self):
174177
self.compressed_image_publisher.publish(compressed_frame_msg)
175178
self.aligned_depth_publisher.publish(depth_frame_msg)
176179
self.camera_info_publisher.publish(self.camera_info_msg)
180+
self.aligned_depth_camera_info_publisher.publish(self.camera_info_msg)
177181

178182
rate.sleep()
179183

feeding_web_app_ros2_test/feeding_web_app_ros2_test/FaceDetection.py

Lines changed: 13 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@
77
import numpy as np
88
import rclpy
99
from rclpy.node import Node
10-
from sensor_msgs.msg import Image
10+
from sensor_msgs.msg import CompressedImage
1111
from threading import Lock
1212

1313

@@ -65,15 +65,20 @@ def __init__(
6565

6666
# Subscribe to the camera feed
6767
self.subscription = self.create_subscription(
68-
Image, "camera/color/image_raw", self.camera_callback, 1
68+
CompressedImage,
69+
"camera/color/image_raw/compressed",
70+
self.camera_callback,
71+
1,
6972
)
7073
self.subscription # prevent unused variable warning
7174

7275
# Create the publishers
7376
self.publisher_results = self.create_publisher(
7477
FaceDetection, "face_detection", 1
7578
)
76-
self.publisher_image = self.create_publisher(Image, "face_detection_img", 1)
79+
self.publisher_image = self.create_publisher(
80+
CompressedImage, "face_detection_img/compressed", 1
81+
)
7782

7883
def toggle_face_detection_callback(self, request, response):
7984
"""
@@ -150,15 +155,16 @@ def camera_callback(self, msg):
150155
face_detection_msg.is_face_detected = is_face_detected
151156
if is_face_detected:
152157
# Add a dummy face marker to the sensor_msgs/Image
153-
cv_image = self.bridge.imgmsg_to_cv2(msg, "bgr8")
158+
cv_image = self.bridge.compressed_imgmsg_to_cv2(msg, "bgr8")
159+
height, width, _ = cv_image.shape
154160
cv2.circle(
155161
cv_image,
156-
(msg.width // 2, msg.height // 2),
157-
msg.height // 25,
162+
(width // 2, height // 2),
163+
height // 25,
158164
(0, 0, 255),
159165
-1,
160166
)
161-
annotated_msg = self.bridge.cv2_to_imgmsg(cv_image, "bgr8")
167+
annotated_msg = self.bridge.cv2_to_compressed_imgmsg(cv_image, "jpeg")
162168
annotated_img = annotated_msg
163169
# Publish the detected mouth center. The below is a hardcoded
164170
# rough position of the mouth from the side staging location,
@@ -185,7 +191,6 @@ def camera_callback(self, msg):
185191
annotated_img = msg
186192
face_detection_msg.is_mouth_open = open_mouth_detected
187193
self.publisher_results.publish(face_detection_msg)
188-
self.get_logger().info("Published face detection")
189194
self.publisher_image.publish(annotated_img)
190195

191196

feeding_web_app_ros2_test/feeding_web_app_ros2_test/SegmentFromPoint.py

Lines changed: 9 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@
99
from rclpy.action import ActionServer, CancelResponse, GoalResponse
1010
from rclpy.executors import MultiThreadedExecutor
1111
from rclpy.node import Node
12-
from sensor_msgs.msg import CompressedImage, Image, RegionOfInterest
12+
from sensor_msgs.msg import CompressedImage, RegionOfInterest
1313
from shapely.geometry import MultiPoint
1414
import threading
1515
import time
@@ -34,8 +34,8 @@ def __init__(self, sleep_time=2.0, send_feedback_hz=10):
3434

3535
# Subscribe to the image topic, to store the latest image
3636
self.image_subscriber = self.create_subscription(
37-
Image,
38-
"/camera/color/image_raw",
37+
CompressedImage,
38+
"/camera/color/image_raw/compressed",
3939
self.image_callback,
4040
1,
4141
)
@@ -123,8 +123,8 @@ def segment_image(self, seed_point, result, segmentation_success):
123123
with self.latest_img_msg_lock:
124124
latest_img_msg = self.latest_img_msg
125125
result.header = latest_img_msg.header
126-
width = latest_img_msg.width
127-
height = latest_img_msg.height
126+
img = self.bridge.compressed_imgmsg_to_cv2(latest_img_msg, "bgr8")
127+
width, height, _ = img.shape
128128

129129
# Sleep (dummy segmentation)
130130
time.sleep(self.sleep_time)
@@ -175,6 +175,10 @@ def segment_image(self, seed_point, result, segmentation_success):
175175
format="jpeg",
176176
data=cv2.imencode(".jpg", mask_img)[1].tostring(),
177177
)
178+
mask_msg.rgb_image = CompressedImage(
179+
format="jpeg",
180+
data=cv2.imencode(".jpg", img[y_min:y_max, x_min:x_max])[1].tostring(),
181+
)
178182
mask_msg.item_id = "dummy_food_id_%d" % (i)
179183
mask_msg.confidence = np.random.random()
180184
result.detected_items.append(mask_msg)

feeding_web_app_ros2_test/launch/feeding_web_app_dummy_nodes_launch.xml

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -10,8 +10,6 @@
1010
<group if="$(var run_web_bridge)">
1111
<!-- The ROSBridge Node -->
1212
<include file="$(find-pkg-share rosbridge_server)/launch/rosbridge_websocket_launch.xml"/>
13-
<!-- The ROS web_video_server -->
14-
<node pkg="web_video_server" exec="web_video_server" name="web_video_server"/>
1513
</group>
1614

1715
<!-- The dummy nodes -->
@@ -23,8 +21,9 @@
2321
<remap from="~/compressed_image" to="/camera/color/image_raw/compressed"/>
2422
<remap from="~/aligned_depth" to="/camera/aligned_depth_to_color/image_raw"/>
2523
<remap from="~/camera_info" to="/camera/color/camera_info"/>
24+
<remap from="~/aligned_depth/camera_info" to="/camera/aligned_depth_to_color/camera_info"/>
2625
<param name="fps" value="30"/>
27-
<param name="rgb_path" value="$(find-pkg-share feeding_web_app_ros2_test)/../data/above_plate_1_rgb.jpg"/>
26+
<param name="rgb_path" value="$(find-pkg-share feeding_web_app_ros2_test)/../data/2022_11_01_ada_picks_up_carrots_camera_compressed_ft_tf.mp4"/>
2827
<param name="depth_path" value="$(find-pkg-share feeding_web_app_ros2_test)/../data/above_plate_1_depth.png"/>
2928
</node>
3029
</group>

feedingwebapp/src/App.jsx

Lines changed: 8 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -22,23 +22,22 @@ import BiteSelectionPointMask from './Pages/Home/BiteSelectionUIStates/BiteSelec
2222
* @param {APP_PAGE} appPage - The current app page. Must be one of the
2323
* states specified in APP_PAGE.
2424
* @param {string} rosbridgeURL - The URL of the rosbridge server.
25-
* @param {string} webVideoServerURL - The URL of the web_video_server.
2625
* @param {bool} debug - Whether to run it in debug mode or not.
2726
*/
28-
function getComponentByAppPage(appPage, rosbridgeURL, webVideoServerURL, debug) {
27+
function getComponentByAppPage(appPage, rosbridgeURL, debug) {
2928
switch (appPage) {
3029
case APP_PAGE.Home:
3130
// Must wrap a component in ROS tags for it to be able to connect to ROS
3231
return (
3332
<RosConnection url={rosbridgeURL} autoConnect>
34-
<Header webVideoServerURL={webVideoServerURL} />
35-
<Home debug={debug} webVideoServerURL={webVideoServerURL} />
33+
<Header />
34+
<Home debug={debug} />
3635
</RosConnection>
3736
)
3837
case APP_PAGE.Settings:
3938
return (
4039
<RosConnection url={rosbridgeURL} autoConnect>
41-
<Header webVideoServerURL={webVideoServerURL} />
40+
<Header />
4241
<Settings />
4342
</RosConnection>
4443
)
@@ -57,8 +56,6 @@ function App() {
5756

5857
// Get the rosbridge URL
5958
const rosbridgeURL = 'ws://'.concat(window.location.hostname, ':', process.env.REACT_APP_ROSBRIDGE_PORT)
60-
// Get the web_video_server URL
61-
const webVideoServerURL = 'http://'.concat(window.location.hostname, ':', process.env.REACT_APP_WEB_VIDEO_SERVER_PORT)
6259

6360
// Get the debug flag
6461
const debug = process.env.REACT_APP_DEBUG === 'true'
@@ -68,7 +65,7 @@ function App() {
6865
<>
6966
<Router>
7067
<Routes>
71-
<Route exact path='/' element={getComponentByAppPage(appPage, rosbridgeURL, webVideoServerURL, debug)} />
68+
<Route exact path='/' element={getComponentByAppPage(appPage, rosbridgeURL, debug)} />
7269
<Route
7370
exact
7471
path='/test_ros'
@@ -83,7 +80,7 @@ function App() {
8380
path='/test_bite_selection_ui/button_overlay_selection'
8481
element={
8582
<RosConnection url={rosbridgeURL} autoConnect>
86-
<Header webVideoServerURL={webVideoServerURL} />
83+
<Header />
8784
<BiteSelectionButtonOverlay debug={debug} />
8885
</RosConnection>
8986
}
@@ -93,7 +90,7 @@ function App() {
9390
path='/test_bite_selection_ui/point_mask_selection'
9491
element={
9592
<RosConnection url={rosbridgeURL} autoConnect>
96-
<Header webVideoServerURL={webVideoServerURL} />
93+
<Header />
9794
<BiteSelectionPointMask debug={debug} />
9895
</RosConnection>
9996
}
@@ -103,7 +100,7 @@ function App() {
103100
path='/test_bite_selection_ui/food_name_selection'
104101
element={
105102
<RosConnection url={rosbridgeURL} autoConnect>
106-
<Header webVideoServerURL={webVideoServerURL} />
103+
<Header />
107104
<BiteSelectionName debug={debug} />
108105
</RosConnection>
109106
}

feedingwebapp/src/Pages/Constants.js

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -48,10 +48,10 @@ NON_MOVING_STATES.add(MEAL_STATE.U_PostMeal)
4848
export { NON_MOVING_STATES }
4949

5050
// The names of the ROS topic(s)
51-
export const CAMERA_FEED_TOPIC = '/local/camera/color/image_raw'
51+
export const CAMERA_FEED_TOPIC = '/local/camera/color/image_raw/compressed'
5252
export const FACE_DETECTION_TOPIC = '/face_detection'
5353
export const FACE_DETECTION_TOPIC_MSG = 'ada_feeding_msgs/FaceDetection'
54-
export const FACE_DETECTION_IMG_TOPIC = '/face_detection_img'
54+
export const FACE_DETECTION_IMG_TOPIC = '/face_detection_img/compressed'
5555

5656
// States from which, if they fail, it is NOT okay for the user to retry the
5757
// same action.

feedingwebapp/src/Pages/Header/Header.jsx

Lines changed: 2 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -4,9 +4,6 @@ import React, { useCallback, useEffect, useState } from 'react'
44
import Navbar from 'react-bootstrap/Navbar'
55
import Nav from 'react-bootstrap/Nav'
66
import { useMediaQuery } from 'react-responsive'
7-
// PropTypes is used to validate that the used props are in fact passed to this
8-
// Component
9-
import PropTypes from 'prop-types'
107
// Toast generates a temporary pop-up with a timeout.
118
import { ToastContainer /* , toast */ } from 'react-toastify'
129
import 'react-toastify/dist/ReactToastify.css'
@@ -23,7 +20,7 @@ import LiveVideoModal from './LiveVideoModal'
2320
* clicking "Video", and the ToastContainer popup that specifies when the user
2421
* cannot click Settings.
2522
*/
26-
const Header = (props) => {
23+
const Header = () => {
2724
// Create a local state variable to toggle on/off the video
2825
// TODO: Since this local state variable is in the header, the LiveVideoModal
2926
// continues showing even if the state changes. Is this desirable? Perhaps
@@ -166,13 +163,9 @@ const Header = (props) => {
166163
* The LiveVideoModal toggles on and off with the Video button and shows the
167164
* robot's live camera feed.
168165
*/}
169-
<LiveVideoModal webVideoServerURL={props.webVideoServerURL} show={videoShow} onHide={() => setVideoShow(false)} />
166+
<LiveVideoModal show={videoShow} onHide={() => setVideoShow(false)} />
170167
</>
171168
)
172169
}
173-
Header.propTypes = {
174-
// The URL of the ROS web video server
175-
webVideoServerURL: PropTypes.string.isRequired
176-
}
177170

178171
export default Header

feedingwebapp/src/Pages/Header/LiveVideoModal.jsx

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,8 @@ function LiveVideoModal(props) {
4949
<Modal.Body ref={modalBodyRef} style={{ overflow: 'hidden' }}>
5050
<center>
5151
<VideoFeed
52-
webVideoServerURL={props.webVideoServerURL}
52+
topic='/local/camera/color/image_raw/compressed'
53+
updateRateHz={10}
5354
parent={modalBodyRef}
5455
marginTop={margin}
5556
marginBottom={margin}
@@ -65,9 +66,7 @@ LiveVideoModal.propTypes = {
6566
// Whether or not the modal is visible
6667
show: PropTypes.bool.isRequired,
6768
// Callback function for when the modal is hidden
68-
onHide: PropTypes.func.isRequired,
69-
// The URL of the ROS web video server
70-
webVideoServerURL: PropTypes.string.isRequired
69+
onHide: PropTypes.func.isRequired
7170
}
7271

7372
export default LiveVideoModal

feedingwebapp/src/Pages/Home/Home.jsx

Lines changed: 4 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,6 @@ import { TIME_TO_RESET_MS } from '../Constants'
2222
*
2323
* @param {boolean} debug - whether to run it in debug mode (e.g., if you aren't
2424
* simulatenously running the robot) or not
25-
* @param {string} webVideoServerURL - the URL of the web video server
2625
* @returns {JSX.Element}
2726
*/
2827
function Home(props) {
@@ -94,10 +93,10 @@ function Home(props) {
9493
)
9594
}
9695
case MEAL_STATE.U_BiteSelection: {
97-
return <BiteSelection debug={props.debug} webVideoServerURL={props.webVideoServerURL} />
96+
return <BiteSelection debug={props.debug} />
9897
}
9998
case MEAL_STATE.U_PlateLocator: {
100-
return <PlateLocator debug={props.debug} webVideoServerURL={props.webVideoServerURL} />
99+
return <PlateLocator debug={props.debug} />
101100
}
102101
case MEAL_STATE.R_BiteAcquisition: {
103102
/**
@@ -153,7 +152,7 @@ function Home(props) {
153152
)
154153
}
155154
case MEAL_STATE.R_DetectingFace: {
156-
return <DetectingFace debug={props.debug} webVideoServerURL={props.webVideoServerURL} />
155+
return <DetectingFace debug={props.debug} />
157156
}
158157
case MEAL_STATE.R_MovingToMouth: {
159158
/**
@@ -254,7 +253,6 @@ function Home(props) {
254253
}, [
255254
mealState,
256255
props.debug,
257-
props.webVideoServerURL,
258256
biteAcquisitionActionInput,
259257
moveAbovePlateActionInput,
260258
moveToMouthActionInput,
@@ -278,9 +276,7 @@ Home.propTypes = {
278276
* Whether to run it in debug mode (e.g., if you aren't simulatenously running
279277
* the robot) or not
280278
*/
281-
debug: PropTypes.bool,
282-
// The URL of the web video server
283-
webVideoServerURL: PropTypes.string.isRequired
279+
debug: PropTypes.bool
284280
}
285281

286282
export default Home

0 commit comments

Comments
 (0)