Commit 472d1126 authored by Larkin Heintzman's avatar Larkin Heintzman

image processing node tweaks

parent 96e6ee2d
......@@ -12,23 +12,23 @@ RUN curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | apt
RUN apt-get update && apt-get install -y ros-melodic-ros-base python3-catkin-tools ros-melodic-catkin
# copy over entrypoint
COPY ./ros_entrypoint.sh ros_entrypoint.sh
COPY ./ros_entrypoint.sh /ros_entrypoint.sh
# opencv install
RUN apt-get update && \
apt-get install -y opencv-data libopencv-dev
# prepare catkin_work space
RUN mkdir -p catkin_ws/src
RUN mkdir -p catkin_ws/src && mkdir -p /tmp/darknetMemories
# darknet ros package install
COPY ./yolov4-for-darknet_ros /catkin_ws/src/darknet_package
# build the enclosed darknet installation
# RUN cd /catkin_ws/src/darknet_ros/darknet && make
# install stuff for building ros packages
RUN apt-get install -y python-rosdep python-rosinstall python-rosinstall-generator python-wstool build-essential ros-melodic-cv-bridge ros-melodic-image-transport && rosdep init && rosdep update
# run catkin_make
# install random pip thing and run catkin_make
RUN apt-get install -y python-pip && pip install empy
RUN /bin/bash -c '. /opt/ros/melodic/setup.bash && cd catkin_ws && catkin_make'
RUN cd /catkin_ws/src/darknet_package/darknet_ros/darknet && make
......
subscribers:
camera_reading:
topic: /webcam/image_raw
topic: /dji_sdk/main_camera_images
queue_size: 1
actions:
......
......@@ -5,7 +5,9 @@
<!-- Use YOLOv4-tiny -->
<arg name="network_param_file" default="$(find darknet_ros)/config/yolov4-tiny.yaml"/>
<arg name="image" default="webcam/image_raw" />
<!-- Start image processing node -->
<node name="darknetImageProcessor" type="darknetImageProc.py" pkg="darknet_ros"/>
<!-- Include main launch file -->
<include file="$(find darknet_ros)/launch/darknet_ros.launch">
......
#! /usr/bin/python3
#! /usr/bin/python
import rospy, sys, math, cv2, numpy as np, std_msgs.msg
from sensor_msgs.msg import Image
from darknet_ros_msgs.msg import BoundingBox
from darknet_ros_msgs.msg import BoundingBoxes
from std_msgs.msg import Header
import os.path, getpass
from cv_bridge import CvBridge, CvBridgeError
......@@ -11,59 +11,46 @@ from cv_bridge import CvBridge, CvBridgeError
class ImageProcessor():
def __init__(self):
self.bridge = CvBridge()
self.imageSubscriber = rospy.Subscriber("webcam/image_raw", Image, self.imageCallback)
self.boxSubscriber = rospy.Subscriber("darknet_ros/bounding_boxes", BoundingBox, self.boxCallback)
self.imageSubscriber = rospy.Subscriber("/darknet_ros/detection_image", Image, self.imageCallback, queue_size=1)
self.boxSubscriber = rospy.Subscriber("/darknet_ros/bounding_boxes", BoundingBoxes, self.boxCallback, queue_size=1)
self.params = None
self.image = None
self.seq = None
self.newImageFlag = False
# stuff that needs to be parameters
self.objectsOfInterest = ["person", "backpack", "car"] # things we report
self.reportConfidence = 0.80 # confidence required for report
self.reportFrames = 10 # number of frames at high confidence before reporting
self.reportConfidence = 0.90 # confidence required for report
self.saveDirectory = "/tmp/darknetMemories/"
def boxCallback(self, box):
# check confidence levels and save image when sure of object
saveFlag = True
if saveFlag:
boxList = box.bounding_boxes
saveFlag = False
highPropObjects = ""
for box in boxList:
if (box.Class in self.objectsOfInterest and box.probability > self.reportConfidence and np.mod(self.seq, 5) == 0):
highPropObjects = highPropObjects + box.Class + "+"
saveFlag = True
if saveFlag and self.newImageFlag:
if os.path.isdir(self.saveDirectory):
cv2.imwrite(self.saveDirectory + "camera_image_{seq}.jpeg".format(seq = self.seq), self.image)
cv2.imwrite(self.saveDirectory + "camera_image_{seq}_{obj}.jpeg".format(seq = self.seq, obj = highPropObjects), self.image)
rospy.loginfo("saving image to folder: " + self.saveDirectory + "-> camera_image_{seq}.jpeg".format(seq = self.seq))
# cv2.waitKey(10)
self.newImageFlag = False
else:
rospy.loginfo("image save process failed!")
def imageCallback(self, frame):
self.newImageFlag = True
# load image from topic for later use
try:
self.image = self.bridge.imgmsg_to_cv2(frame, "bgr8")
self.seq = frame.header.seq
except CvBridgeError as err:
rospy.loginfo("there was error!")
rospy.loginfo(err)
self.image = self.bridge.imgmsg_to_cv2(frame, "bgr8")
self.seq = frame.header.seq
def main():
rospy.init_node("darknetImageProcessor")
iv = ImageProcessor()
rospy.spin()
# while not rospy.is_shutdown():
# if iv.image is not None:
# if np.mod(iv.seq, 32) == 0:
# directory = "/home/" + getpass.getuser() + "/" + folderName
# if os.path.isdir(directory):
# if windowFlag:
# cv2.imshow("image window", iv.image)
# rospy.loginfo("publishing image to window seq: " + iv.seq)
# if saveFlag:
# cv2.imwrite(directory + "/camera_image_{seq}.jpeg".format(seq = iv.seq), iv.image)
# rospy.loginfo("saving image to folder: " + directory + "-> camera_image_{seq}.jpeg".format(seq = iv.seq) + " seq: " + str(iv.seq))
# cv2.waitKey(10)
# else:
# rospy.loginfo("camera dir missing!")
# 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