Difference between revisions of "2021SummerTeam4"
(28 intermediate revisions by the same user not shown) | |||
Line 40: | Line 40: | ||
= '''Overview''' = | = '''Overview''' = | ||
This wiki page includes the progression accomplished on the path to obtaining a self-driving car. This autonomous RC car was achieved by using DonkeyCar, OpenCV, and LiDAR. <br> | |||
The overall goal was to create a vehicle capable of mimicking behaviors, following guidelines, and avoiding obstacles all by itself. | |||
<br> | |||
[[ | |||
Different methods of achieving this autonomy resulted in several techniques being learned, as each method had its own path to the same result. <br> | |||
To focus more on the DonkeyCar, [https://guitar.ucsd.edu/maeece148/index.php/2021SummerTeam4#DonkeyCar_Autonomous_Racing '''Click Here''']. To focus more on the OpenCV, [https://guitar.ucsd.edu/maeece148/index.php/2021SummerTeam4#OpenCV_Autonomous_Racing '''Click Here''']. Finally, to focus more on the LiDAR and the original code used to drive autonomously while avoiding obstacles, [https://guitar.ucsd.edu/maeece148/index.php/2021SummerTeam4#Final_Project:_Obstacle_Avoidance_Using_LIDAR '''Click Here''']. | |||
<br> | <br> | ||
<gallery widths=600px heights=600px mode="nolines"> | |||
File:OV.jpg|Mission | |||
</gallery> | |||
<br> | <br> | ||
='''Mechanical Design'''= | ='''Mechanical Design'''= | ||
== Mount Plate == | == Mount Plate == | ||
30mm (3cm) interval for hardware mounts on top; circuit components were velcroed under the plate. | |||
<br> | |||
[[File:MP.PNG|500px]] | [[File:MP.PNG|500px]] | ||
== Camera Mount == | == Camera Mount == | ||
The disadvantage of an adjustable camera mount is that it is structurally weak, prone to impact. Once we determined | The disadvantage of an adjustable camera mount is that it is structurally weak, prone to impact. Once we determined the optimal height and angle (would you always want larger FOV? Longer range?), | ||
<br> | <br> | ||
we designed a sturdy, protective camera mount at a fixed orientation, held in place with several components - frontal casing, rear casing, and a support - and fastened to each other with bolts and nuts. | we designed a sturdy, protective camera mount at a fixed orientation, held in place with several components - frontal casing, rear casing, and a support - and fastened to each other with bolts and nuts. | ||
Line 87: | Line 70: | ||
<gallery widths=500px heights=500px mode="nolines"> | <gallery widths=500px heights=500px mode="nolines"> | ||
File:CM_1.PNG| | File:CM_1.PNG|Config 1 | ||
File:CM_2.PNG | File:CM_2.PNG|Config 2 | ||
</gallery> | </gallery> | ||
<gallery widths=1000px heights=800px mode="nolines"> | <gallery widths=1000px heights=800px mode="nolines"> | ||
File:CM_D.PNG| | File:CM_D.PNG|Drawing | ||
</gallery> | </gallery> | ||
Line 103: | Line 86: | ||
Since the 'guts' of our car are essentially encapsulated under the plate, it would be cumbersome to disassemble the plate for every maintenance. | Since the 'guts' of our car are essentially encapsulated under the plate, it would be cumbersome to disassemble the plate for every maintenance. | ||
<br> | <br> | ||
Therefore, we employed a hinge system, enabling quick and convenient 'surgery' while also ensuring the most secure protection. | Therefore, we employed a hinge system, enabling quick and convenient 'surgery' while also ensuring the most secure protection. ( Inspired by [https://guitar.ucsd.edu/maeece148/index.php/2020FallTeam3#Hardware Dominic Nightingale] ) | ||
<br> | <br> | ||
Indeed, we benefited from this mechanism more than we had initially thought, as our calibration procedures frequented the need for battery replacements, rewiring, and rearrangements. | Indeed, we benefited from this mechanism more than we had initially thought, as our calibration procedures frequented the need for battery replacements, rewiring, and rearrangements. | ||
<gallery widths=500px heights=500px mode="nolines"> | <gallery widths=500px heights=500px mode="nolines"> | ||
File:HingewTop.JPG| | File:HingewTop.JPG|Hinge with Top | ||
File:Resrr.JPG| | File:Resrr.JPG|Stand | ||
</gallery> | </gallery> | ||
== Hood Bumper== | == Hood Bumper== | ||
This is obviously for aesthetic purpose :) | |||
<br> | |||
[[File:FB.PNG|600px]] | [[File:FB.PNG|600px]] | ||
Line 125: | Line 110: | ||
But let's be honest - it's mostly for the show..! | But let's be honest - it's mostly for the show..! | ||
== | == LiDAR Housing == | ||
The LiDAR must be placed above all other components in order to be able to scan the environment without a blindspot. | |||
<br> | |||
A simple housing supported by M3 stands over the Jetson satisfies this design condition. | |||
<br> | |||
Refer to phase 3 of the vehicle's history to find out what the assembly looks like. | |||
<br> | |||
[[File:LA.PNG|600px]] | [[File:LA.PNG|600px]] | ||
Revision as of 07:15, 8 September 2021
Meet the Misfits - Team 4
From Left to Right: Felipe Ramos - Mechanical Engineering | Esther Grossman - Electrical & Computer Engineering | Paul Bae - Aerospace Engineering
Overview
This wiki page includes the progression accomplished on the path to obtaining a self-driving car. This autonomous RC car was achieved by using DonkeyCar, OpenCV, and LiDAR.
The overall goal was to create a vehicle capable of mimicking behaviors, following guidelines, and avoiding obstacles all by itself.
Different methods of achieving this autonomy resulted in several techniques being learned, as each method had its own path to the same result.
To focus more on the DonkeyCar, Click Here. To focus more on the OpenCV, Click Here. Finally, to focus more on the LiDAR and the original code used to drive autonomously while avoiding obstacles, Click Here.
Mechanical Design
Mount Plate
30mm (3cm) interval for hardware mounts on top; circuit components were velcroed under the plate.
Camera Mount
The disadvantage of an adjustable camera mount is that it is structurally weak, prone to impact. Once we determined the optimal height and angle (would you always want larger FOV? Longer range?),
we designed a sturdy, protective camera mount at a fixed orientation, held in place with several components - frontal casing, rear casing, and a support - and fastened to each other with bolts and nuts.
Tilt angle = 12 deg (config 1), 8 deg (config 2).
Jetson Nano Case
Bolt hinges are added to the base design by ecoiras: https://www.thingiverse.com/thing:3603594
Chassis Hinge
Since the 'guts' of our car are essentially encapsulated under the plate, it would be cumbersome to disassemble the plate for every maintenance.
Therefore, we employed a hinge system, enabling quick and convenient 'surgery' while also ensuring the most secure protection. ( Inspired by Dominic Nightingale )
Indeed, we benefited from this mechanism more than we had initially thought, as our calibration procedures frequented the need for battery replacements, rewiring, and rearrangements.
Hood Bumper
This is obviously for aesthetic purpose :)
Spoiler
A spoiler will generally create more drag at intermediate speeds; it begins to benefit the vehicle at high speeds, when things go out of control.
To generate a downforce, an inverted airfoil is used as the cross-sectional profile.
But let's be honest - it's mostly for the show..!
LiDAR Housing
The LiDAR must be placed above all other components in order to be able to scan the environment without a blindspot.
A simple housing supported by M3 stands over the Jetson satisfies this design condition.
Refer to phase 3 of the vehicle's history to find out what the assembly looks like.
Evolution
Phase 1
Phase 2
Phase 3
Circuit Design
DonkeyCar Autonomous Racing
The footage found here for the autonomous three laps using Donkey Car used a deep learning model in which data sets with different purposes were used together to get this working set. The foundation of this model used data that only focused on following the yellow line. This meant that the racing line wasn’t always necessarily smooth. With this in mind, this is where the other sets of data came into play. By mixing in data in which the racing line was prioritized, the model learned to take a path that focused on stability, all while following the yellow line.
{{#evu:https://www.youtube.com/watch?v=aVhgmDBfa-E?rel=0
|center
}}
OpenCV Autonomous Racing
The objective of our next autonomous racing model was to perform laps around the same track using python OpenCV segmentation. The process was run using ROS Noetic on a docker container created by Dominic.
We first isolated the white lanes of the track, with the intention of doing lane guidance by following the center of all the white lines isolated in the images. We additionally included the dashed yellow center line, which was not a problem since it falls in the center of the track and therefore provided additional guidance data. The algorithm identified the white and yellow contours within a pre-sized field of vision. Then, it drew bounding boxes around the contours and removed boxes below a designated width in order to reduce noise. The centroid of each box was found and its horizontal distance from the center of the car's field of vision was calculated. If the average of the boxes' distances was more than a preset error threshold, the car would assume it is turning and reduce its throttle. When it was within the error_threshold, it would increase its throttle. The steering value was taken as a linear function of the average distance from center.
Isolating white and yellow lines produced too much noise that steered the car off route. We decided to isolate only the yellow center line of the track. This produced a more reliable model. Of course, if the car steered off the track and could no longer see yellow lines, it had little hope of returning to the track, but this was not a frequent problem.
The final issue encountered was the recognition of cones. The car could often not distinguish between the yellow center line and the orange cones, leading it to steer toward the cones in a head-on collision. We added a layer of pre-processing in openCV to remove the orange cones and replace them with black pixels. This led the car to avoid all but one cone, whose pixels were not entirely erased in pre-processing due to its color shading. Nonetheless, a little tweaking of the yellow center line segmentation resulted in good success (balancing the stringency of the criteria to be considered yellow and the need to detect an adequate number of yellow lines).
{{#evu:https://www.youtube.com/watch?v=1kJeqHcrquc?rel=0
|center|
}}
Final Project: Obstacle Avoidance Using LIDAR
For our final project, we experimented with a 360 degree RPlidar. Dominic's same ROS framework was used in a virtual environment running ROS Melodic. The lidar was positioned atop our car, unobstructed by any of the car's mechanical components. The lidar read from a 2D plane parallel to and slightly less than a foot off the ground. This meant that in order to recognize an object, the objects needed to be at least at the height of the lidar. Therefore, we constructed a racetrack from folded chairs, tables, race track guides, and tin foil.
Our car used an algorithm loosely based on artificial potential methods for path planning and control. This control algorithm was added as a ROS node, subscribed to the laser's 'scan' topic. After reading in range data, the lidar isolates readings from approximately 30 degrees to 150 degrees in front of it, as we assume the car only applys forward throttle and therefore avoiding obstacles behind the car is not a concern. Zero degrees maps to completely left of the car and 180 degrees maps to completely right of the car. Within the isolated readings, the closest obstacle is found. If within a given distance threshold, the car enters obstacle avoidance mode and slows the throttle. The new steering direction is in the direction of the vector that is perpendicular to the vector connecting the car and the closest object point. This way the car is always steered parallel to an obstacle's surface. It will continue to follow the surface of the obstacle until it falls out of range of the distance threshold or until it reaches another, closer obstacle. The steering value is an exponential function that can be fine tuned for the speeds your robot is using. It overcorrects (gives high steering values) when the car is very close to the obstacle, and undercorrects (turns slowly) when further from the obstacle but still within the distance threshold for obstacle avoidance. After fine tuning the steering and distance threshold parameters, the algorithm performed well on our race track.
Hector slam was installed in order to localize the car's position and map the room. Using only range information and no other form of odometry, hector slam uses probabilistic mapping to identify the robot's position and construct an occupancy map. The occupancy map for our race track is shown in the video below and was constructed using a single lap around the track. With the tight turns and occasional fast speeds of our car, the hector mapping lost accuracy if run for more than a couple laps.
{{#evu:https://www.youtube.com/watch?v=pJxKa6_FetI?rel=0 |center| }}
obstacle_avoidance_node.py
#!/usr/bin/env python # This program implements a path planner and PID controller loosely based on artificial potential field methods import rospy from std_msgs.msg import Float32, Int32, Int32MultiArray from sensor_msgs.msg import LaserScan import numpy as np from numpy import pi from adafruit_servokit import ServoKit OBSTACLE_DETECTION_NODE_NAME = 'obstacle_detection_node' STEERING_TOPIC_NAME = '/steering' THROTTLE_TOPIC_NAME = '/throttle' CENTROID_TOPIC_NAME = '/centroid' SCAN_TOPIC_NAME = '/scan' kit = ServoKit(channels =16) class PathPlanner: def __init__(self): # Initialize node and create publishers/subscribers self.init_node = rospy.init_node(OBSTACLE_DETECTION_NODE_NAME, anonymous=False) self.steering_publisher = rospy.Publisher(STEERING_TOPIC_NAME, Float32, queue_size=1) self.throttle_publisher = rospy.Publisher(THROTTLE_TOPIC_NAME, Float32, queue_size=1) self.steering_float = Float32() self.throttle_float = Float32() self.scan_subscriber = rospy.Subscriber(SCAN_TOPIC_NAME, LaserScan, self.controller) # Calibrate these parameters self.error_threshold = 5 #degrees self.maxSteerL = 40 #degrees self.maxSteerR = 145 #degrees self.SteerC = 90 #degrees self.zero_throttle = 0.0 self.fast_throttle = 0.15 self.slow_throttle = 0.145 self.max_obstacle_influence = 1.5 #meters # # Display Parameters rospy.loginfo( f'\nno_error_throttle: {self.fast_throttle}' f'\nnerror_throttle: {self.slow_throttle}') def controller(self, scandata): #Facing forward is 0 radians for RPlidar. Remap range to 0 is left and 180 is right. left_angle = -pi/3; right_angle = pi/3 first_half_ranges = scandata.ranges[int(left_angle/scandata.angle_increment):] second_half_ranges = scandata.ranges[:int(right_angle/scandata.angle_increment)] forward_ranges = np.concatenate((first_half_ranges,second_half_ranges)) range_min = np.amin(forward_ranges) range_min_index = np.argmin(forward_ranges) range_min_angle = (range_min_index * scandata.angle_increment * 180/pi)+30 wheel_angle = kit.servo[1].angle rospy.logerr(wheel_angle) #Display wheel_angle each iteration #Determine if obstacle is worth avoiding, then determine if it is on then #left or right of the robots field of vision. Ajust steering to go parallel #to any obstacles if range_min <= self.max_obstacle_influence: throttle_float = self.slow_throttle kp = 1.5*np.exp(-range_min) #steering sensitivity if range_min_angle < 90: steer_angle = 90 + range_min_angle #angle perp to obstacle surface obstacle_wheel_diff = wheel_angle - steer_angle if obstacle_wheel_diff < 0 : wheel_angle = wheel_angle + kp*abs(obstacle_wheel_diff) else: wheel_angle = wheel_angle - kp*abs(obstacle_wheel_diff) else: steer_angle = -90 + range_min_angle #angle perp to obstacle surface obstacle_wheel_diff = wheel_angle - steer_angle if obstacle_wheel_diff > 0 : wheel_angle = wheel_angle - kp*abs(obstacle_wheel_diff) else : wheel_angle = wheel_angle + kp*abs(obstacle_wheel_diff) else: throttle_float = self.fast_throttle #Send out the normalized steering instructions if wheel_angle > self.maxSteerR: wheel_angle = self.maxSteerR elif wheel_angle < self.maxSteerL: wheel_angle = self.maxSteerL steering_float = - (wheel_angle/90 - 1) self.steering_float.data = steering_float self.throttle_float.data = throttle_float self.steering_publisher.publish(self.steering_float) self.throttle_publisher.publish(self.throttle_float) rospy.on_shutdown(self.clean_shutdown) def clean_shutdown(self): print("Shutting Down...") self.throttle_float.data = self.zero_throttle self.throttle_publisher.publish(self.throttle_float) print("Shut down complete") def main(): path_planner = PathPlanner() rate = rospy.Rate(15) while not rospy.is_shutdown(): rospy.spin() rate.sleep() if __name__ == '__main__': main()