Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Got Camera Feed Working With Republisher #93

Merged
merged 5 commits into from
Nov 4, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Original file line number Diff line number Diff line change
Expand Up @@ -146,26 +146,33 @@ def publish_frames(self):
self.num_frames = 0
self.video.set(cv2.CAP_PROP_POS_FRAMES, self.num_frames)

# Publish the RGB Image message
# Configure the RGB Image message
frame_msg = self.bridge.cv2_to_imgmsg(frame, "bgr8")
frame_msg.header.frame_id = "camera_color_optical_frame"
frame_msg.header.stamp = self.get_clock().now().to_msg()
self.image_publisher.publish(frame_msg)

# Publish the RGB CompressedImage message
# Configure the RGB CompressedImage message
compressed_frame_msg = self.bridge.cv2_to_compressed_imgmsg(frame)
compressed_frame_msg.header.frame_id = "camera_color_optical_frame"
compressed_frame_msg.header.stamp = self.get_clock().now().to_msg()
self.compressed_image_publisher.publish(compressed_frame_msg)
compressed_frame_msg.format = (
"jpeg" # web_video_server requires "jpeg" not "jpg"
)

# Publish the depth Image message
# Configure the depth Image message
depth_frame_msg = self.bridge.cv2_to_imgmsg(self.depth_frame, "passthrough")
depth_frame_msg.header.frame_id = "camera_color_optical_frame"
depth_frame_msg.header.stamp = self.get_clock().now().to_msg()
self.aligned_depth_publisher.publish(depth_frame_msg)
depth_frame_msg.header.stamp = (
self.get_clock().now() - rclpy.duration.Duration(seconds=0.15)
).to_msg()

# Configure the Camera Info
self.camera_info_msg.header.stamp = depth_frame_msg.header.stamp

# Publish the Camera Info
self.camera_info_msg.header.stamp = compressed_frame_msg.header.stamp
# Publish all topics
self.image_publisher.publish(frame_msg)
self.compressed_image_publisher.publish(compressed_frame_msg)
self.aligned_depth_publisher.publish(depth_frame_msg)
self.camera_info_publisher.publish(self.camera_info_msg)

rate.sleep()
Expand Down
2 changes: 1 addition & 1 deletion feedingwebapp/src/Pages/Constants.js
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ NON_MOVING_STATES.add(MEAL_STATE.U_PostMeal)
export { NON_MOVING_STATES }

// The names of the ROS topic(s)
export const CAMERA_FEED_TOPIC = '/camera/color/image_raw'
export const CAMERA_FEED_TOPIC = '/local/camera/color/image_raw'
export const FACE_DETECTION_TOPIC = '/face_detection'
export const FACE_DETECTION_TOPIC_MSG = 'ada_feeding_msgs/FaceDetection'
export const FACE_DETECTION_IMG_TOPIC = '/face_detection_img'
Expand Down
4 changes: 2 additions & 2 deletions feedingwebapp/src/Pages/Home/Home.jsx
Original file line number Diff line number Diff line change
Expand Up @@ -152,7 +152,7 @@ function Home(props) {
*/
let currentMealState = MEAL_STATE.R_MovingFromMouthToAbovePlate
let nextMealState = MEAL_STATE.U_BiteSelection
let waitingText = 'Waiting to move above the plate...'
let waitingText = 'Waiting to move from your mouth to above the plate...'
return (
<RobotMotion
debug={props.debug}
Expand All @@ -166,7 +166,7 @@ function Home(props) {
case MEAL_STATE.R_MovingFromMouthToRestingPosition: {
let currentMealState = MEAL_STATE.R_MovingFromMouthToRestingPosition
let nextMealState = MEAL_STATE.U_BiteAcquisitionCheck
let waitingText = 'Waiting to move to the resting position...'
let waitingText = 'Waiting to move from your mouth to the resting position...'
return (
<RobotMotion
debug={props.debug}
Expand Down
47 changes: 6 additions & 41 deletions feedingwebapp/src/Pages/Home/MealStates/BiteSelection.jsx
Original file line number Diff line number Diff line change
Expand Up @@ -86,15 +86,6 @@ const BiteSelection = (props) => {
let { actionName, messageType } = ROS_ACTIONS_NAMES[MEAL_STATE.U_BiteSelection]
let segmentFromPointAction = useRef(createROSActionClient(ros.current, actionName, messageType))

/**
* Callback function for when the user indicates that they want to move the
* robot to locate the plate.
*/
const locatePlateClicked = useCallback(() => {
console.log('locatePlateClicked')
setMealState(MEAL_STATE.U_PlateLocator)
}, [setMealState])

/**
* Callback function for when the user indicates that they are done with their
* meal.
Expand Down Expand Up @@ -163,6 +154,7 @@ const BiteSelection = (props) => {
setActionStatus({
actionStatus: ROS_ACTION_STATUS_SUCCEED
})
console.log('Got result', response.values)
setActionResult(response.values)
} else {
if (
Expand Down Expand Up @@ -336,7 +328,7 @@ const BiteSelection = (props) => {
width: Math.round(REALSENSE_WIDTH * maskScaleFactor),
height: Math.round(REALSENSE_HEIGHT * maskScaleFactor)
}
let imgSrc = `${props.webVideoServerURL}/stream?topic=${CAMERA_FEED_TOPIC}&width=${imgSize.width}&height=${imgSize.height}&quality=20`
let imgSrc = `${props.webVideoServerURL}/stream?topic=${CAMERA_FEED_TOPIC}&width=${imgSize.width}&height=${imgSize.height}&type=ros_compressed`
return (
<View style={{ flexDirection: 'row', justifyContent: 'center', alignItems: 'center', width: '100%', height: '100%' }}>
{actionResult.detected_items.map((detected_item, i) => (
Expand Down Expand Up @@ -434,40 +426,14 @@ const BiteSelection = (props) => {
style={{
flex: 3,
flexDirection: 'row',
justifyContent: 'center',
alignItems: 'center',
width: '100%'
}}
>
<View
style={{
flex: 1,
alignItems: 'center',
justifyContent: 'right'
}}
>
<Button
className='doneButton'
style={{ fontSize: textFontSize, marginTop: '0', marginBottom: '0' }}
onClick={locatePlateClicked}
>
🍽️ Locate Plate
</Button>
</View>
<View
style={{
flex: 1,
alignItems: 'center',
justifyContent: 'left'
}}
>
<Button
className='doneButton'
style={{ fontSize: textFontSize, marginTop: '0', marginBottom: '0' }}
onClick={doneEatingClicked}
>
✅ Done Eating
</Button>
</View>
<Button className='doneButton' style={{ fontSize: textFontSize, marginTop: '0', marginBottom: '0' }} onClick={doneEatingClicked}>
✅ Done Eating
</Button>
</View>
{/**
* Below the buttons, one half of the screen will present the video feed.
Expand Down Expand Up @@ -598,7 +564,6 @@ const BiteSelection = (props) => {
</>
)
}, [
locatePlateClicked,
doneEatingClicked,
dimension,
margin,
Expand Down
2 changes: 1 addition & 1 deletion feedingwebapp/src/Pages/Home/VideoFeed.jsx
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ const VideoFeed = (props) => {
// Render the component
return (
<img
src={`${props.webVideoServerURL}/stream?topic=${CAMERA_FEED_TOPIC}&width=${imgWidth}&height=${imgHeight}&quality=20`}
src={`${props.webVideoServerURL}/stream?topic=${CAMERA_FEED_TOPIC}&width=${imgWidth}&height=${imgHeight}&type=ros_compressed`}
alt='Live video feed from the robot'
style={{
width: imgWidth,
Expand Down