Commit 58a74a63 authored by Larkin Heintzman's avatar Larkin Heintzman

images and shebang updates

parent e4f7ae05
...@@ -8,27 +8,22 @@ ...@@ -8,27 +8,22 @@
<!-- load machine names, plath, neruda, and home versions --> <!-- load machine names, plath, neruda, and home versions -->
<include file="$(find base_station)/launch/machines.launch"/> <include file="$(find base_station)/launch/machines.launch"/>
<node name="waypointGenerator" pkg="database_tools" type="waypointGenerator.py"> <!-- <node name="waypointGenerator" pkg="database_tools" type="waypointGenerator.py">
<!-- type of path, from "points" below, "spiral", or "squares" -->
<param name="pathType" type="string" value="spiral"/> <param name="pathType" type="string" value="spiral"/>
<param name="spiralRadius" type="double" value="1"/> <param name="spiralRadius" type="double" value="1"/>
<param name="spiralLoops" type="double" value="2"/> <param name="spiralLoops" type="double" value="2"/>
<param name="spiralHeight" type="double" value="1"/> <param name="spiralHeight" type="double" value="1"/>
<param name="altitudeIncrement" type="double" value="0"/> <param name="altitudeIncrement" type="double" value="0"/>
<!-- base altitude of all waypoints/position -->
<param name="altitude" type="double" value="2"/> <param name="altitude" type="double" value="2"/>
<!-- number of drones to generate waypoints for -->
<param name="droneNum" type="double" value="3"/> <param name="droneNum" type="double" value="3"/>
<rosparam command="load" param="anchorPoint"> <rosparam command="load" param="anchorPoint">
<!-- backyard center -->
[37.227531, -80.406156] [37.227531, -80.406156]
</rosparam> </rosparam>
<!-- nearby tree variation -->
<rosparam command="load" param="pathPoints"> <rosparam command="load" param="pathPoints">
[] []
</rosparam> </rosparam>
</node> </node> -->
<!-- launch neruda vehicle nodes --> <!-- launch neruda vehicle nodes -->
<include file="$(find base_station)/launch/remote_image_test.launch"> <include file="$(find base_station)/launch/remote_image_test.launch">
......
...@@ -7,7 +7,7 @@ ...@@ -7,7 +7,7 @@
<group ns="$(arg machine_name)"> <group ns="$(arg machine_name)">
<!-- run viewer on base station laptop --> <!-- run viewer on base station laptop -->
<node name="imageViewer" pkg="base_station" type="imageViewerNode.py"/> <node name="imageViewer" pkg="base_station" type="imageSaverNode.py"/>
<!-- run webcam stream on remote node --> <!-- run webcam stream on remote node -->
<!-- got to do this here because including a file to a remote machine is apparently frowned upon --> <!-- got to do this here because including a file to a remote machine is apparently frowned upon -->
......
#! /usr/bin/python3
# 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 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.imwrite("/home/$USER/camera_image.jpeg", iv.image)
cv2.waitKey(10)
# cv2.destroyAllWindows()
if __name__ == "__main__":
main()
#!/usr/bin/python3
import rospy
import cv2
# ROS Image message
from sensor_msgs.msg import Image
# ROS Image message -> OpenCV2 image converter
from cv_bridge import CvBridge, CvBridgeError
# OpenCV2 for saving an image
# Instantiate CvBridge
bridge = CvBridge()
def image_callback(msg):
try:
# Convert your ROS Image message to OpenCV2
cv2_img = bridge.imgmsg_to_cv2(msg, "bgr8")
rospy.loginfo("received new image.")
# Save your OpenCV2 image as a jpeg
cv2.imwrite('/home/llh/sarwebui/media/droneimages/camera_image.jpeg', cv2_img)
except CvBridgeError as e:
print(e)
def main():
rospy.init_node('image_handler')
# Define your image topic
if (rospy.get_param('camera_type') == 0):
image_topic = "dji_osdk_ros/fpv_camera_images"
else:
image_topic = "dji_osdk_ros/main_camera_images"
# Set up your subscriber and define its callback
rospy.Subscriber(image_topic, Image, image_callback)
# Spin until ctrl + c
rospy.loginfo("image handler ready for images...")
rospy.spin()
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