Commit a0ec68de authored by Larkin Heintzman's avatar Larkin Heintzman

remote image launch file updates

parent 2e1b0948
......@@ -7,7 +7,11 @@
<group ns="$(arg machine_name)">
<!-- run viewer on base station laptop -->
<node name="imageViewer" pkg="base_station" type="imageSaverNode.py"/>
<node name="imageNode" pkg="base_station" type="imageNode.py">
<param name="visualize" type="bool" value="false"/>
<param name="save" type="bool" value="true"/>
<param name="folderName" type="string" value="/home/ssher/imageDump"/>
</node>
<!-- run webcam stream on remote node -->
<!-- got to do this here because including a file to a remote machine is apparently frowned upon -->
......
#! /usr/bin/python3
#! /home/llh/anaconda3/bin/python
# just saves the image instead of opening viewer window, for kubernetes node
import rospy, sys, math, cv2, numpy as np, std_msgs.msg
from sensor_msgs.msg import Image
from std_msgs.msg import Header
......@@ -29,8 +26,12 @@ class ImageViewer():
def main():
iv = ImageViewer()
rospy.init_node("imageSaver")
folderName = "/home/" + getpass.getuser() + "/imageDump"
# cv2.namedWindow("image window")
windowFlag = rospy.get_param("~visualize")
saveFlag = rospy.get_param("~save")
folderName = rospy.get_param("~folderName")
# folderName = "/home/" + getpass.getuser() + "/imageDump"
if windowFlag:
cv2.namedWindow("image window")
cv2.waitKey(200)
while not rospy.is_shutdown():
......@@ -39,8 +40,11 @@ def main():
if np.mod(iv.seq, 32) == 0:
if os.path.isdir(folderName):
# print ("File exist")
cv2.imwrite(folderName + "/camera_image_{seq}.jpeg".format(seq = iv.seq), iv.image)
cv2.waitKey(1000)
if windowFlag:
cv2.imshow("image window", iv.image)
if saveFlag:
cv2.imwrite(folderName + "/camera_image_{seq}.jpeg".format(seq = iv.seq), iv.image)
cv2.waitKey(10)
else:
print ("File not exist")
......
#! /home/llh/anaconda3/bin/python
# may need to change that shebang for jetson
import rospy, sys, math, cv2, numpy as np, std_msgs.msg
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
class ImageViewer():
def __init__(self):
self.bridge = CvBridge()
self.subscriber = rospy.Subscriber("usb_camera/image_raw", Image, self.imageCallback)
self.params = None
self.image = None
def imageCallback(self, frame):
# self.params = self.getParams()
try:
self.image = self.bridge.imgmsg_to_cv2(frame, "bgr8")
except CvBridgeError as err:
rospy.loginfo("there was error!")
rospy.loginfo(err)
def main():
iv = ImageViewer()
rospy.init_node("imageViewer")
cv2.namedWindow("image window")
cv2.waitKey(200)
while not rospy.is_shutdown():
if iv.image is not None:
cv2.imshow("image window", iv.image)
cv2.waitKey(10)
cv2.destroyAllWindows()
if __name__ == "__main__":
main()
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment