Skip to content
Snippets Groups Projects
Commit 27d30933 authored by kpp55's avatar kpp55
Browse files

Added ros code

parent 4aca8a02
No related branches found
No related tags found
No related merge requests found
#!/usr/bin/python
import numpy as np
#import rospy
import rospy
import matplotlib.pyplot as plt
import cv2
width = 275
from imutils.video import WebcamVideoStream
from imutils.video import FPS
from std_msgs.msg import String
from std_msgs.msg import Float64
pub = rospy.Publisher('direction', String, queue_size=10)
pub1 = rospy.Publisher('lane_distance', Float64, queue_size=10)
rospy.init_node('lane_status')
rate = rospy.Rate(10) # 100hz
width = 325
# Converts picture to grayscale and applies filter to picture
# params
# pic : a numpy array of pixel values to represent a picture
......@@ -41,7 +48,7 @@ def ROI(pic):
roi = cv2.bitwise_and(pic, mask)
return roi
# Define the region of in which the lanes will be in the cameras view for the robot
# Define the region of in which the lanes will be in the cameras view
# params
# pic: original image to apply the pre-set region of interest too
def ROI_real(pic):
......@@ -86,32 +93,24 @@ def find_middle(leftPoints, rightPoints):
middle_lines = [[],[]]
if rightPoints[1] is None:
print("~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~Caught the empty right list~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~")
if leftPoints[1] == []:
print("~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~Caught the empty list~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~")
return 0
elif leftPoints[1] is None :
print("~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~Caught the empty left list~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~")
elif rightPoints[1] == []:
print("~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~Caught the empty list~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~")
return 0
else:
#print(leftPoints[1])
#print(rightPoints[1])
for x in range(150):
#print("Right x point: " + str(rightPoints[0][x]))
#print("Left x point: " + str(leftPoints[0][x]))
#print("Right Y point: " + str(rightPoints[1][x]))
#print("Left Y point: " + str(leftPoints[1][x]))
midPoint = (rightPoints[0][149-x] + leftPoints[0][x]) / 2
#print("midPoint X: " + str(midPoint))
#print("midPoint Y: " + str(leftPoints[1][x]))
middle_lines[1].append(leftPoints[1][x])
middle_lines[0].append(midPoint)
return middle_lines
# Find the two average lines given the set of lines
# params
# pic: the original image
......@@ -232,25 +231,25 @@ def detectDepartureNew(midPoints):
def myround(x):
return int(5 * round(float(x)/5))
def lane_status(lane_distance):
rospy.loginfo(lane_distance)
pub.publish(lane_distance)
rate.sleep()
video = cv2.VideoCapture("midTest.avi")
#video = cv2.VideoCapture("test2.mp4")
#video = cv2.VideoCapture("highway.mp4")
#video = cv2.VideoCapture(0)
video = WebcamVideoStream(src=1).start()
plt.ion()
while True:
ret, frame = video.read()
while not rospy.is_shutdown():
frame = video.read()
# gray = cv2.cvtColor(frame, cv2.COLOR_BGR2GRAY)
# frame = cv2.imread("../frame.jpeg")
frame_edge = detect_edge(frame)
if not ret:
video = cv2.VideoCapture(1)
continue
new_img = formatImg(frame)
......@@ -276,22 +275,25 @@ while True:
plt.scatter(Rpoints[0], Rpoints[1])
plt.scatter(Lpoints[0], Lpoints[1])
if(Mpoints != 0):
plt.scatter(Mpoints[0], Mpoints[1])
lane_distance = detectDepartureNew(Mpoints)
lane_status(lane_distance)
plt.scatter(300, 400)
else:
print("No midpoint calculated")
#plt.scatter(310, 300)
plt.imshow(frame, zorder=0)
#detectDeparture(Lpoints, 310, Rpoints)
detectDepartureNew(Mpoints)
plt.pause(.001)
lane = applyLines(frame, lines)
#lane = applyLines(frame, lines)
#cv2.imshow("edges", wEdges)
#cv2.imshow("cropped", cropped)
cv2.imshow("cropped", cropped)
#cv2.imshow("frame", lane)
key = cv2.waitKey(25)
......
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please to comment